modbusRTU自定义协议 从机接收主机轮询

This commit is contained in:
kkkjtr 2025-10-22 16:33:44 +08:00
parent 92c8b36932
commit 74b941ab72
66 changed files with 2465 additions and 3307 deletions

File diff suppressed because one or more lines are too long

Binary file not shown.

Binary file not shown.

File diff suppressed because one or more lines are too long

View File

@ -59,7 +59,7 @@ void MX_ADC1_Init(void)
*/
sConfig.Channel = ADC_CHANNEL_0;
sConfig.Rank = ADC_REGULAR_RANK_1;
sConfig.SamplingTime = ADC_SAMPLETIME_55CYCLES_5;
sConfig.SamplingTime = ADC_SAMPLETIME_7CYCLES_5;
if (HAL_ADC_ConfigChannel(&hadc1, &sConfig) != HAL_OK)
{
Error_Handler();
@ -147,10 +147,10 @@ void HAL_ADC_MspInit(ADC_HandleTypeDef* adcHandle)
hdma_adc1.Init.Direction = DMA_PERIPH_TO_MEMORY;
hdma_adc1.Init.PeriphInc = DMA_PINC_DISABLE;
hdma_adc1.Init.MemInc = DMA_MINC_ENABLE;
hdma_adc1.Init.PeriphDataAlignment = DMA_PDATAALIGN_HALFWORD;
hdma_adc1.Init.MemDataAlignment = DMA_MDATAALIGN_HALFWORD;
hdma_adc1.Init.Mode = DMA_CIRCULAR;
hdma_adc1.Init.Priority = DMA_PRIORITY_HIGH;
hdma_adc1.Init.PeriphDataAlignment = DMA_PDATAALIGN_WORD;
hdma_adc1.Init.MemDataAlignment = DMA_MDATAALIGN_WORD;
hdma_adc1.Init.Mode = DMA_NORMAL;
hdma_adc1.Init.Priority = DMA_PRIORITY_MEDIUM;
if (HAL_DMA_Init(&hdma_adc1) != HAL_OK)
{
Error_Handler();

View File

@ -63,11 +63,6 @@ void MX_GPIO_Init(void)
GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
/*Configure GPIO pins : PD0 PD1 */
GPIO_InitStruct.Pin = GPIO_PIN_0|GPIO_PIN_1;
GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
HAL_GPIO_Init(GPIOD, &GPIO_InitStruct);
/*Configure GPIO pins : PA6 PA7 PA8 PA11
PA12 */
GPIO_InitStruct.Pin = GPIO_PIN_6|GPIO_PIN_7|GPIO_PIN_8|GPIO_PIN_11
@ -97,15 +92,19 @@ void MX_GPIO_Init(void)
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
HAL_GPIO_Init(SW1_GPIO_Port, &GPIO_InitStruct);
/*Configure GPIO pins : SW2_Pin SW3_Pin SW4_Pin SW5_Pin */
GPIO_InitStruct.Pin = SW2_Pin|SW3_Pin|SW4_Pin|SW5_Pin;
/*Configure GPIO pins : SW2_Pin SW3_Pin SW4_Pin */
GPIO_InitStruct.Pin = SW2_Pin|SW3_Pin|SW4_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
/*Configure peripheral I/O remapping */
__HAL_AFIO_REMAP_PD01_ENABLE();
/*Configure GPIO pin : SW5_Pin */
GPIO_InitStruct.Pin = SW5_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
HAL_GPIO_Init(SW5_GPIO_Port, &GPIO_InitStruct);
}

View File

@ -4,18 +4,9 @@
* @file : main.c
* @brief : Main program body
******************************************************************************
* @attention
*
* Copyright (c) 2025 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 "adc.h"
@ -25,73 +16,376 @@
/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
#include "string.h"
#include "stdio.h"
#include <stdio.h>
#include <string.h>
/* USER CODE END Includes */
/* Private typedef -----------------------------------------------------------*/
/* USER CODE BEGIN PTD */
#ifdef __GNUC__
#define PUTCHAR_PROTOTYPE int __io_putchar(int ch)
#else
#define PUTCHAR_PROTOTYPE int fputc(int ch, FILE *f)
#endif
typedef enum {
ROW_PA15 = 0,
ROW_PB3,
ROW_PB4,
ROW_PB5,
ROW_PB6
} MatrixRow_t;
// Modbus协议定义
typedef enum {
CMD_READ_MATRIX = 0x03 // 读取矩阵数据
} ModbusCommand_t;
// 通信状态
typedef enum {
STATE_IDLE = 0,
STATE_RECEIVING,
STATE_PROCESSING
} CommState_t;
PUTCHAR_PROTOTYPE
{
HAL_UART_Transmit(&huart1, (uint8_t *)&ch, 1, 0xFFFF);
return ch;
}
/* USER CODE END PTD */
/* Private define ------------------------------------------------------------*/
/* USER CODE BEGIN PD */
uint8_t txData[] = "Hello World\r\n"; // \r\n <20>ǻ<EFBFBD><C7BB>з<EFBFBD>
#define ADC_CHANNELS 6
uint16_t adc_values[ADC_CHANNELS];
volatile uint8_t adc_data_ready = 0;
#define ADC_BUFFER_SIZE ADC_CHANNELS
#define MATRIX_ROWS 5
#define MATRIX_COLS 6
#define THRESHOLD_LOW 100
#define THRESHOLD_HIGH 300
// 协议相关定义
#define RX_BUFFER_SIZE 16
#define TX_FRAME_SIZE 10 // 1+1+1+5+2=10字节
/* USER CODE END PD */
/* Private macro -------------------------------------------------------------*/
/* USER CODE BEGIN PM */
/* USER CODE END PM */
/* Private variables ---------------------------------------------------------*/
/* USER CODE BEGIN PV */
uint32_t adc_buffer[ADC_BUFFER_SIZE] = {0};
uint32_t matrix_data[MATRIX_ROWS][MATRIX_COLS] = {0};
uint8_t matrix_bitmap[MATRIX_ROWS][MATRIX_COLS] = {0};
volatile uint8_t adc_data_ready = 0;
MatrixRow_t current_row = ROW_PA15;
uint8_t matrix_scan_complete = 0;
// 通信相关变量
uint8_t device_address = 0x01;
uint8_t rx_buffer[RX_BUFFER_SIZE];
uint8_t tx_frame[TX_FRAME_SIZE];
volatile uint8_t rx_index = 0;
volatile CommState_t comm_state = STATE_IDLE;
volatile uint32_t last_rx_time = 0;
/* USER CODE END PV */
/* Private function prototypes -----------------------------------------------*/
void SystemClock_Config(void);
/* USER CODE BEGIN PFP */
void ADC_Start_Conversion(void);
void Matrix_Select_Row(MatrixRow_t row);
void Matrix_Scan_Next_Row(void);
void Matrix_Process_Data(void);
void Matrix_Reset_All_Rows(void);
// 新增函数
void Device_Address_Init(void);
uint8_t Matrix_Compress_Row(int row);
uint16_t Calculate_CRC16(uint8_t *data, uint8_t length);
void Process_Modbus_Request(void);
void Send_Modbus_Response(void);
uint8_t Validate_Modbus_Frame(uint8_t *frame, uint8_t length);
/* USER CODE END PFP */
/* Private user code ---------------------------------------------------------*/
/* USER CODE BEGIN 0 */
// DMA传输完成回调
void HAL_ADC_ConvCpltCallback(ADC_HandleTypeDef* hadc)
/**
* @brief
*/
void Device_Address_Init(void)
{
adc_data_ready = 1; // 设置数据就绪标志
GPIO_PinState pb12_state = HAL_GPIO_ReadPin(GPIOB, GPIO_PIN_12);
GPIO_PinState pb13_state = HAL_GPIO_ReadPin(GPIOB, GPIO_PIN_13);
if(pb12_state == GPIO_PIN_RESET && pb13_state == GPIO_PIN_RESET)
{
device_address = 0x01;
}
else if(pb12_state == GPIO_PIN_SET && pb13_state == GPIO_PIN_SET)
{
device_address = 0x02;
}
else if(pb12_state == GPIO_PIN_SET && pb13_state == GPIO_PIN_RESET)
{
device_address = 0x03;
}
else
{
device_address = 0xFF; // 错误地址
}
}
// 处理ADC数据的函数
void process_adc_data(void)
/**
* @brief 8
*/
uint8_t Matrix_Compress_Row(int row)
{
if (adc_data_ready) {
adc_data_ready = 0;
uint8_t compressed = 0;
for(int col = 0; col < MATRIX_COLS; col++)
{
if(matrix_bitmap[row][col] == 1)
{
compressed |= (1 << col);
}
}
return compressed;
}
// 在这里处理6个通道的ADC数据
// adc_values[0] ~ adc_values[5] 对应6个通道
/**
* @brief Modbus CRC16校验
*/
uint16_t Calculate_CRC16(uint8_t *data, uint8_t length)
{
uint16_t crc = 0xFFFF;
for(uint8_t i = 0; i < length; i++)
{
crc ^= data[i];
for(uint8_t j = 0; j < 8; j++)
{
if(crc & 0x0001)
{
crc = (crc >> 1) ^ 0xA001;
}
else
{
crc = crc >> 1;
}
}
}
return crc;
}
// 例如:通过串口输出
for (int i = 0; i < ADC_CHANNELS; i++) {
printf("Channel %d: %d\r\n", i, adc_values[i]);
/**
* @brief Modbus帧
*/
uint8_t Validate_Modbus_Frame(uint8_t *frame, uint8_t length)
{
if(length < 6) return 0; // 最小帧长为6字节
// 检查地址是否匹配
if(frame[0] != device_address && frame[0] != 0xFF) return 0;
// 检查功能码
if(frame[1] != CMD_READ_MATRIX) return 0;
// 检查CRC
uint16_t received_crc = (frame[length-1] << 8) | frame[length-2];
uint16_t calculated_crc = Calculate_CRC16(frame, length-2);
return (received_crc == calculated_crc);
}
/**
* @brief Modbus请求
*/
void Process_Modbus_Request(void)
{
if(comm_state != STATE_PROCESSING) return;
// 验证帧
if(!Validate_Modbus_Frame(rx_buffer, rx_index))
{
// CRC错误或格式错误不响应
comm_state = STATE_IDLE;
rx_index = 0;
return;
}
// 解析请求帧
uint8_t slave_addr = rx_buffer[0];
uint8_t function_code = rx_buffer[1];
uint16_t start_addr = (rx_buffer[2] << 8) | rx_buffer[3];
uint16_t data_count = (rx_buffer[4] << 8) | rx_buffer[5];
// 处理读取矩阵请求
if(function_code == CMD_READ_MATRIX && start_addr == 0x0000 && data_count == 0x0005)
{
Send_Modbus_Response();
}
comm_state = STATE_IDLE;
rx_index = 0;
}
/**
* @brief Modbus响应
*/
void Send_Modbus_Response(void)
{
uint8_t frame_index = 0;
// 设备地址
tx_frame[frame_index++] = device_address;
// 功能码
tx_frame[frame_index++] = CMD_READ_MATRIX;
// 数据长度
tx_frame[frame_index++] = MATRIX_ROWS;
// 压缩后的矩阵数据
for(int row = 0; row < MATRIX_ROWS; row++)
{
tx_frame[frame_index++] = Matrix_Compress_Row(row);
}
// 计算CRC16
uint16_t crc = Calculate_CRC16(tx_frame, frame_index);
tx_frame[frame_index++] = crc & 0xFF;
tx_frame[frame_index++] = (crc >> 8) & 0xFF;
// 发送响应帧
HAL_UART_Transmit(&huart1, tx_frame, TX_FRAME_SIZE, HAL_MAX_DELAY);
}
/**
* @brief
*/
void HAL_UART_RxCpltCallback(UART_HandleTypeDef *huart)
{
if(huart->Instance == USART1)
{
// 记录接收时间
last_rx_time = HAL_GetTick();
if(comm_state == STATE_IDLE)
{
comm_state = STATE_RECEIVING;
rx_index = 0;
}
// 读取接收到的字节
uint8_t data;
HAL_UART_Receive(huart, &data, 1, 0);
if(rx_index < RX_BUFFER_SIZE)
{
rx_buffer[rx_index++] = data;
}
// 重新启动接收
HAL_UART_Receive_IT(&huart1, &data, 1);
}
}
/**
* @brief
*/
void HAL_UARTEx_RxEventCallback(UART_HandleTypeDef *huart, uint16_t Size)
{
if(huart->Instance == USART1)
{
// 帧接收完成,开始处理
comm_state = STATE_PROCESSING;
}
}
/**
* @brief ADC转换
*/
void ADC_Start_Conversion(void)
{
if (HAL_ADC_Start_DMA(&hadc1, (uint32_t*)adc_buffer, ADC_BUFFER_SIZE) != HAL_OK)
{
Error_Handler();
}
}
/**
* @brief
*/
void Matrix_Select_Row(MatrixRow_t row)
{
Matrix_Reset_All_Rows();
switch(row)
{
case ROW_PA15:
HAL_GPIO_WritePin(GPIOA, GPIO_PIN_15, GPIO_PIN_SET);
break;
case ROW_PB3:
HAL_GPIO_WritePin(GPIOB, GPIO_PIN_3, GPIO_PIN_SET);
break;
case ROW_PB4:
HAL_GPIO_WritePin(GPIOB, GPIO_PIN_4, GPIO_PIN_SET);
break;
case ROW_PB5:
HAL_GPIO_WritePin(GPIOB, GPIO_PIN_5, GPIO_PIN_SET);
break;
case ROW_PB6:
HAL_GPIO_WritePin(GPIOB, GPIO_PIN_6, GPIO_PIN_SET);
break;
}
}
/**
* @brief
*/
void Matrix_Reset_All_Rows(void)
{
HAL_GPIO_WritePin(GPIOA, GPIO_PIN_15, GPIO_PIN_RESET);
HAL_GPIO_WritePin(GPIOB, GPIO_PIN_3, GPIO_PIN_RESET);
HAL_GPIO_WritePin(GPIOB, GPIO_PIN_4, GPIO_PIN_RESET);
HAL_GPIO_WritePin(GPIOB, GPIO_PIN_5, GPIO_PIN_RESET);
HAL_GPIO_WritePin(GPIOB, GPIO_PIN_6, GPIO_PIN_RESET);
}
/**
* @brief
*/
void Matrix_Scan_Next_Row(void)
{
Matrix_Select_Row(current_row);
HAL_Delay(2);
ADC_Start_Conversion();
}
/**
* @brief
*/
void Matrix_Process_Data(void)
{
for (int row = 0; row < MATRIX_ROWS; row++)
{
for (int col = 0; col < MATRIX_COLS; col++)
{
if (matrix_data[row][col] < THRESHOLD_LOW)
{
matrix_bitmap[row][col] = 1;
}
else if (matrix_data[row][col] > THRESHOLD_HIGH)
{
matrix_bitmap[row][col] = 0;
}
else
{
matrix_bitmap[row][col] = 0;
}
}
}
}
/**
* @brief ADC转换完成回调函数
*/
void HAL_ADC_ConvCpltCallback(ADC_HandleTypeDef* hadc)
{
for (int col = 0; col < MATRIX_COLS; col++)
{
matrix_data[current_row][col] = adc_buffer[col];
}
adc_data_ready = 1;
}
/* USER CODE END 0 */
/**
@ -100,95 +394,112 @@ void process_adc_data(void)
*/
int main(void)
{
HAL_Init();
SystemClock_Config();
MX_GPIO_Init();
MX_DMA_Init();
MX_ADC1_Init();
MX_USART1_UART_Init();
/* USER CODE BEGIN 1 */
HAL_StatusTypeDef ret;
/* USER CODE END 1 */
/* USER CODE BEGIN 2 */
// 初始化设备地址
Device_Address_Init();
/* MCU Configuration--------------------------------------------------------*/
// 初始化所有行为低电平
Matrix_Reset_All_Rows();
/* Reset of all peripherals, Initializes the Flash interface and the Systick. */
HAL_Init();
// 启动串口接收
uint8_t rx_byte;
HAL_UART_Receive_IT(&huart1, &rx_byte, 1);
/* USER CODE BEGIN Init */
// 启用串口空闲中断
__HAL_UART_ENABLE_IT(&huart1, UART_IT_IDLE);
/* USER CODE END Init */
// 启动第一次矩阵扫描
Matrix_Scan_Next_Row();
/* USER CODE END 2 */
/* Configure the system clock */
SystemClock_Config();
/* Infinite loop */
/* USER CODE BEGIN WHILE */
while (1)
{
// 处理矩阵扫描
if(adc_data_ready)
{
adc_data_ready = 0;
/* USER CODE BEGIN SysInit */
current_row++;
if(current_row >= MATRIX_ROWS)
{
current_row = ROW_PA15;
matrix_scan_complete = 1;
}
/* USER CODE END SysInit */
if(matrix_scan_complete)
{
Matrix_Process_Data();
matrix_scan_complete = 0;
}
/* Initialize all configured peripherals */
MX_GPIO_Init();
MX_DMA_Init();
MX_ADC1_Init();
MX_USART1_UART_Init();
/* USER CODE BEGIN 2 */
ret = HAL_ADC_Start_DMA(&hadc1, (uint32_t*)adc_values, ADC_CHANNELS);
Matrix_Scan_Next_Row();
}
/* USER CODE END 2 */
/* Infinite loop */
/* USER CODE BEGIN WHILE */
while (1)
{
// process_adc_data();
printf("test\r\n");
HAL_Delay(500);
/* USER CODE END WHILE */
/* USER CODE BEGIN 3 */
}
/* USER CODE END 3 */
// 处理Modbus请求
if(comm_state == STATE_PROCESSING)
{
Process_Modbus_Request();
}
/* USER CODE END WHILE */
}
/* 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};
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_HSI;
RCC_OscInitStruct.HSIState = RCC_HSI_ON;
RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT;
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSI_DIV2;
RCC_OscInitStruct.PLL.PLLMUL = RCC_PLL_MUL16;
if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK)
{
Error_Handler();
}
/** 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.HSEPredivValue = RCC_HSE_PREDIV_DIV1;
RCC_OscInitStruct.HSIState = RCC_HSI_ON;
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
RCC_OscInitStruct.PLL.PLLMUL = RCC_PLL_MUL9;
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_CLOCKTYPE_PCLK2;
RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2;
RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2;
/** Initializes the CPU, AHB and APB buses clocks
*/
RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK
|RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2;
RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2;
RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2;
if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2) != HAL_OK)
{
Error_Handler();
}
PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_ADC;
PeriphClkInit.AdcClockSelection = RCC_ADCPCLK2_DIV4;
if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK)
{
Error_Handler();
}
if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2) != HAL_OK)
{
Error_Handler();
}
PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_ADC;
PeriphClkInit.AdcClockSelection = RCC_ADCPCLK2_DIV4;
if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK)
{
Error_Handler();
}
}
/* USER CODE BEGIN 4 */
@ -201,14 +512,15 @@ void SystemClock_Config(void)
*/
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 */
/* 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
@ -219,9 +531,10 @@ void Error_Handler(void)
*/
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,
/* 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 */
/* USER CODE END 6 */
}
#endif /* USE_FULL_ASSERT */

File diff suppressed because one or more lines are too long

View File

@ -157,39 +157,7 @@
<Bp>
<Number>0</Number>
<Type>0</Type>
<LineNumber>209</LineNumber>
<EnabledFlag>1</EnabledFlag>
<Address>134221000</Address>
<ByteObject>0</ByteObject>
<HtxType>0</HtxType>
<ManyObjects>0</ManyObjects>
<SizeOfObject>0</SizeOfObject>
<BreakByAccess>0</BreakByAccess>
<BreakIfRCount>1</BreakIfRCount>
<Filename>../Core/Src/stm32f1xx_it.c</Filename>
<ExecCommand></ExecCommand>
<Expression>\\PressureSensorBoard_slave\../Core/Src/stm32f1xx_it.c\209</Expression>
</Bp>
<Bp>
<Number>1</Number>
<Type>0</Type>
<LineNumber>77</LineNumber>
<EnabledFlag>1</EnabledFlag>
<Address>134221314</Address>
<ByteObject>0</ByteObject>
<HtxType>0</HtxType>
<ManyObjects>0</ManyObjects>
<SizeOfObject>0</SizeOfObject>
<BreakByAccess>0</BreakByAccess>
<BreakIfRCount>1</BreakIfRCount>
<Filename>../Core/Src/main.c</Filename>
<ExecCommand></ExecCommand>
<Expression>\\PressureSensorBoard_slave\../Core/Src/main.c\77</Expression>
</Bp>
<Bp>
<Number>2</Number>
<Type>0</Type>
<LineNumber>83</LineNumber>
<LineNumber>297</LineNumber>
<EnabledFlag>1</EnabledFlag>
<Address>0</Address>
<ByteObject>0</ByteObject>

View File

@ -190,7 +190,7 @@
<hadIRAM2>0</hadIRAM2>
<hadIROM2>0</hadIROM2>
<StupSel>8</StupSel>
<useUlib>0</useUlib>
<useUlib>1</useUlib>
<EndSel>0</EndSel>
<uLtcg>0</uLtcg>
<nSecure>0</nSecure>
@ -469,6 +469,57 @@
<FileName>usart.c</FileName>
<FileType>1</FileType>
<FilePath>../Core/Src/usart.c</FilePath>
<FileOption>
<CommonProperty>
<UseCPPCompiler>2</UseCPPCompiler>
<RVCTCodeConst>0</RVCTCodeConst>
<RVCTZI>0</RVCTZI>
<RVCTOtherData>0</RVCTOtherData>
<ModuleSelection>0</ModuleSelection>
<IncludeInBuild>1</IncludeInBuild>
<AlwaysBuild>2</AlwaysBuild>
<GenerateAssemblyFile>2</GenerateAssemblyFile>
<AssembleAssemblyFile>2</AssembleAssemblyFile>
<PublicsOnly>2</PublicsOnly>
<StopOnExitCode>11</StopOnExitCode>
<CustomArgument></CustomArgument>
<IncludeLibraryModules></IncludeLibraryModules>
<ComprImg>1</ComprImg>
</CommonProperty>
<FileArmAds>
<Cads>
<interw>2</interw>
<Optim>0</Optim>
<oTime>2</oTime>
<SplitLS>2</SplitLS>
<OneElfS>2</OneElfS>
<Strict>2</Strict>
<EnumInt>2</EnumInt>
<PlainCh>2</PlainCh>
<Ropi>2</Ropi>
<Rwpi>2</Rwpi>
<wLevel>0</wLevel>
<uThumb>2</uThumb>
<uSurpInc>2</uSurpInc>
<uC99>2</uC99>
<uGnu>2</uGnu>
<useXO>2</useXO>
<v6Lang>0</v6Lang>
<v6LangP>0</v6LangP>
<vShortEn>2</vShortEn>
<vShortWch>2</vShortWch>
<v6Lto>2</v6Lto>
<v6WtE>2</v6WtE>
<v6Rtti>2</v6Rtti>
<VariousControls>
<MiscControls></MiscControls>
<Define></Define>
<Undefine></Undefine>
<IncludePath></IncludePath>
</VariousControls>
</Cads>
</FileArmAds>
</FileOption>
</File>
<File>
<FileName>stm32f1xx_it.c</FileName>
@ -554,6 +605,57 @@
<FileName>stm32f1xx_hal_uart.c</FileName>
<FileType>1</FileType>
<FilePath>../Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_uart.c</FilePath>
<FileOption>
<CommonProperty>
<UseCPPCompiler>2</UseCPPCompiler>
<RVCTCodeConst>0</RVCTCodeConst>
<RVCTZI>0</RVCTZI>
<RVCTOtherData>0</RVCTOtherData>
<ModuleSelection>0</ModuleSelection>
<IncludeInBuild>1</IncludeInBuild>
<AlwaysBuild>2</AlwaysBuild>
<GenerateAssemblyFile>2</GenerateAssemblyFile>
<AssembleAssemblyFile>2</AssembleAssemblyFile>
<PublicsOnly>2</PublicsOnly>
<StopOnExitCode>11</StopOnExitCode>
<CustomArgument></CustomArgument>
<IncludeLibraryModules></IncludeLibraryModules>
<ComprImg>1</ComprImg>
</CommonProperty>
<FileArmAds>
<Cads>
<interw>2</interw>
<Optim>0</Optim>
<oTime>2</oTime>
<SplitLS>2</SplitLS>
<OneElfS>2</OneElfS>
<Strict>2</Strict>
<EnumInt>2</EnumInt>
<PlainCh>2</PlainCh>
<Ropi>2</Ropi>
<Rwpi>2</Rwpi>
<wLevel>0</wLevel>
<uThumb>2</uThumb>
<uSurpInc>2</uSurpInc>
<uC99>2</uC99>
<uGnu>2</uGnu>
<useXO>2</useXO>
<v6Lang>0</v6Lang>
<v6LangP>0</v6LangP>
<vShortEn>2</vShortEn>
<vShortWch>2</vShortWch>
<v6Lto>2</v6Lto>
<v6WtE>2</v6WtE>
<v6Rtti>2</v6Rtti>
<VariousControls>
<MiscControls></MiscControls>
<Define></Define>
<Undefine></Undefine>
<IncludePath></IncludePath>
</VariousControls>
</Cads>
</FileArmAds>
</FileOption>
</File>
</Files>
</Group>

View File

@ -22,19 +22,17 @@ Dialog DLL: TCM.DLL V1.56.4.0
<h2>Project:</h2>
C:\Users\15435\Desktop\PressureSensorBoard\Software\slave\PressureSensorBoard-slave\MDK-ARM\PressureSensorBoard-slave.uvprojx
Project File Date: 10/11/2025
Project File Date: 10/22/2025
<h2>Output:</h2>
*** Using Compiler 'V5.06 update 7 (build 960)', folder: 'C:\app\Keil_v5\ARM\ARMCC\Bin'
Build target 'PressureSensorBoard-slave'
assembling startup_stm32f103xb.s...
compiling gpio.c...
compiling main.c...
../Core/Src/main.c(105): warning: #550-D: variable "ret" was set but never used
HAL_StatusTypeDef ret;
../Core/Src/main.c(204): warning: #177-D: variable "slave_addr" was declared but never referenced
uint8_t slave_addr = rx_buffer[0];
../Core/Src/main.c: 1 warning, 0 errors
linking...
Program Size: Code=8528 RO-data=324 RW-data=32 ZI-data=2088
Program Size: Code=6788 RO-data=312 RW-data=28 ZI-data=1412
FromELF: creating hex file...
"PressureSensorBoard-slave\PressureSensorBoard-slave.axf" - 0 Error(s), 1 Warning(s).

View File

@ -22,7 +22,7 @@
"pressuresensorboard-slave\stm32f1xx_hal_exti.o"
"pressuresensorboard-slave\stm32f1xx_hal_uart.o"
"pressuresensorboard-slave\system_stm32f1xx.o"
--strict --scatter "PressureSensorBoard-slave\PressureSensorBoard-slave.sct"
--library_type=microlib --strict --scatter "PressureSensorBoard-slave\PressureSensorBoard-slave.sct"
--summary_stderr --info summarysizes --map --load_addr_map_info --xref --callgraph --symbols
--info sizes --info totals --info unused --info veneers
--list "PressureSensorBoard-slave.map" -o PressureSensorBoard-slave\PressureSensorBoard-slave.axf

View File

@ -1,10 +1,10 @@
Dependencies for Project 'PressureSensorBoard-slave', Target 'PressureSensorBoard-slave': (DO NOT MODIFY !)
CompilerVersion: 5060960::V5.06 update 7 (build 960)::.\ARMCC
F (startup_stm32f103xb.s)(0x68E9B505)(--cpu Cortex-M3 -g --apcs=interwork -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include --pd "__UVISION_VERSION SETA 541" --pd "STM32F10X_MD SETA 1" --pd "_RTE_ SETA 1" --list startup_stm32f103xb.lst --xref -o pressuresensorboard-slave\startup_stm32f103xb.o --depend pressuresensorboard-slave\startup_stm32f103xb.d)
F (../Core/Src/main.c)(0x68E9B504)(--c99 -c --cpu Cortex-M3 -g -O3 --apcs=interwork --split_sections -I ../Core/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc/Legacy -I ../Drivers/CMSIS/Device/ST/STM32F1xx/Include -I ../Drivers/CMSIS/Include -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include -D__UVISION_VERSION="541" -DSTM32F10X_MD -D_RTE_ -DUSE_HAL_DRIVER -DSTM32F103xB -o pressuresensorboard-slave\main.o --omf_browse pressuresensorboard-slave\main.crf --depend pressuresensorboard-slave\main.d)
I (../Core/Inc/main.h)(0x68E72B5B)
F (startup_stm32f103xb.s)(0x68F885DF)(--cpu Cortex-M3 -g --apcs=interwork --pd "__MICROLIB SETA 1" -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include --pd "__UVISION_VERSION SETA 541" --pd "STM32F10X_MD SETA 1" --pd "_RTE_ SETA 1" --list startup_stm32f103xb.lst --xref -o pressuresensorboard-slave\startup_stm32f103xb.o --depend pressuresensorboard-slave\startup_stm32f103xb.d)
F (../Core/Src/main.c)(0x68F895C8)(--c99 -c --cpu Cortex-M3 -D__MICROLIB -g -O3 --apcs=interwork --split_sections -I ../Core/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc/Legacy -I ../Drivers/CMSIS/Device/ST/STM32F1xx/Include -I ../Drivers/CMSIS/Include -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include -D__UVISION_VERSION="541" -DSTM32F10X_MD -D_RTE_ -DUSE_HAL_DRIVER -DSTM32F103xB -o pressuresensorboard-slave\main.o --omf_browse pressuresensorboard-slave\main.crf --depend pressuresensorboard-slave\main.d)
I (../Core/Inc/main.h)(0x68F0969B)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal.h)(0x68E72B55)
I (../Core/Inc/stm32f1xx_hal_conf.h)(0x68E89462)
I (../Core/Inc/stm32f1xx_hal_conf.h)(0x68F195EE)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_rcc.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_def.h)(0x68E72B55)
I (../Drivers/CMSIS/Device/ST/STM32F1xx/Include/stm32f1xx.h)(0x68E72B55)
@ -31,16 +31,16 @@ I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash_ex.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_pwr.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_uart.h)(0x68E72B55)
I (../Core/Inc/adc.h)(0x68E72B5A)
I (../Core/Inc/dma.h)(0x68E89462)
I (../Core/Inc/usart.h)(0x68E72B5A)
I (../Core/Inc/dma.h)(0x68F09C6C)
I (../Core/Inc/usart.h)(0x68F195EE)
I (../Core/Inc/gpio.h)(0x68E72B5A)
I (C:\app\Keil_v5\ARM\ARMCC\include\string.h)(0x6025237E)
I (C:\app\Keil_v5\ARM\ARMCC\include\stdio.h)(0x60252374)
F (../Core/Src/gpio.c)(0x68E9B504)(--c99 -c --cpu Cortex-M3 -g -O3 --apcs=interwork --split_sections -I ../Core/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc/Legacy -I ../Drivers/CMSIS/Device/ST/STM32F1xx/Include -I ../Drivers/CMSIS/Include -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include -D__UVISION_VERSION="541" -DSTM32F10X_MD -D_RTE_ -DUSE_HAL_DRIVER -DSTM32F103xB -o pressuresensorboard-slave\gpio.o --omf_browse pressuresensorboard-slave\gpio.crf --depend pressuresensorboard-slave\gpio.d)
I (C:\app\Keil_v5\ARM\ARMCC\include\string.h)(0x6025237E)
F (../Core/Src/gpio.c)(0x68F195EE)(--c99 -c --cpu Cortex-M3 -D__MICROLIB -g -O3 --apcs=interwork --split_sections -I ../Core/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc/Legacy -I ../Drivers/CMSIS/Device/ST/STM32F1xx/Include -I ../Drivers/CMSIS/Include -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include -D__UVISION_VERSION="541" -DSTM32F10X_MD -D_RTE_ -DUSE_HAL_DRIVER -DSTM32F103xB -o pressuresensorboard-slave\gpio.o --omf_browse pressuresensorboard-slave\gpio.crf --depend pressuresensorboard-slave\gpio.d)
I (../Core/Inc/gpio.h)(0x68E72B5A)
I (../Core/Inc/main.h)(0x68E72B5B)
I (../Core/Inc/main.h)(0x68F0969B)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal.h)(0x68E72B55)
I (../Core/Inc/stm32f1xx_hal_conf.h)(0x68E89462)
I (../Core/Inc/stm32f1xx_hal_conf.h)(0x68F195EE)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_rcc.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_def.h)(0x68E72B55)
I (../Drivers/CMSIS/Device/ST/STM32F1xx/Include/stm32f1xx.h)(0x68E72B55)
@ -66,11 +66,11 @@ I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash_ex.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_pwr.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_uart.h)(0x68E72B55)
F (../Core/Src/adc.c)(0x68E8A670)(--c99 -c --cpu Cortex-M3 -g -O3 --apcs=interwork --split_sections -I ../Core/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc/Legacy -I ../Drivers/CMSIS/Device/ST/STM32F1xx/Include -I ../Drivers/CMSIS/Include -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include -D__UVISION_VERSION="541" -DSTM32F10X_MD -D_RTE_ -DUSE_HAL_DRIVER -DSTM32F103xB -o pressuresensorboard-slave\adc.o --omf_browse pressuresensorboard-slave\adc.crf --depend pressuresensorboard-slave\adc.d)
F (../Core/Src/adc.c)(0x68F885DD)(--c99 -c --cpu Cortex-M3 -D__MICROLIB -g -O3 --apcs=interwork --split_sections -I ../Core/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc/Legacy -I ../Drivers/CMSIS/Device/ST/STM32F1xx/Include -I ../Drivers/CMSIS/Include -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include -D__UVISION_VERSION="541" -DSTM32F10X_MD -D_RTE_ -DUSE_HAL_DRIVER -DSTM32F103xB -o pressuresensorboard-slave\adc.o --omf_browse pressuresensorboard-slave\adc.crf --depend pressuresensorboard-slave\adc.d)
I (../Core/Inc/adc.h)(0x68E72B5A)
I (../Core/Inc/main.h)(0x68E72B5B)
I (../Core/Inc/main.h)(0x68F0969B)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal.h)(0x68E72B55)
I (../Core/Inc/stm32f1xx_hal_conf.h)(0x68E89462)
I (../Core/Inc/stm32f1xx_hal_conf.h)(0x68F195EE)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_rcc.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_def.h)(0x68E72B55)
I (../Drivers/CMSIS/Device/ST/STM32F1xx/Include/stm32f1xx.h)(0x68E72B55)
@ -96,11 +96,11 @@ I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash_ex.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_pwr.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_uart.h)(0x68E72B55)
F (../Core/Src/dma.c)(0x68E89462)(--c99 -c --cpu Cortex-M3 -g -O3 --apcs=interwork --split_sections -I ../Core/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc/Legacy -I ../Drivers/CMSIS/Device/ST/STM32F1xx/Include -I ../Drivers/CMSIS/Include -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include -D__UVISION_VERSION="541" -DSTM32F10X_MD -D_RTE_ -DUSE_HAL_DRIVER -DSTM32F103xB -o pressuresensorboard-slave\dma.o --omf_browse pressuresensorboard-slave\dma.crf --depend pressuresensorboard-slave\dma.d)
I (../Core/Inc/dma.h)(0x68E89462)
I (../Core/Inc/main.h)(0x68E72B5B)
F (../Core/Src/dma.c)(0x68F09C6C)(--c99 -c --cpu Cortex-M3 -D__MICROLIB -g -O3 --apcs=interwork --split_sections -I ../Core/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc/Legacy -I ../Drivers/CMSIS/Device/ST/STM32F1xx/Include -I ../Drivers/CMSIS/Include -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include -D__UVISION_VERSION="541" -DSTM32F10X_MD -D_RTE_ -DUSE_HAL_DRIVER -DSTM32F103xB -o pressuresensorboard-slave\dma.o --omf_browse pressuresensorboard-slave\dma.crf --depend pressuresensorboard-slave\dma.d)
I (../Core/Inc/dma.h)(0x68F09C6C)
I (../Core/Inc/main.h)(0x68F0969B)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal.h)(0x68E72B55)
I (../Core/Inc/stm32f1xx_hal_conf.h)(0x68E89462)
I (../Core/Inc/stm32f1xx_hal_conf.h)(0x68F195EE)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_rcc.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_def.h)(0x68E72B55)
I (../Drivers/CMSIS/Device/ST/STM32F1xx/Include/stm32f1xx.h)(0x68E72B55)
@ -126,11 +126,11 @@ I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash_ex.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_pwr.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_uart.h)(0x68E72B55)
F (../Core/Src/usart.c)(0x68E72B5A)(--c99 -c --cpu Cortex-M3 -g -O3 --apcs=interwork --split_sections -I ../Core/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc/Legacy -I ../Drivers/CMSIS/Device/ST/STM32F1xx/Include -I ../Drivers/CMSIS/Include -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include -D__UVISION_VERSION="541" -DSTM32F10X_MD -D_RTE_ -DUSE_HAL_DRIVER -DSTM32F103xB -o pressuresensorboard-slave\usart.o --omf_browse pressuresensorboard-slave\usart.crf --depend pressuresensorboard-slave\usart.d)
I (../Core/Inc/usart.h)(0x68E72B5A)
I (../Core/Inc/main.h)(0x68E72B5B)
F (../Core/Src/usart.c)(0x68F195EE)(--c99 -c --cpu Cortex-M3 -D__MICROLIB -g -O3 --apcs=interwork --split_sections -I ../Core/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc/Legacy -I ../Drivers/CMSIS/Device/ST/STM32F1xx/Include -I ../Drivers/CMSIS/Include -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include -D__UVISION_VERSION="541" -DSTM32F10X_MD -D_RTE_ -DUSE_HAL_DRIVER -DSTM32F103xB -o pressuresensorboard-slave\usart.o --omf_browse pressuresensorboard-slave\usart.crf --depend pressuresensorboard-slave\usart.d)
I (../Core/Inc/usart.h)(0x68F195EE)
I (../Core/Inc/main.h)(0x68F0969B)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal.h)(0x68E72B55)
I (../Core/Inc/stm32f1xx_hal_conf.h)(0x68E89462)
I (../Core/Inc/stm32f1xx_hal_conf.h)(0x68F195EE)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_rcc.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_def.h)(0x68E72B55)
I (../Drivers/CMSIS/Device/ST/STM32F1xx/Include/stm32f1xx.h)(0x68E72B55)
@ -156,10 +156,10 @@ I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash_ex.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_pwr.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_uart.h)(0x68E72B55)
F (../Core/Src/stm32f1xx_it.c)(0x68E89462)(--c99 -c --cpu Cortex-M3 -g -O3 --apcs=interwork --split_sections -I ../Core/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc/Legacy -I ../Drivers/CMSIS/Device/ST/STM32F1xx/Include -I ../Drivers/CMSIS/Include -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include -D__UVISION_VERSION="541" -DSTM32F10X_MD -D_RTE_ -DUSE_HAL_DRIVER -DSTM32F103xB -o pressuresensorboard-slave\stm32f1xx_it.o --omf_browse pressuresensorboard-slave\stm32f1xx_it.crf --depend pressuresensorboard-slave\stm32f1xx_it.d)
I (../Core/Inc/main.h)(0x68E72B5B)
F (../Core/Src/stm32f1xx_it.c)(0x68F09C6D)(--c99 -c --cpu Cortex-M3 -D__MICROLIB -g -O3 --apcs=interwork --split_sections -I ../Core/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc/Legacy -I ../Drivers/CMSIS/Device/ST/STM32F1xx/Include -I ../Drivers/CMSIS/Include -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include -D__UVISION_VERSION="541" -DSTM32F10X_MD -D_RTE_ -DUSE_HAL_DRIVER -DSTM32F103xB -o pressuresensorboard-slave\stm32f1xx_it.o --omf_browse pressuresensorboard-slave\stm32f1xx_it.crf --depend pressuresensorboard-slave\stm32f1xx_it.d)
I (../Core/Inc/main.h)(0x68F0969B)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal.h)(0x68E72B55)
I (../Core/Inc/stm32f1xx_hal_conf.h)(0x68E89462)
I (../Core/Inc/stm32f1xx_hal_conf.h)(0x68F195EE)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_rcc.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_def.h)(0x68E72B55)
I (../Drivers/CMSIS/Device/ST/STM32F1xx/Include/stm32f1xx.h)(0x68E72B55)
@ -185,11 +185,11 @@ I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash_ex.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_pwr.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_uart.h)(0x68E72B55)
I (../Core/Inc/stm32f1xx_it.h)(0x68E89462)
F (../Core/Src/stm32f1xx_hal_msp.c)(0x68E72B5B)(--c99 -c --cpu Cortex-M3 -g -O3 --apcs=interwork --split_sections -I ../Core/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc/Legacy -I ../Drivers/CMSIS/Device/ST/STM32F1xx/Include -I ../Drivers/CMSIS/Include -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include -D__UVISION_VERSION="541" -DSTM32F10X_MD -D_RTE_ -DUSE_HAL_DRIVER -DSTM32F103xB -o pressuresensorboard-slave\stm32f1xx_hal_msp.o --omf_browse pressuresensorboard-slave\stm32f1xx_hal_msp.crf --depend pressuresensorboard-slave\stm32f1xx_hal_msp.d)
I (../Core/Inc/main.h)(0x68E72B5B)
I (../Core/Inc/stm32f1xx_it.h)(0x68F09C6D)
F (../Core/Src/stm32f1xx_hal_msp.c)(0x68E72B5B)(--c99 -c --cpu Cortex-M3 -D__MICROLIB -g -O3 --apcs=interwork --split_sections -I ../Core/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc/Legacy -I ../Drivers/CMSIS/Device/ST/STM32F1xx/Include -I ../Drivers/CMSIS/Include -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include -D__UVISION_VERSION="541" -DSTM32F10X_MD -D_RTE_ -DUSE_HAL_DRIVER -DSTM32F103xB -o pressuresensorboard-slave\stm32f1xx_hal_msp.o --omf_browse pressuresensorboard-slave\stm32f1xx_hal_msp.crf --depend pressuresensorboard-slave\stm32f1xx_hal_msp.d)
I (../Core/Inc/main.h)(0x68F0969B)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal.h)(0x68E72B55)
I (../Core/Inc/stm32f1xx_hal_conf.h)(0x68E89462)
I (../Core/Inc/stm32f1xx_hal_conf.h)(0x68F195EE)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_rcc.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_def.h)(0x68E72B55)
I (../Drivers/CMSIS/Device/ST/STM32F1xx/Include/stm32f1xx.h)(0x68E72B55)
@ -215,9 +215,9 @@ I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash_ex.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_pwr.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_uart.h)(0x68E72B55)
F (../Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_gpio_ex.c)(0x68E72B55)(--c99 -c --cpu Cortex-M3 -g -O3 --apcs=interwork --split_sections -I ../Core/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc/Legacy -I ../Drivers/CMSIS/Device/ST/STM32F1xx/Include -I ../Drivers/CMSIS/Include -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include -D__UVISION_VERSION="541" -DSTM32F10X_MD -D_RTE_ -DUSE_HAL_DRIVER -DSTM32F103xB -o pressuresensorboard-slave\stm32f1xx_hal_gpio_ex.o --omf_browse pressuresensorboard-slave\stm32f1xx_hal_gpio_ex.crf --depend pressuresensorboard-slave\stm32f1xx_hal_gpio_ex.d)
F (../Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_gpio_ex.c)(0x68E72B55)(--c99 -c --cpu Cortex-M3 -D__MICROLIB -g -O3 --apcs=interwork --split_sections -I ../Core/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc/Legacy -I ../Drivers/CMSIS/Device/ST/STM32F1xx/Include -I ../Drivers/CMSIS/Include -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include -D__UVISION_VERSION="541" -DSTM32F10X_MD -D_RTE_ -DUSE_HAL_DRIVER -DSTM32F103xB -o pressuresensorboard-slave\stm32f1xx_hal_gpio_ex.o --omf_browse pressuresensorboard-slave\stm32f1xx_hal_gpio_ex.crf --depend pressuresensorboard-slave\stm32f1xx_hal_gpio_ex.d)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal.h)(0x68E72B55)
I (../Core/Inc/stm32f1xx_hal_conf.h)(0x68E89462)
I (../Core/Inc/stm32f1xx_hal_conf.h)(0x68F195EE)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_rcc.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_def.h)(0x68E72B55)
I (../Drivers/CMSIS/Device/ST/STM32F1xx/Include/stm32f1xx.h)(0x68E72B55)
@ -243,9 +243,9 @@ I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash_ex.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_pwr.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_uart.h)(0x68E72B55)
F (../Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_adc.c)(0x68E72B55)(--c99 -c --cpu Cortex-M3 -g -O3 --apcs=interwork --split_sections -I ../Core/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc/Legacy -I ../Drivers/CMSIS/Device/ST/STM32F1xx/Include -I ../Drivers/CMSIS/Include -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include -D__UVISION_VERSION="541" -DSTM32F10X_MD -D_RTE_ -DUSE_HAL_DRIVER -DSTM32F103xB -o pressuresensorboard-slave\stm32f1xx_hal_adc.o --omf_browse pressuresensorboard-slave\stm32f1xx_hal_adc.crf --depend pressuresensorboard-slave\stm32f1xx_hal_adc.d)
F (../Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_adc.c)(0x68E72B55)(--c99 -c --cpu Cortex-M3 -D__MICROLIB -g -O3 --apcs=interwork --split_sections -I ../Core/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc/Legacy -I ../Drivers/CMSIS/Device/ST/STM32F1xx/Include -I ../Drivers/CMSIS/Include -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include -D__UVISION_VERSION="541" -DSTM32F10X_MD -D_RTE_ -DUSE_HAL_DRIVER -DSTM32F103xB -o pressuresensorboard-slave\stm32f1xx_hal_adc.o --omf_browse pressuresensorboard-slave\stm32f1xx_hal_adc.crf --depend pressuresensorboard-slave\stm32f1xx_hal_adc.d)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal.h)(0x68E72B55)
I (../Core/Inc/stm32f1xx_hal_conf.h)(0x68E89462)
I (../Core/Inc/stm32f1xx_hal_conf.h)(0x68F195EE)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_rcc.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_def.h)(0x68E72B55)
I (../Drivers/CMSIS/Device/ST/STM32F1xx/Include/stm32f1xx.h)(0x68E72B55)
@ -271,9 +271,9 @@ I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash_ex.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_pwr.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_uart.h)(0x68E72B55)
F (../Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_adc_ex.c)(0x68E72B55)(--c99 -c --cpu Cortex-M3 -g -O3 --apcs=interwork --split_sections -I ../Core/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc/Legacy -I ../Drivers/CMSIS/Device/ST/STM32F1xx/Include -I ../Drivers/CMSIS/Include -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include -D__UVISION_VERSION="541" -DSTM32F10X_MD -D_RTE_ -DUSE_HAL_DRIVER -DSTM32F103xB -o pressuresensorboard-slave\stm32f1xx_hal_adc_ex.o --omf_browse pressuresensorboard-slave\stm32f1xx_hal_adc_ex.crf --depend pressuresensorboard-slave\stm32f1xx_hal_adc_ex.d)
F (../Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_adc_ex.c)(0x68E72B55)(--c99 -c --cpu Cortex-M3 -D__MICROLIB -g -O3 --apcs=interwork --split_sections -I ../Core/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc/Legacy -I ../Drivers/CMSIS/Device/ST/STM32F1xx/Include -I ../Drivers/CMSIS/Include -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include -D__UVISION_VERSION="541" -DSTM32F10X_MD -D_RTE_ -DUSE_HAL_DRIVER -DSTM32F103xB -o pressuresensorboard-slave\stm32f1xx_hal_adc_ex.o --omf_browse pressuresensorboard-slave\stm32f1xx_hal_adc_ex.crf --depend pressuresensorboard-slave\stm32f1xx_hal_adc_ex.d)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal.h)(0x68E72B55)
I (../Core/Inc/stm32f1xx_hal_conf.h)(0x68E89462)
I (../Core/Inc/stm32f1xx_hal_conf.h)(0x68F195EE)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_rcc.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_def.h)(0x68E72B55)
I (../Drivers/CMSIS/Device/ST/STM32F1xx/Include/stm32f1xx.h)(0x68E72B55)
@ -299,9 +299,9 @@ I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash_ex.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_pwr.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_uart.h)(0x68E72B55)
F (../Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal.c)(0x68E72B55)(--c99 -c --cpu Cortex-M3 -g -O3 --apcs=interwork --split_sections -I ../Core/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc/Legacy -I ../Drivers/CMSIS/Device/ST/STM32F1xx/Include -I ../Drivers/CMSIS/Include -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include -D__UVISION_VERSION="541" -DSTM32F10X_MD -D_RTE_ -DUSE_HAL_DRIVER -DSTM32F103xB -o pressuresensorboard-slave\stm32f1xx_hal.o --omf_browse pressuresensorboard-slave\stm32f1xx_hal.crf --depend pressuresensorboard-slave\stm32f1xx_hal.d)
F (../Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal.c)(0x68E72B55)(--c99 -c --cpu Cortex-M3 -D__MICROLIB -g -O3 --apcs=interwork --split_sections -I ../Core/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc/Legacy -I ../Drivers/CMSIS/Device/ST/STM32F1xx/Include -I ../Drivers/CMSIS/Include -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include -D__UVISION_VERSION="541" -DSTM32F10X_MD -D_RTE_ -DUSE_HAL_DRIVER -DSTM32F103xB -o pressuresensorboard-slave\stm32f1xx_hal.o --omf_browse pressuresensorboard-slave\stm32f1xx_hal.crf --depend pressuresensorboard-slave\stm32f1xx_hal.d)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal.h)(0x68E72B55)
I (../Core/Inc/stm32f1xx_hal_conf.h)(0x68E89462)
I (../Core/Inc/stm32f1xx_hal_conf.h)(0x68F195EE)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_rcc.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_def.h)(0x68E72B55)
I (../Drivers/CMSIS/Device/ST/STM32F1xx/Include/stm32f1xx.h)(0x68E72B55)
@ -327,9 +327,9 @@ I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash_ex.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_pwr.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_uart.h)(0x68E72B55)
F (../Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_rcc.c)(0x68E72B55)(--c99 -c --cpu Cortex-M3 -g -O3 --apcs=interwork --split_sections -I ../Core/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc/Legacy -I ../Drivers/CMSIS/Device/ST/STM32F1xx/Include -I ../Drivers/CMSIS/Include -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include -D__UVISION_VERSION="541" -DSTM32F10X_MD -D_RTE_ -DUSE_HAL_DRIVER -DSTM32F103xB -o pressuresensorboard-slave\stm32f1xx_hal_rcc.o --omf_browse pressuresensorboard-slave\stm32f1xx_hal_rcc.crf --depend pressuresensorboard-slave\stm32f1xx_hal_rcc.d)
F (../Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_rcc.c)(0x68E72B55)(--c99 -c --cpu Cortex-M3 -D__MICROLIB -g -O3 --apcs=interwork --split_sections -I ../Core/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc/Legacy -I ../Drivers/CMSIS/Device/ST/STM32F1xx/Include -I ../Drivers/CMSIS/Include -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include -D__UVISION_VERSION="541" -DSTM32F10X_MD -D_RTE_ -DUSE_HAL_DRIVER -DSTM32F103xB -o pressuresensorboard-slave\stm32f1xx_hal_rcc.o --omf_browse pressuresensorboard-slave\stm32f1xx_hal_rcc.crf --depend pressuresensorboard-slave\stm32f1xx_hal_rcc.d)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal.h)(0x68E72B55)
I (../Core/Inc/stm32f1xx_hal_conf.h)(0x68E89462)
I (../Core/Inc/stm32f1xx_hal_conf.h)(0x68F195EE)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_rcc.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_def.h)(0x68E72B55)
I (../Drivers/CMSIS/Device/ST/STM32F1xx/Include/stm32f1xx.h)(0x68E72B55)
@ -355,9 +355,9 @@ I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash_ex.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_pwr.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_uart.h)(0x68E72B55)
F (../Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_rcc_ex.c)(0x68E72B55)(--c99 -c --cpu Cortex-M3 -g -O3 --apcs=interwork --split_sections -I ../Core/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc/Legacy -I ../Drivers/CMSIS/Device/ST/STM32F1xx/Include -I ../Drivers/CMSIS/Include -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include -D__UVISION_VERSION="541" -DSTM32F10X_MD -D_RTE_ -DUSE_HAL_DRIVER -DSTM32F103xB -o pressuresensorboard-slave\stm32f1xx_hal_rcc_ex.o --omf_browse pressuresensorboard-slave\stm32f1xx_hal_rcc_ex.crf --depend pressuresensorboard-slave\stm32f1xx_hal_rcc_ex.d)
F (../Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_rcc_ex.c)(0x68E72B55)(--c99 -c --cpu Cortex-M3 -D__MICROLIB -g -O3 --apcs=interwork --split_sections -I ../Core/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc/Legacy -I ../Drivers/CMSIS/Device/ST/STM32F1xx/Include -I ../Drivers/CMSIS/Include -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include -D__UVISION_VERSION="541" -DSTM32F10X_MD -D_RTE_ -DUSE_HAL_DRIVER -DSTM32F103xB -o pressuresensorboard-slave\stm32f1xx_hal_rcc_ex.o --omf_browse pressuresensorboard-slave\stm32f1xx_hal_rcc_ex.crf --depend pressuresensorboard-slave\stm32f1xx_hal_rcc_ex.d)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal.h)(0x68E72B55)
I (../Core/Inc/stm32f1xx_hal_conf.h)(0x68E89462)
I (../Core/Inc/stm32f1xx_hal_conf.h)(0x68F195EE)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_rcc.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_def.h)(0x68E72B55)
I (../Drivers/CMSIS/Device/ST/STM32F1xx/Include/stm32f1xx.h)(0x68E72B55)
@ -383,9 +383,9 @@ I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash_ex.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_pwr.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_uart.h)(0x68E72B55)
F (../Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_gpio.c)(0x68E72B55)(--c99 -c --cpu Cortex-M3 -g -O3 --apcs=interwork --split_sections -I ../Core/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc/Legacy -I ../Drivers/CMSIS/Device/ST/STM32F1xx/Include -I ../Drivers/CMSIS/Include -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include -D__UVISION_VERSION="541" -DSTM32F10X_MD -D_RTE_ -DUSE_HAL_DRIVER -DSTM32F103xB -o pressuresensorboard-slave\stm32f1xx_hal_gpio.o --omf_browse pressuresensorboard-slave\stm32f1xx_hal_gpio.crf --depend pressuresensorboard-slave\stm32f1xx_hal_gpio.d)
F (../Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_gpio.c)(0x68E72B55)(--c99 -c --cpu Cortex-M3 -D__MICROLIB -g -O3 --apcs=interwork --split_sections -I ../Core/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc/Legacy -I ../Drivers/CMSIS/Device/ST/STM32F1xx/Include -I ../Drivers/CMSIS/Include -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include -D__UVISION_VERSION="541" -DSTM32F10X_MD -D_RTE_ -DUSE_HAL_DRIVER -DSTM32F103xB -o pressuresensorboard-slave\stm32f1xx_hal_gpio.o --omf_browse pressuresensorboard-slave\stm32f1xx_hal_gpio.crf --depend pressuresensorboard-slave\stm32f1xx_hal_gpio.d)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal.h)(0x68E72B55)
I (../Core/Inc/stm32f1xx_hal_conf.h)(0x68E89462)
I (../Core/Inc/stm32f1xx_hal_conf.h)(0x68F195EE)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_rcc.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_def.h)(0x68E72B55)
I (../Drivers/CMSIS/Device/ST/STM32F1xx/Include/stm32f1xx.h)(0x68E72B55)
@ -411,9 +411,9 @@ I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash_ex.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_pwr.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_uart.h)(0x68E72B55)
F (../Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_dma.c)(0x68E72B55)(--c99 -c --cpu Cortex-M3 -g -O3 --apcs=interwork --split_sections -I ../Core/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc/Legacy -I ../Drivers/CMSIS/Device/ST/STM32F1xx/Include -I ../Drivers/CMSIS/Include -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include -D__UVISION_VERSION="541" -DSTM32F10X_MD -D_RTE_ -DUSE_HAL_DRIVER -DSTM32F103xB -o pressuresensorboard-slave\stm32f1xx_hal_dma.o --omf_browse pressuresensorboard-slave\stm32f1xx_hal_dma.crf --depend pressuresensorboard-slave\stm32f1xx_hal_dma.d)
F (../Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_dma.c)(0x68E72B55)(--c99 -c --cpu Cortex-M3 -D__MICROLIB -g -O3 --apcs=interwork --split_sections -I ../Core/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc/Legacy -I ../Drivers/CMSIS/Device/ST/STM32F1xx/Include -I ../Drivers/CMSIS/Include -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include -D__UVISION_VERSION="541" -DSTM32F10X_MD -D_RTE_ -DUSE_HAL_DRIVER -DSTM32F103xB -o pressuresensorboard-slave\stm32f1xx_hal_dma.o --omf_browse pressuresensorboard-slave\stm32f1xx_hal_dma.crf --depend pressuresensorboard-slave\stm32f1xx_hal_dma.d)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal.h)(0x68E72B55)
I (../Core/Inc/stm32f1xx_hal_conf.h)(0x68E89462)
I (../Core/Inc/stm32f1xx_hal_conf.h)(0x68F195EE)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_rcc.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_def.h)(0x68E72B55)
I (../Drivers/CMSIS/Device/ST/STM32F1xx/Include/stm32f1xx.h)(0x68E72B55)
@ -439,9 +439,9 @@ I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash_ex.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_pwr.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_uart.h)(0x68E72B55)
F (../Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_cortex.c)(0x68E72B55)(--c99 -c --cpu Cortex-M3 -g -O3 --apcs=interwork --split_sections -I ../Core/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc/Legacy -I ../Drivers/CMSIS/Device/ST/STM32F1xx/Include -I ../Drivers/CMSIS/Include -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include -D__UVISION_VERSION="541" -DSTM32F10X_MD -D_RTE_ -DUSE_HAL_DRIVER -DSTM32F103xB -o pressuresensorboard-slave\stm32f1xx_hal_cortex.o --omf_browse pressuresensorboard-slave\stm32f1xx_hal_cortex.crf --depend pressuresensorboard-slave\stm32f1xx_hal_cortex.d)
F (../Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_cortex.c)(0x68E72B55)(--c99 -c --cpu Cortex-M3 -D__MICROLIB -g -O3 --apcs=interwork --split_sections -I ../Core/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc/Legacy -I ../Drivers/CMSIS/Device/ST/STM32F1xx/Include -I ../Drivers/CMSIS/Include -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include -D__UVISION_VERSION="541" -DSTM32F10X_MD -D_RTE_ -DUSE_HAL_DRIVER -DSTM32F103xB -o pressuresensorboard-slave\stm32f1xx_hal_cortex.o --omf_browse pressuresensorboard-slave\stm32f1xx_hal_cortex.crf --depend pressuresensorboard-slave\stm32f1xx_hal_cortex.d)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal.h)(0x68E72B55)
I (../Core/Inc/stm32f1xx_hal_conf.h)(0x68E89462)
I (../Core/Inc/stm32f1xx_hal_conf.h)(0x68F195EE)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_rcc.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_def.h)(0x68E72B55)
I (../Drivers/CMSIS/Device/ST/STM32F1xx/Include/stm32f1xx.h)(0x68E72B55)
@ -467,9 +467,9 @@ I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash_ex.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_pwr.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_uart.h)(0x68E72B55)
F (../Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_pwr.c)(0x68E72B55)(--c99 -c --cpu Cortex-M3 -g -O3 --apcs=interwork --split_sections -I ../Core/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc/Legacy -I ../Drivers/CMSIS/Device/ST/STM32F1xx/Include -I ../Drivers/CMSIS/Include -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include -D__UVISION_VERSION="541" -DSTM32F10X_MD -D_RTE_ -DUSE_HAL_DRIVER -DSTM32F103xB -o pressuresensorboard-slave\stm32f1xx_hal_pwr.o --omf_browse pressuresensorboard-slave\stm32f1xx_hal_pwr.crf --depend pressuresensorboard-slave\stm32f1xx_hal_pwr.d)
F (../Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_pwr.c)(0x68E72B55)(--c99 -c --cpu Cortex-M3 -D__MICROLIB -g -O3 --apcs=interwork --split_sections -I ../Core/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc/Legacy -I ../Drivers/CMSIS/Device/ST/STM32F1xx/Include -I ../Drivers/CMSIS/Include -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include -D__UVISION_VERSION="541" -DSTM32F10X_MD -D_RTE_ -DUSE_HAL_DRIVER -DSTM32F103xB -o pressuresensorboard-slave\stm32f1xx_hal_pwr.o --omf_browse pressuresensorboard-slave\stm32f1xx_hal_pwr.crf --depend pressuresensorboard-slave\stm32f1xx_hal_pwr.d)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal.h)(0x68E72B55)
I (../Core/Inc/stm32f1xx_hal_conf.h)(0x68E89462)
I (../Core/Inc/stm32f1xx_hal_conf.h)(0x68F195EE)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_rcc.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_def.h)(0x68E72B55)
I (../Drivers/CMSIS/Device/ST/STM32F1xx/Include/stm32f1xx.h)(0x68E72B55)
@ -495,9 +495,9 @@ I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash_ex.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_pwr.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_uart.h)(0x68E72B55)
F (../Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_flash.c)(0x68E72B55)(--c99 -c --cpu Cortex-M3 -g -O3 --apcs=interwork --split_sections -I ../Core/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc/Legacy -I ../Drivers/CMSIS/Device/ST/STM32F1xx/Include -I ../Drivers/CMSIS/Include -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include -D__UVISION_VERSION="541" -DSTM32F10X_MD -D_RTE_ -DUSE_HAL_DRIVER -DSTM32F103xB -o pressuresensorboard-slave\stm32f1xx_hal_flash.o --omf_browse pressuresensorboard-slave\stm32f1xx_hal_flash.crf --depend pressuresensorboard-slave\stm32f1xx_hal_flash.d)
F (../Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_flash.c)(0x68E72B55)(--c99 -c --cpu Cortex-M3 -D__MICROLIB -g -O3 --apcs=interwork --split_sections -I ../Core/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc/Legacy -I ../Drivers/CMSIS/Device/ST/STM32F1xx/Include -I ../Drivers/CMSIS/Include -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include -D__UVISION_VERSION="541" -DSTM32F10X_MD -D_RTE_ -DUSE_HAL_DRIVER -DSTM32F103xB -o pressuresensorboard-slave\stm32f1xx_hal_flash.o --omf_browse pressuresensorboard-slave\stm32f1xx_hal_flash.crf --depend pressuresensorboard-slave\stm32f1xx_hal_flash.d)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal.h)(0x68E72B55)
I (../Core/Inc/stm32f1xx_hal_conf.h)(0x68E89462)
I (../Core/Inc/stm32f1xx_hal_conf.h)(0x68F195EE)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_rcc.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_def.h)(0x68E72B55)
I (../Drivers/CMSIS/Device/ST/STM32F1xx/Include/stm32f1xx.h)(0x68E72B55)
@ -523,9 +523,9 @@ I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash_ex.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_pwr.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_uart.h)(0x68E72B55)
F (../Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_flash_ex.c)(0x68E72B55)(--c99 -c --cpu Cortex-M3 -g -O3 --apcs=interwork --split_sections -I ../Core/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc/Legacy -I ../Drivers/CMSIS/Device/ST/STM32F1xx/Include -I ../Drivers/CMSIS/Include -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include -D__UVISION_VERSION="541" -DSTM32F10X_MD -D_RTE_ -DUSE_HAL_DRIVER -DSTM32F103xB -o pressuresensorboard-slave\stm32f1xx_hal_flash_ex.o --omf_browse pressuresensorboard-slave\stm32f1xx_hal_flash_ex.crf --depend pressuresensorboard-slave\stm32f1xx_hal_flash_ex.d)
F (../Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_flash_ex.c)(0x68E72B55)(--c99 -c --cpu Cortex-M3 -D__MICROLIB -g -O3 --apcs=interwork --split_sections -I ../Core/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc/Legacy -I ../Drivers/CMSIS/Device/ST/STM32F1xx/Include -I ../Drivers/CMSIS/Include -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include -D__UVISION_VERSION="541" -DSTM32F10X_MD -D_RTE_ -DUSE_HAL_DRIVER -DSTM32F103xB -o pressuresensorboard-slave\stm32f1xx_hal_flash_ex.o --omf_browse pressuresensorboard-slave\stm32f1xx_hal_flash_ex.crf --depend pressuresensorboard-slave\stm32f1xx_hal_flash_ex.d)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal.h)(0x68E72B55)
I (../Core/Inc/stm32f1xx_hal_conf.h)(0x68E89462)
I (../Core/Inc/stm32f1xx_hal_conf.h)(0x68F195EE)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_rcc.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_def.h)(0x68E72B55)
I (../Drivers/CMSIS/Device/ST/STM32F1xx/Include/stm32f1xx.h)(0x68E72B55)
@ -551,9 +551,9 @@ I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash_ex.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_pwr.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_uart.h)(0x68E72B55)
F (../Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_exti.c)(0x68E72B55)(--c99 -c --cpu Cortex-M3 -g -O3 --apcs=interwork --split_sections -I ../Core/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc/Legacy -I ../Drivers/CMSIS/Device/ST/STM32F1xx/Include -I ../Drivers/CMSIS/Include -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include -D__UVISION_VERSION="541" -DSTM32F10X_MD -D_RTE_ -DUSE_HAL_DRIVER -DSTM32F103xB -o pressuresensorboard-slave\stm32f1xx_hal_exti.o --omf_browse pressuresensorboard-slave\stm32f1xx_hal_exti.crf --depend pressuresensorboard-slave\stm32f1xx_hal_exti.d)
F (../Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_exti.c)(0x68E72B55)(--c99 -c --cpu Cortex-M3 -D__MICROLIB -g -O3 --apcs=interwork --split_sections -I ../Core/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc/Legacy -I ../Drivers/CMSIS/Device/ST/STM32F1xx/Include -I ../Drivers/CMSIS/Include -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include -D__UVISION_VERSION="541" -DSTM32F10X_MD -D_RTE_ -DUSE_HAL_DRIVER -DSTM32F103xB -o pressuresensorboard-slave\stm32f1xx_hal_exti.o --omf_browse pressuresensorboard-slave\stm32f1xx_hal_exti.crf --depend pressuresensorboard-slave\stm32f1xx_hal_exti.d)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal.h)(0x68E72B55)
I (../Core/Inc/stm32f1xx_hal_conf.h)(0x68E89462)
I (../Core/Inc/stm32f1xx_hal_conf.h)(0x68F195EE)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_rcc.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_def.h)(0x68E72B55)
I (../Drivers/CMSIS/Device/ST/STM32F1xx/Include/stm32f1xx.h)(0x68E72B55)
@ -579,9 +579,9 @@ I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash_ex.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_pwr.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_uart.h)(0x68E72B55)
F (../Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_uart.c)(0x68E72B55)(--c99 -c --cpu Cortex-M3 -g -O3 --apcs=interwork --split_sections -I ../Core/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc/Legacy -I ../Drivers/CMSIS/Device/ST/STM32F1xx/Include -I ../Drivers/CMSIS/Include -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include -D__UVISION_VERSION="541" -DSTM32F10X_MD -D_RTE_ -DUSE_HAL_DRIVER -DSTM32F103xB -o pressuresensorboard-slave\stm32f1xx_hal_uart.o --omf_browse pressuresensorboard-slave\stm32f1xx_hal_uart.crf --depend pressuresensorboard-slave\stm32f1xx_hal_uart.d)
F (../Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_uart.c)(0x68E72B55)(--c99 -c --cpu Cortex-M3 -D__MICROLIB -g -O3 --apcs=interwork --split_sections -I ../Core/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc/Legacy -I ../Drivers/CMSIS/Device/ST/STM32F1xx/Include -I ../Drivers/CMSIS/Include -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include -D__UVISION_VERSION="541" -DSTM32F10X_MD -D_RTE_ -DUSE_HAL_DRIVER -DSTM32F103xB -o pressuresensorboard-slave\stm32f1xx_hal_uart.o --omf_browse pressuresensorboard-slave\stm32f1xx_hal_uart.crf --depend pressuresensorboard-slave\stm32f1xx_hal_uart.d)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal.h)(0x68E72B55)
I (../Core/Inc/stm32f1xx_hal_conf.h)(0x68E89462)
I (../Core/Inc/stm32f1xx_hal_conf.h)(0x68F195EE)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_rcc.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_def.h)(0x68E72B55)
I (../Drivers/CMSIS/Device/ST/STM32F1xx/Include/stm32f1xx.h)(0x68E72B55)
@ -607,7 +607,7 @@ I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_flash_ex.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_pwr.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_uart.h)(0x68E72B55)
F (../Core/Src/system_stm32f1xx.c)(0x68E72B55)(--c99 -c --cpu Cortex-M3 -g -O3 --apcs=interwork --split_sections -I ../Core/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc/Legacy -I ../Drivers/CMSIS/Device/ST/STM32F1xx/Include -I ../Drivers/CMSIS/Include -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include -D__UVISION_VERSION="541" -DSTM32F10X_MD -D_RTE_ -DUSE_HAL_DRIVER -DSTM32F103xB -o pressuresensorboard-slave\system_stm32f1xx.o --omf_browse pressuresensorboard-slave\system_stm32f1xx.crf --depend pressuresensorboard-slave\system_stm32f1xx.d)
F (../Core/Src/system_stm32f1xx.c)(0x68E72B55)(--c99 -c --cpu Cortex-M3 -D__MICROLIB -g -O3 --apcs=interwork --split_sections -I ../Core/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc -I ../Drivers/STM32F1xx_HAL_Driver/Inc/Legacy -I ../Drivers/CMSIS/Device/ST/STM32F1xx/Include -I ../Drivers/CMSIS/Include -I.\RTE\_PressureSensorBoard-slave -IC:\app\Keil_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Keil\STM32F1xx_DFP\2.4.1\Device\Include -D__UVISION_VERSION="541" -DSTM32F10X_MD -D_RTE_ -DUSE_HAL_DRIVER -DSTM32F103xB -o pressuresensorboard-slave\system_stm32f1xx.o --omf_browse pressuresensorboard-slave\system_stm32f1xx.crf --depend pressuresensorboard-slave\system_stm32f1xx.d)
I (../Drivers/CMSIS/Device/ST/STM32F1xx/Include/stm32f1xx.h)(0x68E72B55)
I (../Drivers/CMSIS/Device/ST/STM32F1xx/Include/stm32f103xb.h)(0x68E72B55)
I (../Drivers/CMSIS/Include/core_cm3.h)(0x68E72B29)
@ -617,7 +617,7 @@ I (../Drivers/CMSIS/Include/cmsis_compiler.h)(0x68E72B29)
I (../Drivers/CMSIS/Include/cmsis_armcc.h)(0x68E72B29)
I (../Drivers/CMSIS/Device/ST/STM32F1xx/Include/system_stm32f1xx.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal.h)(0x68E72B55)
I (../Core/Inc/stm32f1xx_hal_conf.h)(0x68E89462)
I (../Core/Inc/stm32f1xx_hal_conf.h)(0x68F195EE)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_rcc.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_def.h)(0x68E72B55)
I (../Drivers/STM32F1xx_HAL_Driver/Inc/Legacy/stm32_hal_legacy.h)(0x68E72B55)

View File

@ -32,5 +32,5 @@ pressuresensorboard-slave\main.o: ../Core/Inc/adc.h
pressuresensorboard-slave\main.o: ../Core/Inc/dma.h
pressuresensorboard-slave\main.o: ../Core/Inc/usart.h
pressuresensorboard-slave\main.o: ../Core/Inc/gpio.h
pressuresensorboard-slave\main.o: C:\app\Keil_v5\ARM\ARMCC\Bin\..\include\string.h
pressuresensorboard-slave\main.o: C:\app\Keil_v5\ARM\ARMCC\Bin\..\include\stdio.h
pressuresensorboard-slave\main.o: C:\app\Keil_v5\ARM\ARMCC\Bin\..\include\string.h

View File

@ -214,9 +214,9 @@ ARM Macro Assembler Page 4
]
130 00000000 IMPORT __main
131 00000000 IMPORT SystemInit
132 00000000 4809 LDR R0, =SystemInit
132 00000000 4806 LDR R0, =SystemInit
133 00000002 4780 BLX R0
134 00000004 4809 LDR R0, =__main
134 00000004 4806 LDR R0, =__main
135 00000006 4700 BX R0
136 00000008 ENDP
137 00000008
@ -442,42 +442,30 @@ ARM Macro Assembler Page 7
280 0000001C ;*******************************************************
************************
281 0000001C IF :DEF:__MICROLIB
288 0000001C
289 0000001C IMPORT __use_two_region_memory
290 0000001C EXPORT __user_initial_stackheap
291 0000001C
292 0000001C __user_initial_stackheap
293 0000001C
294 0000001C 4804 LDR R0, = Heap_Mem
295 0000001E 4905 LDR R1, =(Stack_Mem + Stack_Size)
296 00000020 4A05 LDR R2, = (Heap_Mem + Heap_Size)
297 00000022 4B06 LDR R3, = Stack_Mem
298 00000024 4770 BX LR
282 0000001C
283 0000001C EXPORT __initial_sp
284 0000001C EXPORT __heap_base
285 0000001C EXPORT __heap_limit
286 0000001C
287 0000001C ELSE
302 ENDIF
303 0000001C
304 0000001C END
00000000
00000000
ARM Macro Assembler Page 8
299 00000026
300 00000026 00 00 ALIGN
301 00000028
302 00000028 ENDIF
303 00000028
304 00000028 END
00000000
00000000
00000000
00000400
00000200
00000000
Command Line: --debug --xref --diag_suppress=9931 --cpu=Cortex-M3 --apcs=interw
ork --depend=pressuresensorboard-slave\startup_stm32f103xb.d -opressuresensorbo
ard-slave\startup_stm32f103xb.o -I.\RTE\_PressureSensorBoard-slave -IC:\app\Kei
l_v5\ARM\Packs\ARM\CMSIS\6.1.0\CMSIS\Core\Include -IC:\app\Keil_v5\ARM\Packs\Ke
il\STM32F1xx_DFP\2.4.1\Device\Include --predefine="__UVISION_VERSION SETA 541"
--predefine="STM32F10X_MD SETA 1" --predefine="_RTE_ SETA 1" --list=startup_stm
32f103xb.lst startup_stm32f103xb.s
il\STM32F1xx_DFP\2.4.1\Device\Include --predefine="__MICROLIB SETA 1" --predefi
ne="__UVISION_VERSION SETA 541" --predefine="STM32F10X_MD SETA 1" --predefine="
_RTE_ SETA 1" --list=startup_stm32f103xb.lst startup_stm32f103xb.s
@ -498,9 +486,8 @@ Symbol: Stack_Mem
Definitions
At line 35 in file startup_stm32f103xb.s
Uses
At line 295 in file startup_stm32f103xb.s
At line 297 in file startup_stm32f103xb.s
None
Comment: Stack_Mem unused
__initial_sp 00000400
Symbol: __initial_sp
@ -508,7 +495,8 @@ Symbol: __initial_sp
At line 36 in file startup_stm32f103xb.s
Uses
At line 60 in file startup_stm32f103xb.s
Comment: __initial_sp used once
At line 283 in file startup_stm32f103xb.s
3 symbols
@ -530,25 +518,24 @@ Symbol: Heap_Mem
Definitions
At line 47 in file startup_stm32f103xb.s
Uses
At line 294 in file startup_stm32f103xb.s
At line 296 in file startup_stm32f103xb.s
None
Comment: Heap_Mem unused
__heap_base 00000000
Symbol: __heap_base
Definitions
At line 46 in file startup_stm32f103xb.s
Uses
None
Comment: __heap_base unused
At line 284 in file startup_stm32f103xb.s
Comment: __heap_base used once
__heap_limit 00000200
Symbol: __heap_limit
Definitions
At line 48 in file startup_stm32f103xb.s
Uses
None
Comment: __heap_limit unused
At line 285 in file startup_stm32f103xb.s
Comment: __heap_limit used once
4 symbols
@ -1130,15 +1117,7 @@ Symbol: WWDG_IRQHandler
At line 78 in file startup_stm32f103xb.s
At line 184 in file startup_stm32f103xb.s
__user_initial_stackheap 0000001C
Symbol: __user_initial_stackheap
Definitions
At line 292 in file startup_stm32f103xb.s
Uses
At line 290 in file startup_stm32f103xb.s
Comment: __user_initial_stackheap used once
56 symbols
55 symbols
@ -1152,8 +1131,7 @@ Symbol: Heap_Size
At line 43 in file startup_stm32f103xb.s
Uses
At line 47 in file startup_stm32f103xb.s
At line 296 in file startup_stm32f103xb.s
Comment: Heap_Size used once
Stack_Size 00000400
Symbol: Stack_Size
@ -1161,8 +1139,7 @@ Symbol: Stack_Size
At line 32 in file startup_stm32f103xb.s
Uses
At line 35 in file startup_stm32f103xb.s
At line 295 in file startup_stm32f103xb.s
Comment: Stack_Size used once
__Vectors_Size 000000EC
Symbol: __Vectors_Size
@ -1194,13 +1171,5 @@ Symbol: __main
Uses
At line 134 in file startup_stm32f103xb.s
Comment: __main used once
__use_two_region_memory 00000000
Symbol: __use_two_region_memory
Definitions
At line 289 in file startup_stm32f103xb.s
Uses
None
Comment: __use_two_region_memory unused
3 symbols
409 symbols in table
2 symbols
406 symbols in table

View File

@ -16,24 +16,24 @@ ADC1.Rank-3\#ChannelRegularConversion=3
ADC1.Rank-4\#ChannelRegularConversion=4
ADC1.Rank-5\#ChannelRegularConversion=5
ADC1.Rank-6\#ChannelRegularConversion=6
ADC1.SamplingTime-1\#ChannelRegularConversion=ADC_SAMPLETIME_55CYCLES_5
ADC1.SamplingTime-2\#ChannelRegularConversion=ADC_SAMPLETIME_55CYCLES_5
ADC1.SamplingTime-3\#ChannelRegularConversion=ADC_SAMPLETIME_55CYCLES_5
ADC1.SamplingTime-4\#ChannelRegularConversion=ADC_SAMPLETIME_55CYCLES_5
ADC1.SamplingTime-5\#ChannelRegularConversion=ADC_SAMPLETIME_55CYCLES_5
ADC1.SamplingTime-6\#ChannelRegularConversion=ADC_SAMPLETIME_55CYCLES_5
ADC1.SamplingTime-1\#ChannelRegularConversion=ADC_SAMPLETIME_7CYCLES_5
ADC1.SamplingTime-2\#ChannelRegularConversion=ADC_SAMPLETIME_7CYCLES_5
ADC1.SamplingTime-3\#ChannelRegularConversion=ADC_SAMPLETIME_7CYCLES_5
ADC1.SamplingTime-4\#ChannelRegularConversion=ADC_SAMPLETIME_7CYCLES_5
ADC1.SamplingTime-5\#ChannelRegularConversion=ADC_SAMPLETIME_7CYCLES_5
ADC1.SamplingTime-6\#ChannelRegularConversion=ADC_SAMPLETIME_7CYCLES_5
ADC1.master=1
CAD.formats=[]
CAD.pinconfig=Dual
CAD.provider=
Dma.ADC1.0.Direction=DMA_PERIPH_TO_MEMORY
Dma.ADC1.0.Instance=DMA1_Channel1
Dma.ADC1.0.MemDataAlignment=DMA_MDATAALIGN_HALFWORD
Dma.ADC1.0.MemDataAlignment=DMA_MDATAALIGN_WORD
Dma.ADC1.0.MemInc=DMA_MINC_ENABLE
Dma.ADC1.0.Mode=DMA_CIRCULAR
Dma.ADC1.0.PeriphDataAlignment=DMA_PDATAALIGN_HALFWORD
Dma.ADC1.0.Mode=DMA_NORMAL
Dma.ADC1.0.PeriphDataAlignment=DMA_PDATAALIGN_WORD
Dma.ADC1.0.PeriphInc=DMA_PINC_DISABLE
Dma.ADC1.0.Priority=DMA_PRIORITY_HIGH
Dma.ADC1.0.Priority=DMA_PRIORITY_MEDIUM
Dma.ADC1.0.RequestParameters=Instance,Direction,PeriphInc,MemInc,PeriphDataAlignment,MemDataAlignment,Mode,Priority
Dma.Request0=ADC1
Dma.RequestsNb=1
@ -51,25 +51,27 @@ Mcu.IP5=USART1
Mcu.IPNb=6
Mcu.Name=STM32F103C(8-B)Tx
Mcu.Package=LQFP48
Mcu.Pin0=PA0-WKUP
Mcu.Pin1=PA1
Mcu.Pin10=PA13
Mcu.Pin11=PA14
Mcu.Pin12=PA15
Mcu.Pin13=PB3
Mcu.Pin14=PB4
Mcu.Pin15=PB5
Mcu.Pin16=PB6
Mcu.Pin17=VP_SYS_VS_Systick
Mcu.Pin2=PA2
Mcu.Pin3=PA3
Mcu.Pin4=PA4
Mcu.Pin5=PA5
Mcu.Pin6=PB12
Mcu.Pin7=PB13
Mcu.Pin8=PA9
Mcu.Pin9=PA10
Mcu.PinsNb=18
Mcu.Pin0=PD0-OSC_IN
Mcu.Pin1=PD1-OSC_OUT
Mcu.Pin10=PA9
Mcu.Pin11=PA10
Mcu.Pin12=PA13
Mcu.Pin13=PA14
Mcu.Pin14=PA15
Mcu.Pin15=PB3
Mcu.Pin16=PB4
Mcu.Pin17=PB5
Mcu.Pin18=PB6
Mcu.Pin19=VP_SYS_VS_Systick
Mcu.Pin2=PA0-WKUP
Mcu.Pin3=PA1
Mcu.Pin4=PA2
Mcu.Pin5=PA3
Mcu.Pin6=PA4
Mcu.Pin7=PA5
Mcu.Pin8=PB12
Mcu.Pin9=PB13
Mcu.PinsNb=20
Mcu.ThirdPartyNb=0
Mcu.UserConstants=
Mcu.UserName=STM32F103C8Tx
@ -133,12 +135,15 @@ PB5.GPIO_Speed=GPIO_SPEED_FREQ_HIGH
PB5.Locked=true
PB5.PinState=GPIO_PIN_RESET
PB5.Signal=GPIO_Output
PB6.GPIOParameters=GPIO_Speed,PinState,GPIO_Label
PB6.GPIOParameters=PinState,GPIO_Label
PB6.GPIO_Label=SW5
PB6.GPIO_Speed=GPIO_SPEED_FREQ_HIGH
PB6.Locked=true
PB6.PinState=GPIO_PIN_RESET
PB6.Signal=GPIO_Output
PD0-OSC_IN.Mode=HSE-External-Oscillator
PD0-OSC_IN.Signal=RCC_OSC_IN
PD1-OSC_OUT.Mode=HSE-External-Oscillator
PD1-OSC_OUT.Signal=RCC_OSC_OUT
PinOutPanel.RotationAngle=0
ProjectManager.AskForMigrate=true
ProjectManager.BackupPrevious=false
@ -172,28 +177,28 @@ ProjectManager.UAScriptAfterPath=
ProjectManager.UAScriptBeforePath=
ProjectManager.UnderRoot=false
ProjectManager.functionlistsort=1-SystemClock_Config-RCC-false-HAL-false,2-MX_GPIO_Init-GPIO-false-HAL-true,3-MX_DMA_Init-DMA-false-HAL-true,4-MX_ADC1_Init-ADC1-false-HAL-true,5-MX_USART1_UART_Init-USART1-false-HAL-true
RCC.ADCFreqValue=8000000
RCC.ADCPresc=RCC_ADCPCLK2_DIV4
RCC.AHBFreq_Value=64000000
RCC.ADCFreqValue=12000000
RCC.ADCPresc=RCC_ADCPCLK2_DIV6
RCC.AHBFreq_Value=72000000
RCC.APB1CLKDivider=RCC_HCLK_DIV2
RCC.APB1Freq_Value=32000000
RCC.APB1TimFreq_Value=64000000
RCC.APB2CLKDivider=RCC_HCLK_DIV2
RCC.APB2Freq_Value=32000000
RCC.APB2TimFreq_Value=64000000
RCC.FCLKCortexFreq_Value=64000000
RCC.APB1Freq_Value=36000000
RCC.APB1TimFreq_Value=72000000
RCC.APB2Freq_Value=72000000
RCC.APB2TimFreq_Value=72000000
RCC.FCLKCortexFreq_Value=72000000
RCC.FamilyName=M
RCC.HCLKFreq_Value=64000000
RCC.IPParameters=ADCFreqValue,ADCPresc,AHBFreq_Value,APB1CLKDivider,APB1Freq_Value,APB1TimFreq_Value,APB2CLKDivider,APB2Freq_Value,APB2TimFreq_Value,FCLKCortexFreq_Value,FamilyName,HCLKFreq_Value,MCOFreq_Value,PLLCLKFreq_Value,PLLMCOFreq_Value,PLLMUL,SYSCLKFreq_VALUE,SYSCLKSource,TimSysFreq_Value,USBFreq_Value,VCOOutput2Freq_Value
RCC.MCOFreq_Value=64000000
RCC.PLLCLKFreq_Value=64000000
RCC.PLLMCOFreq_Value=32000000
RCC.PLLMUL=RCC_PLL_MUL16
RCC.SYSCLKFreq_VALUE=64000000
RCC.HCLKFreq_Value=72000000
RCC.IPParameters=ADCFreqValue,ADCPresc,AHBFreq_Value,APB1CLKDivider,APB1Freq_Value,APB1TimFreq_Value,APB2Freq_Value,APB2TimFreq_Value,FCLKCortexFreq_Value,FamilyName,HCLKFreq_Value,MCOFreq_Value,PLLCLKFreq_Value,PLLMCOFreq_Value,PLLMUL,PLLSourceVirtual,SYSCLKFreq_VALUE,SYSCLKSource,TimSysFreq_Value,USBFreq_Value,VCOOutput2Freq_Value
RCC.MCOFreq_Value=72000000
RCC.PLLCLKFreq_Value=72000000
RCC.PLLMCOFreq_Value=36000000
RCC.PLLMUL=RCC_PLL_MUL9
RCC.PLLSourceVirtual=RCC_PLLSOURCE_HSE
RCC.SYSCLKFreq_VALUE=72000000
RCC.SYSCLKSource=RCC_SYSCLKSOURCE_PLLCLK
RCC.TimSysFreq_Value=64000000
RCC.USBFreq_Value=64000000
RCC.VCOOutput2Freq_Value=4000000
RCC.TimSysFreq_Value=72000000
RCC.USBFreq_Value=72000000
RCC.VCOOutput2Freq_Value=8000000
SH.ADCx_IN0.0=ADC1_IN0,IN0
SH.ADCx_IN0.ConfNb=1
SH.ADCx_IN1.0=ADC1_IN1,IN1

Binary file not shown.