initial commit

This commit is contained in:
Alexander Kurmis
2022-02-20 19:18:20 +03:00
commit e226faa454
88 changed files with 86787 additions and 0 deletions

159
Core/Src/board_logic.c Normal file
View File

@@ -0,0 +1,159 @@
/*
* board_logic.c
*
*/
#include <stdint.h>
#include <stdio.h>
#include "main.h"
#include "modbus_logic.h"
#include "board_logic.h"
#define BOARD_DESC_LEN (23)
static const char board_description[BOARD_DESC_LEN] = "RS485 Relay Module v1";
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_OFF HAL_GPIO_WritePin(RL_MAIN_GPIO_Port, RL_MAIN_Pin, GPIO_PIN_RESET)
#define REL_AUX_ON HAL_GPIO_WritePin(RL_AUX_GPIO_Port, RL_AUX_Pin, GPIO_PIN_SET)
#define REL_AUX_OFF HAL_GPIO_WritePin(RL_AUX_GPIO_Port, RL_AUX_Pin, GPIO_PIN_RESET)
#define LED_MAIN_ON HAL_GPIO_WritePin(LED_MAIN_GPIO_Port, LED_MAIN_Pin, GPIO_PIN_SET)
#define LED_MAIN_OFF HAL_GPIO_WritePin(LED_MAIN_GPIO_Port, LED_MAIN_Pin, GPIO_PIN_RESET)
#define LED_AUX_ON HAL_GPIO_WritePin(LED_AUX_GPIO_Port, LED_AUX_Pin, GPIO_PIN_SET)
#define LED_AUX_OFF HAL_GPIO_WritePin(LED_AUX_GPIO_Port, LED_AUX_Pin, GPIO_PIN_RESET)
#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)
uint16_t relays=0;
uint16_t motor_pwm=0;
uint16_t led_time_act=0;
void update_service_indication(void);
void loop_iterate()
{
if(relays&REL_MAIN_BIT)
{
REL_MAIN_ON;
LED_MAIN_ON;
}
else
{
REL_MAIN_OFF;
LED_MAIN_OFF;
}
if(relays&REL_AUX_BIT)
{
REL_AUX_ON;
LED_AUX_ON;
}
else
{
REL_AUX_OFF;
LED_AUX_OFF;
}
/*
if(motor_pwm>MOTOR_MAX)motor_pwm=MOTOR_MAX;
if(motor_pwm<MOTOR_MIN)motor_pwm=MOTOR_MIN;
if(motor_pwm==0)
//TCCR1A&=~(1<<COM1B1);
else
{
//MOTOR_PWM = motor_pwm;
//TCCR1A|=(1<<COM1B1);
}
*/
modbus_loop_iterate();
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)
{
if(led_time_act)
{
LED_ACT_ON;
led_time_act--;
}
else
LED_ACT_OFF;
/*
if(led_time_g)
{
LED_G_ON;
led_time_g--;
}
else
LED_G_OFF;
*/
}
uint8_t read_register(uint16_t address, uint16_t* value)
{
if (address == 0x0001)
*value = MODBUS_PROTOCOL_VERSION;
else if (address == 0x0002)
*value = MODBUS_FIRMWARE_VERSION;
else if (address == 0x0003)
*value = MODBUS_BOARD_TYPE;
else if (address == 0x0004)
*value = tranfer_errors_count;
else if (address == 0x0005)
*value = 0; // supported data rate: unknown
else if (address >= 0x0010 && address <= 0x0099)
{
int index = address - 0x0010;
if (index < BOARD_DESC_LEN)
*value = board_description[index];
else
*value = 0;
}
else if (address == 0x2001) //Read relays state
{
*value = relays;
}
else if (address == 0x2002) //Read motor pwm
{
*value = motor_pwm;
}
else
return 1;
return 0;
}
uint8_t write_register(uint16_t address, uint16_t value)
{
uint8_t ret;
ret=0;
#ifdef UART_DEBUG
printf("Write A=0x%X D=0x%X\n\r",address,value);
#endif
switch (address)
{
case 0x2001: relays = value; break;
case 0x2002: motor_pwm = value; break;
default: ret = 1;
}
return ret;
}

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

@@ -0,0 +1,370 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file : main.c
* @brief : Main program body
******************************************************************************
* @attention
*
* Copyright (c) 2022 STMicroelectronics.
* All rights reserved.
*
* This software is licensed under terms that can be found in the LICENSE file
* in the root directory of this software component.
* If no LICENSE file comes with this software, it is provided AS-IS.
*
******************************************************************************
*/
/* USER CODE END Header */
/* Includes ------------------------------------------------------------------*/
#include "main.h"
/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
#include "string.h"
#include "stdio.h"
#include "modbus_logic.h"
#include "board_logic.h"
/* USER CODE END Includes */
/* Private typedef -----------------------------------------------------------*/
/* USER CODE BEGIN PTD */
/* USER CODE END PTD */
/* Private define ------------------------------------------------------------*/
/* USER CODE BEGIN PD */
/* USER CODE END PD */
/* Private macro -------------------------------------------------------------*/
/* USER CODE BEGIN PM */
/* USER CODE END PM */
/* Private variables ---------------------------------------------------------*/
TIM_HandleTypeDef htim1;
TIM_HandleTypeDef htim3;
UART_HandleTypeDef huart1;
/* USER CODE BEGIN PV */
/* USER CODE END PV */
/* Private function prototypes -----------------------------------------------*/
void SystemClock_Config(void);
static void MX_GPIO_Init(void);
static void MX_TIM3_Init(void);
static void MX_USART1_UART_Init(void);
static void MX_TIM1_Init(void);
/* USER CODE BEGIN PFP */
/* USER CODE END PFP */
/* Private user code ---------------------------------------------------------*/
/* USER CODE BEGIN 0 */
/* USER CODE END 0 */
/**
* @brief The application entry point.
* @retval int
*/
int main(void)
{
/* USER CODE BEGIN 1 */
/* USER CODE END 1 */
/* MCU Configuration--------------------------------------------------------*/
/* Reset of all peripherals, Initializes the Flash interface and the Systick. */
HAL_Init();
/* USER CODE BEGIN Init */
/* USER CODE END Init */
/* Configure the system clock */
SystemClock_Config();
/* USER CODE BEGIN SysInit */
/* USER CODE END SysInit */
/* Initialize all configured peripherals */
MX_GPIO_Init();
MX_TIM3_Init();
MX_USART1_UART_Init();
MX_TIM1_Init();
/* USER CODE BEGIN 2 */
__HAL_UART_ENABLE_IT(&huart1, UART_IT_RXNE); // включить прерывания usart'a
HAL_TIM_Base_Start_IT(&htim1);
/* USER CODE END 2 */
/* Infinite loop */
/* USER CODE BEGIN WHILE */
while (1)
{
/* USER CODE END WHILE */
/* USER CODE BEGIN 3 */
loop_iterate();
}
/* USER CODE END 3 */
}
/**
* @brief System Clock Configuration
* @retval None
*/
void SystemClock_Config(void)
{
RCC_OscInitTypeDef RCC_OscInitStruct = {0};
RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};
RCC_PeriphCLKInitTypeDef PeriphClkInit = {0};
/** Initializes the RCC Oscillators according to the specified parameters
* in the RCC_OscInitTypeDef structure.
*/
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
RCC_OscInitStruct.HSEState = RCC_HSE_ON;
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
RCC_OscInitStruct.PLL.PLLMUL = RCC_PLL_MUL6;
RCC_OscInitStruct.PLL.PREDIV = RCC_PREDIV_DIV1;
if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK)
{
Error_Handler();
}
/** Initializes the CPU, AHB and APB buses clocks
*/
RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK
|RCC_CLOCKTYPE_PCLK1;
RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1;
if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_1) != HAL_OK)
{
Error_Handler();
}
PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USART1;
PeriphClkInit.Usart1ClockSelection = RCC_USART1CLKSOURCE_PCLK1;
if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK)
{
Error_Handler();
}
}
/**
* @brief TIM1 Initialization Function
* @param None
* @retval None
*/
static void MX_TIM1_Init(void)
{
/* USER CODE BEGIN TIM1_Init 0 */
/* USER CODE END TIM1_Init 0 */
TIM_ClockConfigTypeDef sClockSourceConfig = {0};
TIM_MasterConfigTypeDef sMasterConfig = {0};
/* USER CODE BEGIN TIM1_Init 1 */
/* USER CODE END TIM1_Init 1 */
htim1.Instance = TIM1;
htim1.Init.Prescaler = 479;
htim1.Init.CounterMode = TIM_COUNTERMODE_UP;
htim1.Init.Period = 100;
htim1.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
htim1.Init.RepetitionCounter = 0;
htim1.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
if (HAL_TIM_Base_Init(&htim1) != HAL_OK)
{
Error_Handler();
}
sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL;
if (HAL_TIM_ConfigClockSource(&htim1, &sClockSourceConfig) != HAL_OK)
{
Error_Handler();
}
sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
if (HAL_TIMEx_MasterConfigSynchronization(&htim1, &sMasterConfig) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN TIM1_Init 2 */
/* USER CODE END TIM1_Init 2 */
}
/**
* @brief TIM3 Initialization Function
* @param None
* @retval None
*/
static void MX_TIM3_Init(void)
{
/* USER CODE BEGIN TIM3_Init 0 */
/* USER CODE END TIM3_Init 0 */
TIM_MasterConfigTypeDef sMasterConfig = {0};
TIM_OC_InitTypeDef sConfigOC = {0};
/* USER CODE BEGIN TIM3_Init 1 */
/* USER CODE END TIM3_Init 1 */
htim3.Instance = TIM3;
htim3.Init.Prescaler = 239;
htim3.Init.CounterMode = TIM_COUNTERMODE_UP;
htim3.Init.Period = 256;
htim3.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
htim3.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
if (HAL_TIM_PWM_Init(&htim3) != HAL_OK)
{
Error_Handler();
}
sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
if (HAL_TIMEx_MasterConfigSynchronization(&htim3, &sMasterConfig) != 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(&htim3, &sConfigOC, TIM_CHANNEL_1) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN TIM3_Init 2 */
/* USER CODE END TIM3_Init 2 */
HAL_TIM_MspPostInit(&htim3);
}
/**
* @brief USART1 Initialization Function
* @param None
* @retval None
*/
static void MX_USART1_UART_Init(void)
{
/* USER CODE BEGIN USART1_Init 0 */
/* USER CODE END USART1_Init 0 */
/* USER CODE BEGIN USART1_Init 1 */
/* USER CODE END USART1_Init 1 */
huart1.Instance = USART1;
huart1.Init.BaudRate = 9600;
huart1.Init.WordLength = UART_WORDLENGTH_8B;
huart1.Init.StopBits = UART_STOPBITS_1;
huart1.Init.Parity = UART_PARITY_NONE;
huart1.Init.Mode = UART_MODE_TX_RX;
huart1.Init.HwFlowCtl = UART_HWCONTROL_NONE;
huart1.Init.OverSampling = UART_OVERSAMPLING_16;
huart1.Init.OneBitSampling = UART_ONE_BIT_SAMPLE_DISABLE;
huart1.AdvancedInit.AdvFeatureInit = UART_ADVFEATURE_NO_INIT;
if (HAL_UART_Init(&huart1) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN USART1_Init 2 */
/* USER CODE END USART1_Init 2 */
}
/**
* @brief GPIO Initialization Function
* @param None
* @retval None
*/
static void MX_GPIO_Init(void)
{
GPIO_InitTypeDef GPIO_InitStruct = {0};
/* GPIO Ports Clock Enable */
__HAL_RCC_GPIOF_CLK_ENABLE();
__HAL_RCC_GPIOA_CLK_ENABLE();
__HAL_RCC_GPIOB_CLK_ENABLE();
/*Configure GPIO pin Output Level */
HAL_GPIO_WritePin(GPIOA, LED_AUX_Pin|LED_MAIN_Pin|TXEN_Pin|RL_AUX_Pin, GPIO_PIN_RESET);
/*Configure GPIO pin Output Level */
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 */
GPIO_InitStruct.Pin = LED_AUX_Pin|LED_MAIN_Pin|TXEN_Pin|RL_AUX_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
/*Configure GPIO pins : LED_ERR_Pin LED_ACT_Pin RL_MAIN_Pin */
GPIO_InitStruct.Pin = LED_ERR_Pin|LED_ACT_Pin|RL_MAIN_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
}
/* 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 */
/**
* @brief This function is executed in case of error occurrence.
* @retval None
*/
void Error_Handler(void)
{
/* USER CODE BEGIN Error_Handler_Debug */
/* User can add his own implementation to report the HAL error return state */
__disable_irq();
while (1)
{
}
/* USER CODE END Error_Handler_Debug */
}
#ifdef USE_FULL_ASSERT
/**
* @brief Reports the name of the source file and the source line number
* where the assert_param error has occurred.
* @param file: pointer to the source file name
* @param line: assert_param error line source number
* @retval None
*/
void assert_failed(uint8_t *file, uint32_t line)
{
/* USER CODE BEGIN 6 */
/* User can add his own implementation to report the file name and line number,
ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
/* USER CODE END 6 */
}
#endif /* USE_FULL_ASSERT */

271
Core/Src/modbus_logic.c Normal file
View File

@@ -0,0 +1,271 @@
/*
* modbus_logic.c
*
* Created on: 11 <20><><EFBFBD>. 2019 <20>.
*/
#include <stdint.h>
#include "main.h"
#include "uart.h"
#include "modbus_logic.h"
volatile uint8_t recv_buffer[BUFFERS_SIZE];
volatile uint8_t send_buffer[BUFFERS_SIZE];
uint16_t bytes_to_send = 0;
uint16_t last_rx_time = 0xFFFF;
enum recv_state cmd_receiving = RECV_IDLE;
enum send_state cmd_sending = SEND_IDLE;
uint16_t tranfer_errors_count;
extern uint16_t led_time_act;
static void process_incoming_packet();
void UART_RxCpltCallback(void)
{
uint16_t pdu_size;
uint16_t remaining_size;
if (cmd_receiving == RECV_READ_HEADER)
{
// Check destination address
if (recv_buffer[5] != BOARD_ADRESS)
{
cmd_receiving = RECV_ERROR;
return;
}
// Check function code
if (recv_buffer[6] == 3 || recv_buffer[6] == 4 || recv_buffer[6] == 6)
{
cmd_receiving = RECV_READ_COMPLETE;
return;
}
else if (recv_buffer[6] == 0x10)
{
cmd_receiving = RECV_READ_DATA;
pdu_size = *((uint16_t*)(recv_buffer + 2));
// Receive remaining PDU and checksum
remaining_size = pdu_size - (MODBUS_HEADER_SIZE - 4) + 2;
if (remaining_size + MODBUS_HEADER_SIZE <= BUFFERS_SIZE)
UART_Receive_IT(recv_buffer + MODBUS_HEADER_SIZE, remaining_size, 5000);
else
tranfer_errors_count++;
return;
}
else
{
tranfer_errors_count++;
cmd_receiving = RECV_ERROR;
return;
}
}
else if (cmd_receiving == RECV_READ_DATA)
{
cmd_receiving = RECV_READ_COMPLETE;
}
}
void UART_TxCpltCallback()
{
cmd_sending = SEND_IDLE;
}
void modbus_loop_iterate()
{
if (cmd_sending == SEND_IDLE)
{
if (cmd_receiving == RECV_ERROR)
{
//delay_ms(30); // poor man's way to synchronize packets
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)
{
cmd_receiving = RECV_READ_HEADER;
UART_Receive_IT(recv_buffer, MODBUS_HEADER_SIZE, 5000);
}
else if (cmd_receiving == RECV_READ_COMPLETE)
{
process_incoming_packet();
cmd_receiving = RECV_IDLE;
}
}
else if (cmd_sending == SEND_BUSY && bytes_to_send != 0)
{
UART_Transmit_IT(send_buffer, bytes_to_send, 1000);
bytes_to_send = 0;
}
}
static uint16_t checksum(int size)
{
uint16_t index;
uint16_t checksum = 0;
for (index = 0; index < size; index++)
checksum += send_buffer[index];
return checksum;
}
void process_incoming_packet()
{
uint8_t source;
uint8_t dest;
uint8_t func_code;
uint16_t checksum_recv;
uint16_t transaction_id;
uint16_t pdu_size;
uint16_t checksum_real;
uint16_t response_pdu_length;
uint16_t address;
uint8_t write_result;
uint16_t size;
uint16_t i;
led_time_act=100;
dest = recv_buffer[5];
if(dest!=BOARD_ADRESS)return;
transaction_id = *((uint16_t*)(recv_buffer));
pdu_size = *((uint16_t*)(recv_buffer + 2));
if (pdu_size + 6 > BUFFERS_SIZE)
{
tranfer_errors_count++;
return;
}
source = recv_buffer[4];
func_code = recv_buffer[6];
//checksum_recv = *((uint16_t*)(recv_buffer + 4 + pdu_size));
checksum_recv = recv_buffer[4 + pdu_size];
checksum_recv += ((uint16_t)recv_buffer[5 + pdu_size])<<8;
checksum_real = 0;
for (i = 0; i < 4 + pdu_size; i++)
checksum_real += recv_buffer[i];
if (checksum_recv != checksum_real)
{
tranfer_errors_count++;
return;
}
// Prepare response header
*(uint16_t*)(send_buffer) = transaction_id;
send_buffer[4] = BOARD_ADRESS;
send_buffer[5] = source;
response_pdu_length = 0;
if ((func_code == 3 || func_code == 4) && pdu_size == 7) // Read holding/input registers
{
uint16_t start_address = *((uint16_t*)(recv_buffer + 7));
uint16_t quantity = *((uint16_t*)(recv_buffer + 9));
if (quantity > MAX_REGS_PER_QUERY)
{
tranfer_errors_count++;
return;
}
response_pdu_length = 2 * quantity + 1 + 3;
send_buffer[6] = func_code;
send_buffer[7] = 0; // bytes counter
for (address = start_address; address < start_address + quantity; address++)
{
uint16_t value;
uint8_t read_result = read_register(address, &value);
if (read_result != 0)
{
send_buffer[6] = func_code + 0x80;
send_buffer[7] = read_result;
response_pdu_length = 4;
break;
}
send_buffer[7] += 2;
*((uint16_t*)(&(send_buffer[8 + 2 * (address - start_address)]))) = value;
}
}
else if (func_code == 6 && pdu_size == 7) // Write holding register
{
uint16_t address = *((uint16_t*)(recv_buffer + 7));
uint16_t value = *((uint16_t*)(recv_buffer + 9));
response_pdu_length = 7;
send_buffer[6] = func_code;
write_result = write_register(address, value);
if (write_result == 0)
{
//*((uint16_t*)(send_buffer + 7)) = address;
send_buffer[7] = (uint8_t)(address&0x00FF);
send_buffer[8] = (uint8_t)((address&0xFF00)>>8);
//*((uint16_t*)(send_buffer + 9)) = value;
send_buffer[9] = (uint8_t)(value&0x00FF);
send_buffer[10] = (uint8_t)((value&0xFF00)>>8);
}
else
{
response_pdu_length = 4;
send_buffer[6] = 0x86;
send_buffer[7] = write_result;
}
}
else if (func_code == 0x10) // Write multiple registers
{
uint16_t start_address = *((uint16_t*)(recv_buffer + 7));
uint16_t quantity = *((uint16_t*)(recv_buffer + 9));
uint8_t byte_count = recv_buffer[11];
if (pdu_size != 3 + 5 + quantity * 2 || quantity * 2 != byte_count)
{
tranfer_errors_count++;
return;
}
response_pdu_length = 7;
send_buffer[6] = func_code;
//*((uint16_t*)(send_buffer + 7)) = start_address;
send_buffer[7] = (uint8_t)(start_address&0x00FF);
send_buffer[8] = (uint8_t)((start_address&0xFF00)>>8);
//*((uint16_t*)(send_buffer + 9)) = quantity;
send_buffer[9] = (uint8_t)(quantity&0x00FF);
send_buffer[10] = (uint8_t)((quantity&0xFF00)>>8);
for (address = start_address; address < start_address + quantity; address++)
{
uint16_t value = *((uint16_t*)(recv_buffer + 12u + 2u * (address - start_address)));
write_result = write_register(address, value);
if (write_result != 0)
{
response_pdu_length = 4;
send_buffer[6] = 0x90;
send_buffer[7] = write_result;
break;
}
}
}
else
{
tranfer_errors_count++;
return;
}
//*((uint16_t*)(send_buffer + 2)) = response_pdu_length;
send_buffer[2] = (uint8_t)(response_pdu_length&0x00FF);
send_buffer[3] = (uint8_t)((response_pdu_length&0xFF00)>>8);
size = 4 + response_pdu_length;
//*((uint16_t*)(send_buffer + size)) = checksum(size);
uint16_t s = checksum(size);
send_buffer[size] = (uint8_t)(s&0x00FF);
send_buffer[size+1] = (uint8_t)((s&0xFF00)>>8);
if (cmd_sending == SEND_IDLE)
{
bytes_to_send = size + 2;
cmd_sending = SEND_BUSY;
}
else
{
tranfer_errors_count++;
}
}

View File

@@ -0,0 +1,277 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file stm32f0xx_hal_msp.c
* @brief This file provides code for the MSP Initialization
* and de-Initialization codes.
******************************************************************************
* @attention
*
* Copyright (c) 2022 STMicroelectronics.
* All rights reserved.
*
* This software is licensed under terms that can be found in the LICENSE file
* in the root directory of this software component.
* If no LICENSE file comes with this software, it is provided AS-IS.
*
******************************************************************************
*/
/* USER CODE END Header */
/* Includes ------------------------------------------------------------------*/
#include "main.h"
/* USER CODE BEGIN Includes */
/* USER CODE END Includes */
/* Private typedef -----------------------------------------------------------*/
/* USER CODE BEGIN TD */
/* USER CODE END TD */
/* Private define ------------------------------------------------------------*/
/* USER CODE BEGIN Define */
/* USER CODE END Define */
/* Private macro -------------------------------------------------------------*/
/* USER CODE BEGIN Macro */
/* USER CODE END Macro */
/* Private variables ---------------------------------------------------------*/
/* USER CODE BEGIN PV */
/* USER CODE END PV */
/* Private function prototypes -----------------------------------------------*/
/* USER CODE BEGIN PFP */
/* USER CODE END PFP */
/* External functions --------------------------------------------------------*/
/* USER CODE BEGIN ExternalFunctions */
/* USER CODE END ExternalFunctions */
/* USER CODE BEGIN 0 */
/* USER CODE END 0 */
void HAL_TIM_MspPostInit(TIM_HandleTypeDef *htim);
/**
* Initializes the Global MSP.
*/
void HAL_MspInit(void)
{
/* USER CODE BEGIN MspInit 0 */
/* USER CODE END MspInit 0 */
__HAL_RCC_SYSCFG_CLK_ENABLE();
__HAL_RCC_PWR_CLK_ENABLE();
/* System interrupt init*/
/* USER CODE BEGIN MspInit 1 */
/* USER CODE END MspInit 1 */
}
/**
* @brief TIM_Base MSP Initialization
* This function configures the hardware resources used in this example
* @param htim_base: TIM_Base handle pointer
* @retval None
*/
void HAL_TIM_Base_MspInit(TIM_HandleTypeDef* htim_base)
{
if(htim_base->Instance==TIM1)
{
/* USER CODE BEGIN TIM1_MspInit 0 */
/* USER CODE END TIM1_MspInit 0 */
/* Peripheral clock enable */
__HAL_RCC_TIM1_CLK_ENABLE();
/* TIM1 interrupt Init */
HAL_NVIC_SetPriority(TIM1_BRK_UP_TRG_COM_IRQn, 0, 0);
HAL_NVIC_EnableIRQ(TIM1_BRK_UP_TRG_COM_IRQn);
HAL_NVIC_SetPriority(TIM1_CC_IRQn, 0, 0);
HAL_NVIC_EnableIRQ(TIM1_CC_IRQn);
/* USER CODE BEGIN TIM1_MspInit 1 */
/* USER CODE END TIM1_MspInit 1 */
}
}
/**
* @brief TIM_PWM MSP Initialization
* This function configures the hardware resources used in this example
* @param htim_pwm: TIM_PWM handle pointer
* @retval None
*/
void HAL_TIM_PWM_MspInit(TIM_HandleTypeDef* htim_pwm)
{
if(htim_pwm->Instance==TIM3)
{
/* USER CODE BEGIN TIM3_MspInit 0 */
/* USER CODE END TIM3_MspInit 0 */
/* Peripheral clock enable */
__HAL_RCC_TIM3_CLK_ENABLE();
/* USER CODE BEGIN TIM3_MspInit 1 */
/* USER CODE END TIM3_MspInit 1 */
}
}
void HAL_TIM_MspPostInit(TIM_HandleTypeDef* htim)
{
GPIO_InitTypeDef GPIO_InitStruct = {0};
if(htim->Instance==TIM3)
{
/* USER CODE BEGIN TIM3_MspPostInit 0 */
/* USER CODE END TIM3_MspPostInit 0 */
__HAL_RCC_GPIOB_CLK_ENABLE();
/**TIM3 GPIO Configuration
PB4 ------> TIM3_CH1
*/
GPIO_InitStruct.Pin = GPIO_PIN_4;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Alternate = GPIO_AF1_TIM3;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
/* USER CODE BEGIN TIM3_MspPostInit 1 */
/* USER CODE END TIM3_MspPostInit 1 */
}
}
/**
* @brief TIM_Base MSP De-Initialization
* This function freeze the hardware resources used in this example
* @param htim_base: TIM_Base handle pointer
* @retval None
*/
void HAL_TIM_Base_MspDeInit(TIM_HandleTypeDef* htim_base)
{
if(htim_base->Instance==TIM1)
{
/* USER CODE BEGIN TIM1_MspDeInit 0 */
/* USER CODE END TIM1_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_TIM1_CLK_DISABLE();
/* TIM1 interrupt DeInit */
HAL_NVIC_DisableIRQ(TIM1_BRK_UP_TRG_COM_IRQn);
HAL_NVIC_DisableIRQ(TIM1_CC_IRQn);
/* USER CODE BEGIN TIM1_MspDeInit 1 */
/* USER CODE END TIM1_MspDeInit 1 */
}
}
/**
* @brief TIM_PWM MSP De-Initialization
* This function freeze the hardware resources used in this example
* @param htim_pwm: TIM_PWM handle pointer
* @retval None
*/
void HAL_TIM_PWM_MspDeInit(TIM_HandleTypeDef* htim_pwm)
{
if(htim_pwm->Instance==TIM3)
{
/* USER CODE BEGIN TIM3_MspDeInit 0 */
/* USER CODE END TIM3_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_TIM3_CLK_DISABLE();
/* USER CODE BEGIN TIM3_MspDeInit 1 */
/* USER CODE END TIM3_MspDeInit 1 */
}
}
/**
* @brief UART MSP Initialization
* This function configures the hardware resources used in this example
* @param huart: UART handle pointer
* @retval None
*/
void HAL_UART_MspInit(UART_HandleTypeDef* huart)
{
GPIO_InitTypeDef GPIO_InitStruct = {0};
if(huart->Instance==USART1)
{
/* USER CODE BEGIN USART1_MspInit 0 */
/* USER CODE END USART1_MspInit 0 */
/* Peripheral clock enable */
__HAL_RCC_USART1_CLK_ENABLE();
__HAL_RCC_GPIOA_CLK_ENABLE();
/**USART1 GPIO Configuration
PA9 ------> USART1_TX
PA10 ------> USART1_RX
*/
GPIO_InitStruct.Pin = GPIO_PIN_9|GPIO_PIN_10;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF1_USART1;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
/* USART1 interrupt Init */
HAL_NVIC_SetPriority(USART1_IRQn, 0, 0);
HAL_NVIC_EnableIRQ(USART1_IRQn);
/* USER CODE BEGIN USART1_MspInit 1 */
/* USER CODE END USART1_MspInit 1 */
}
}
/**
* @brief UART MSP De-Initialization
* This function freeze the hardware resources used in this example
* @param huart: UART handle pointer
* @retval None
*/
void HAL_UART_MspDeInit(UART_HandleTypeDef* huart)
{
if(huart->Instance==USART1)
{
/* USER CODE BEGIN USART1_MspDeInit 0 */
/* USER CODE END USART1_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_USART1_CLK_DISABLE();
/**USART1 GPIO Configuration
PA9 ------> USART1_TX
PA10 ------> USART1_RX
*/
HAL_GPIO_DeInit(GPIOA, GPIO_PIN_9|GPIO_PIN_10);
/* USART1 interrupt DeInit */
HAL_NVIC_DisableIRQ(USART1_IRQn);
/* USER CODE BEGIN USART1_MspDeInit 1 */
/* USER CODE END USART1_MspDeInit 1 */
}
}
/* USER CODE BEGIN 1 */
/* USER CODE END 1 */

191
Core/Src/stm32f0xx_it.c Normal file
View File

@@ -0,0 +1,191 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file stm32f0xx_it.c
* @brief Interrupt Service Routines.
******************************************************************************
* @attention
*
* Copyright (c) 2022 STMicroelectronics.
* All rights reserved.
*
* This software is licensed under terms that can be found in the LICENSE file
* in the root directory of this software component.
* If no LICENSE file comes with this software, it is provided AS-IS.
*
******************************************************************************
*/
/* USER CODE END Header */
/* Includes ------------------------------------------------------------------*/
#include "main.h"
#include "stm32f0xx_it.h"
/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
/* USER CODE END Includes */
/* Private typedef -----------------------------------------------------------*/
/* USER CODE BEGIN TD */
/* USER CODE END TD */
/* Private define ------------------------------------------------------------*/
/* USER CODE BEGIN PD */
/* USER CODE END PD */
/* Private macro -------------------------------------------------------------*/
/* USER CODE BEGIN PM */
/* USER CODE END PM */
/* Private variables ---------------------------------------------------------*/
/* USER CODE BEGIN PV */
/* USER CODE END PV */
/* Private function prototypes -----------------------------------------------*/
/* USER CODE BEGIN PFP */
/* USER CODE END PFP */
/* Private user code ---------------------------------------------------------*/
/* USER CODE BEGIN 0 */
/* USER CODE END 0 */
/* External variables --------------------------------------------------------*/
extern TIM_HandleTypeDef htim1;
extern UART_HandleTypeDef huart1;
/* USER CODE BEGIN EV */
/* USER CODE END EV */
/******************************************************************************/
/* Cortex-M0 Processor Interruption and Exception Handlers */
/******************************************************************************/
/**
* @brief This function handles Non maskable interrupt.
*/
void NMI_Handler(void)
{
/* USER CODE BEGIN NonMaskableInt_IRQn 0 */
/* USER CODE END NonMaskableInt_IRQn 0 */
/* USER CODE BEGIN NonMaskableInt_IRQn 1 */
while (1)
{
}
/* USER CODE END NonMaskableInt_IRQn 1 */
}
/**
* @brief This function handles Hard fault interrupt.
*/
void HardFault_Handler(void)
{
/* USER CODE BEGIN HardFault_IRQn 0 */
/* USER CODE END HardFault_IRQn 0 */
while (1)
{
/* USER CODE BEGIN W1_HardFault_IRQn 0 */
/* USER CODE END W1_HardFault_IRQn 0 */
}
}
/**
* @brief This function handles System service call via SWI instruction.
*/
void SVC_Handler(void)
{
/* USER CODE BEGIN SVC_IRQn 0 */
/* USER CODE END SVC_IRQn 0 */
/* USER CODE BEGIN SVC_IRQn 1 */
/* USER CODE END SVC_IRQn 1 */
}
/**
* @brief This function handles Pendable request for system service.
*/
void PendSV_Handler(void)
{
/* USER CODE BEGIN PendSV_IRQn 0 */
/* USER CODE END PendSV_IRQn 0 */
/* USER CODE BEGIN PendSV_IRQn 1 */
/* USER CODE END PendSV_IRQn 1 */
}
/**
* @brief This function handles System tick timer.
*/
void SysTick_Handler(void)
{
/* USER CODE BEGIN SysTick_IRQn 0 */
/* USER CODE END SysTick_IRQn 0 */
HAL_IncTick();
/* USER CODE BEGIN SysTick_IRQn 1 */
/* USER CODE END SysTick_IRQn 1 */
}
/******************************************************************************/
/* STM32F0xx Peripheral Interrupt Handlers */
/* Add here the Interrupt Handlers for the used peripherals. */
/* For the available peripheral interrupt handler names, */
/* please refer to the startup file (startup_stm32f0xx.s). */
/******************************************************************************/
/**
* @brief This function handles TIM1 break, update, trigger and commutation interrupts.
*/
void TIM1_BRK_UP_TRG_COM_IRQHandler(void)
{
/* USER CODE BEGIN TIM1_BRK_UP_TRG_COM_IRQn 0 */
/* USER CODE END TIM1_BRK_UP_TRG_COM_IRQn 0 */
HAL_TIM_IRQHandler(&htim1);
/* USER CODE BEGIN TIM1_BRK_UP_TRG_COM_IRQn 1 */
/* USER CODE END TIM1_BRK_UP_TRG_COM_IRQn 1 */
}
/**
* @brief This function handles TIM1 capture compare interrupt.
*/
void TIM1_CC_IRQHandler(void)
{
/* USER CODE BEGIN TIM1_CC_IRQn 0 */
/* USER CODE END TIM1_CC_IRQn 0 */
HAL_TIM_IRQHandler(&htim1);
/* USER CODE BEGIN TIM1_CC_IRQn 1 */
/* USER CODE END TIM1_CC_IRQn 1 */
}
/**
* @brief This function handles USART1 global interrupt.
*/
void USART1_IRQHandler(void)
{
/* USER CODE BEGIN USART1_IRQn 0 */
USER_UART1_IRQHandler(&huart1);
return;
/* USER CODE END USART1_IRQn 0 */
HAL_UART_IRQHandler(&huart1);
/* USER CODE BEGIN USART1_IRQn 1 */
/* USER CODE END USART1_IRQn 1 */
}
/* USER CODE BEGIN 1 */
/* USER CODE END 1 */

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

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

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

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

247
Core/Src/system_stm32f0xx.c Normal file
View File

@@ -0,0 +1,247 @@
/**
******************************************************************************
* @file system_stm32f0xx.c
* @author MCD Application Team
* @brief CMSIS Cortex-M0 Device Peripheral Access Layer System Source File.
*
* 1. This file provides two functions and one global variable to be called from
* user application:
* - SystemInit(): This function is called at startup just after reset and
* before branch to main program. This call is made inside
* the "startup_stm32f0xx.s" file.
*
* - SystemCoreClock variable: Contains the core clock (HCLK), it can be used
* by the user application to setup the SysTick
* timer or configure other parameters.
*
* - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must
* be called whenever the core clock is changed
* during program execution.
*
*
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2016 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
/** @addtogroup CMSIS
* @{
*/
/** @addtogroup stm32f0xx_system
* @{
*/
/** @addtogroup STM32F0xx_System_Private_Includes
* @{
*/
#include "stm32f0xx.h"
/**
* @}
*/
/** @addtogroup STM32F0xx_System_Private_TypesDefinitions
* @{
*/
/**
* @}
*/
/** @addtogroup STM32F0xx_System_Private_Defines
* @{
*/
#if !defined (HSE_VALUE)
#define HSE_VALUE ((uint32_t)8000000) /*!< Default value of the External oscillator in Hz.
This value can be provided and adapted by the user application. */
#endif /* HSE_VALUE */
#if !defined (HSI_VALUE)
#define HSI_VALUE ((uint32_t)8000000) /*!< Default value of the Internal oscillator in Hz.
This value can be provided and adapted by the user application. */
#endif /* HSI_VALUE */
#if !defined (HSI48_VALUE)
#define HSI48_VALUE ((uint32_t)48000000) /*!< Default value of the HSI48 Internal oscillator in Hz.
This value can be provided and adapted by the user application. */
#endif /* HSI48_VALUE */
/**
* @}
*/
/** @addtogroup STM32F0xx_System_Private_Macros
* @{
*/
/**
* @}
*/
/** @addtogroup STM32F0xx_System_Private_Variables
* @{
*/
/* This variable is updated in three ways:
1) by calling CMSIS function SystemCoreClockUpdate()
2) by calling HAL API function HAL_RCC_GetHCLKFreq()
3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency
Note: If you use this function to configure the system clock; then there
is no need to call the 2 first functions listed above, since SystemCoreClock
variable is updated automatically.
*/
uint32_t SystemCoreClock = 8000000;
const uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
const uint8_t APBPrescTable[8] = {0, 0, 0, 0, 1, 2, 3, 4};
/**
* @}
*/
/** @addtogroup STM32F0xx_System_Private_FunctionPrototypes
* @{
*/
/**
* @}
*/
/** @addtogroup STM32F0xx_System_Private_Functions
* @{
*/
/**
* @brief Setup the microcontroller system
* @param None
* @retval None
*/
void SystemInit(void)
{
/* NOTE :SystemInit(): This function is called at startup just after reset and
before branch to main program. This call is made inside
the "startup_stm32f0xx.s" file.
User can setups the default system clock (System clock source, PLL Multiplier
and Divider factors, AHB/APBx prescalers and Flash settings).
*/
}
/**
* @brief Update SystemCoreClock variable according to Clock Register Values.
* The SystemCoreClock variable contains the core clock (HCLK), it can
* be used by the user application to setup the SysTick timer or configure
* other parameters.
*
* @note Each time the core clock (HCLK) changes, this function must be called
* to update SystemCoreClock variable value. Otherwise, any configuration
* based on this variable will be incorrect.
*
* @note - The system frequency computed by this function is not the real
* frequency in the chip. It is calculated based on the predefined
* constant and the selected clock source:
*
* - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*)
*
* - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**)
*
* - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**)
* or HSI_VALUE(*) multiplied/divided by the PLL factors.
*
* (*) HSI_VALUE is a constant defined in stm32f0xx_hal_conf.h file (default value
* 8 MHz) but the real value may vary depending on the variations
* in voltage and temperature.
*
* (**) HSE_VALUE is a constant defined in stm32f0xx_hal_conf.h file (its value
* depends on the application requirements), user has to ensure that HSE_VALUE
* is same as the real frequency of the crystal used. Otherwise, this function
* may have wrong result.
*
* - The result of this function could be not correct when using fractional
* value for HSE crystal.
*
* @param None
* @retval None
*/
void SystemCoreClockUpdate (void)
{
uint32_t tmp = 0, pllmull = 0, pllsource = 0, predivfactor = 0;
/* Get SYSCLK source -------------------------------------------------------*/
tmp = RCC->CFGR & RCC_CFGR_SWS;
switch (tmp)
{
case RCC_CFGR_SWS_HSI: /* HSI used as system clock */
SystemCoreClock = HSI_VALUE;
break;
case RCC_CFGR_SWS_HSE: /* HSE used as system clock */
SystemCoreClock = HSE_VALUE;
break;
case RCC_CFGR_SWS_PLL: /* PLL used as system clock */
/* Get PLL clock source and multiplication factor ----------------------*/
pllmull = RCC->CFGR & RCC_CFGR_PLLMUL;
pllsource = RCC->CFGR & RCC_CFGR_PLLSRC;
pllmull = ( pllmull >> 18) + 2;
predivfactor = (RCC->CFGR2 & RCC_CFGR2_PREDIV) + 1;
if (pllsource == RCC_CFGR_PLLSRC_HSE_PREDIV)
{
/* HSE used as PLL clock source : SystemCoreClock = HSE/PREDIV * PLLMUL */
SystemCoreClock = (HSE_VALUE/predivfactor) * pllmull;
}
#if defined(STM32F042x6) || defined(STM32F048xx) || defined(STM32F072xB) || defined(STM32F078xx) || defined(STM32F091xC) || defined(STM32F098xx)
else if (pllsource == RCC_CFGR_PLLSRC_HSI48_PREDIV)
{
/* HSI48 used as PLL clock source : SystemCoreClock = HSI48/PREDIV * PLLMUL */
SystemCoreClock = (HSI48_VALUE/predivfactor) * pllmull;
}
#endif /* STM32F042x6 || STM32F048xx || STM32F072xB || STM32F078xx || STM32F091xC || STM32F098xx */
else
{
#if defined(STM32F042x6) || defined(STM32F048xx) || defined(STM32F070x6) \
|| defined(STM32F078xx) || defined(STM32F071xB) || defined(STM32F072xB) \
|| defined(STM32F070xB) || defined(STM32F091xC) || defined(STM32F098xx) || defined(STM32F030xC)
/* HSI used as PLL clock source : SystemCoreClock = HSI/PREDIV * PLLMUL */
SystemCoreClock = (HSI_VALUE/predivfactor) * pllmull;
#else
/* HSI used as PLL clock source : SystemCoreClock = HSI/2 * PLLMUL */
SystemCoreClock = (HSI_VALUE >> 1) * pllmull;
#endif /* STM32F042x6 || STM32F048xx || STM32F070x6 ||
STM32F071xB || STM32F072xB || STM32F078xx || STM32F070xB ||
STM32F091xC || STM32F098xx || STM32F030xC */
}
break;
default: /* HSI used as system clock */
SystemCoreClock = HSI_VALUE;
break;
}
/* Compute HCLK clock frequency ----------------*/
/* Get HCLK prescaler */
tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)];
/* HCLK clock frequency */
SystemCoreClock >>= tmp;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

102
Core/Src/uart.c Normal file
View File

@@ -0,0 +1,102 @@
#include "uart.h"
#include "main.h"
#include <stdint.h>
#include <string.h>
#include <stdio.h>
uint8_t * uart_tx_buf;
uint8_t uart_tx_busy=0;
uint16_t uart_tx_counter=0;
uint16_t uart_tx_len=0;
uint8_t * uart_rx_buf;
uint8_t uart_rx_busy=0;
uint16_t uart_rx_counter=0;
uint16_t uart_rx_len=0;
extern uint16_t last_rx_time;
extern UART_HandleTypeDef huart1;
#define TXEN_ON HAL_GPIO_WritePin(TXEN_GPIO_Port, TXEN_Pin, GPIO_PIN_SET)
#define TXEN_OFF HAL_GPIO_WritePin(TXEN_GPIO_Port, TXEN_Pin, GPIO_PIN_RESET)
void USER_UART1_IRQHandler(UART_HandleTypeDef *huart)
{
uint8_t data;
if((huart1.Instance->ISR & USART_ISR_RXNE) != RESET)
{
last_rx_time = 0;
data = (uint8_t)(huart1.Instance->RDR & (uint8_t)0x00FF); // читает байт из регистра
if(uart_rx_busy)
{
uart_rx_buf[uart_rx_counter]=data;
if(++uart_rx_counter == uart_rx_len)
{
uart_rx_busy = 0;
UART_RxCpltCallback();
}
}
}
if((uart_tx_busy)&&((huart1.Instance->ISR & USART_ISR_TC) != RESET))
{
if(++uart_tx_counter == uart_tx_len)
{
TXEN_OFF;
uart_tx_busy = 0;
UART_TxCpltCallback();
__HAL_UART_DISABLE_IT(&huart1, UART_IT_TC);
}
else
//putchar(uart_tx_buf[uart_tx_counter]);
huart->Instance->TDR=uart_tx_buf[uart_tx_counter];
}
huart->Instance->ICR=0xFFFFFFFF;
}
uint8_t UART_Receive_IT(uint8_t * data, uint16_t len, uint16_t timeout)
{
uint16_t i;
//if(len>UART_RX_LEN)return RET_OVERFLOW;
for(i=0;i<timeout;i++)
{
if(uart_rx_busy!=0)
HAL_Delay(1);
else
break;
}
if(i==timeout) return RET_TIMEOUT;
uart_rx_counter = 0;
uart_rx_len = len;
uart_rx_buf = data;
uart_rx_busy = 1;
return RET_OK;
}
uint8_t UART_Transmit_IT(uint8_t * data, uint16_t len, uint16_t timeout)
{
uint16_t i;
for(i=0;i<timeout;i++)
{
if(uart_tx_busy!=0)
HAL_Delay(1);
else
break;
}
if(i==timeout) return RET_TIMEOUT;
uart_tx_busy = 1;
TXEN_ON;
HAL_Delay(1);
uart_tx_buf = data;
uart_tx_counter = 0;
uart_tx_len = len;
huart1.Instance->TDR=uart_tx_buf[0];
//putchar(uart_tx_buf[0]);
__HAL_UART_ENABLE_IT(&huart1, UART_IT_TC);
return RET_OK;
}