STM32使用Modbus协议读取温湿度

前言

  • 软件版本
    STM32CubeMX 6.4 0
    Keil 531

  • 硬件
    STM32F103C8T6
    AHT20温湿度传感器

题目要求

用stm32最小核心板+AHT20模块,完成一个 modbus接口的温湿度Slave设备,能够让上位机PC通过modbus协议获取温湿度。主程序采用多任务框架,比如RT-thread Nano。

1 移植RT-Thread

1.1 CubeMX 安装Nano pack

官方下载参考
https://www.rt-thread.org/document/site/#/rt-thread-version/rt-thread-nano/nano-port-cube/an0041-nano-port-cube

  1. 获取软件包地址
    要获取 RT-Thread Nano 软件包,需要在 CubeMX 中添加
    https://www.rt-thread.org/download/cube/RealThread.RT-Thread.pdsc
  2. 打开 CubeMX,从菜单栏 help 进入 Manage embedded software packages 界面,点击 From Url 按钮,进入 User Defined Packs Manager 界面,其次点击 new,填入上述网址,然后点击 check.
    在这里插入图片描述
  3. 下载安装完成后如下,前面的勾选框变为绿色
    在这里插入图片描述

1.2 CubeMX创建项目

  1. 选择Nano组件
    点击 Softwares Packages->Select Components,进入组件配置界面
    在这里插入图片描述
    选择RealThread, 然后根3.1.5版本的,然后点击 OK
    在这里插入图片描述
    这时会新增Software Packs展开就可以看见添加的RealThread.RT_Thread,勾选相应内容
    在这里插入图片描述

  2. RCC配置
    在这里插入图片描述

  3. SYS配置
    在这里插入图片描述

  4. USART1
    在这里插入图片描述

  5. NVIC选择
    在这里插入图片描述
    RT-Thread 操作系统重定义 HardFault_HandlerPendSV_HandlerSysTick_Handler 中断函数,为了避免重复定义的问题,在生成工程之前,需要在中断配置中,代码生成的选项中,取消选择三个中断函数

  6. GPIO
    选择B15作为指示灯

  7. 时钟配置
    在这里插入图片描述

2 Keil修改代码

AHT20采集详细代码见之前博客
https://blog.csdn.net/apple_52030329/article/details/127854432

2.1 添加文件

在Cube生成项目的文件夹下,在MDK-ARM文件夹下建立AHT文件夹,并在该文件夹下,添加如下文件

在这里插入图片描述

在项目中添加文件

在这里插入图片描述
在这里插入图片描述

2.2 移植freeModusRTU

下载链接:https://github.com/cwalter-at/freemodbus

解压并打开刚刚下载的文件,点进demo里,新建一个STM32MB文件夹

在这里插入图片描述

将BARE文件夹里的文件全部复制到刚刚建立的STM32MB文件夹里
再把modbus文件夹全部复制到刚刚新建的STM32MB文件夹,到最后的结果如下图:

在这里插入图片描述

打开MDK-ARM文件夹,将STM32MB文件复制到这里

在这里插入图片描述

新建名为MB和MB_Port的组,MB内添加STM32MB文件夹下modbus文件夹内所有.c文件,MB_Port内添加STM32MB文件夹下port文件夹内所有.c文件以及根目录的demo.c文件:

在这里插入图片描述

在这里插入图片描述

添加头文件路径

在这里插入图片描述

2.3 修改代码

portserial.c

#include "port.h"

/* ----------------------- Modbus includes ----------------------------------*/
#include "mb.h"
#include "mbport.h"
#include "usart.h"

/* ----------------------- static functions ---------------------------------*/
void prvvUARTTxReadyISR( void );
void prvvUARTRxISR( void );

/* ----------------------- Start implementation -----------------------------*/
void
vMBPortSerialEnable( BOOL xRxEnable, BOOL xTxEnable )
{
    
    
    /* If xRXEnable enable serial receive interrupts. If xTxENable enable
     * transmitter empty interrupts.
     */
	 if (xRxEnable)															//将串口收发中断和modbus联系起来,下面的串口改为自己使能的串口
			{
    
    
				__HAL_UART_ENABLE_IT(&huart1,UART_IT_RXNE);	//我用的是串口1,故为&huart1
			}
		else
			{
    
    
				__HAL_UART_DISABLE_IT(&huart1,UART_IT_RXNE);
			}
		if (xTxEnable)
			{
    
    
				__HAL_UART_ENABLE_IT(&huart1,UART_IT_TXE);
			}
		else
			{
    
    
				__HAL_UART_DISABLE_IT(&huart1,UART_IT_TXE);
			}	
}

BOOL
xMBPortSerialInit( UCHAR ucPORT, ULONG ulBaudRate, UCHAR ucDataBits, eMBParity eParity )
{
    
    
    return TRUE;
}

BOOL
xMBPortSerialPutByte( CHAR ucByte )
{
    
    
    /* Put a byte in the UARTs transmit buffer. This function is called
     * by the protocol stack if pxMBFrameCBTransmitterEmpty( ) has been
     * called. */
	if(HAL_UART_Transmit (&huart1 ,(uint8_t *)&ucByte,1,0x01) != HAL_OK )	//添加发送一位代码
			   return FALSE ;
			else
    return TRUE;
}

BOOL
xMBPortSerialGetByte( CHAR * pucByte )
{
    
    
    /* Return the byte in the UARTs receive buffer. This function is called
     * by the protocol stack after pxMBFrameCBByteReceived( ) has been called.
     */
	if(HAL_UART_Receive (&huart1 ,(uint8_t *)pucByte,1,0x01) != HAL_OK )//添加接收一位代码
			    return FALSE ;
	   else
    return TRUE;
}

/* Create an interrupt handler for the transmit buffer empty interrupt
 * (or an equivalent) for your target processor. This function should then
 * call pxMBFrameCBTransmitterEmpty( ) which tells the protocol stack that
 * a new character can be sent. The protocol stack will then call 
 * xMBPortSerialPutByte( ) to send the character.
 */
void prvvUARTTxReadyISR( void )
{
    
    
    pxMBFrameCBTransmitterEmpty(  );
}

/* Create an interrupt handler for the receive interrupt for your target
 * processor. This function should then call pxMBFrameCBByteReceived( ). The
 * protocol stack will then call xMBPortSerialGetByte( ) to retrieve the
 * character.
 */
void prvvUARTRxISR( void )
{
    
    
    pxMBFrameCBByteReceived(  );
}

porttimer.c

/*
 * FreeModbus Libary: BARE Port
 * Copyright (C) 2006 Christian Walter <[email protected]>
 *
 * This library is free software; you can redistribute it and/or
 * modify it under the terms of the GNU Lesser General Public
 * License as published by the Free Software Foundation; either
 * version 2.1 of the License, or (at your option) any later version.
 *
 * This library is distributed in the hope that it will be useful,
 * but WITHOUT ANY WARRANTY; without even the implied warranty of
 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
 * Lesser General Public License for more details.
 *
 * You should have received a copy of the GNU Lesser General Public
 * License along with this library; if not, write to the Free Software
 * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
 *
 * File: $Id$
 */

/* ----------------------- Platform includes --------------------------------*/
#include "port.h"
#include "stm32f1xx_hal.h"
#include "tim.h"
/* ----------------------- Modbus includes ----------------------------------*/
#include "mb.h"
#include "mbport.h"

/* ----------------------- static functions ---------------------------------*/
void prvvTIMERExpiredISR( void );

/* ----------------------- Start implementation -----------------------------*/
BOOL
xMBPortTimersInit( USHORT usTim1Timerout50us )//定时器初始化直接返回TRUE,已经在mian函数初始化过
{
    
    
    return  TRUE;
}


inline void
vMBPortTimersEnable(  )//使能定时器中断,我用的是定时器4,所以为&htim4
{
    
    
    /* Enable the timer with the timeout passed to xMBPortTimersInit( ) */
				 /* Enable the timer with the timeout passed to xMBPortTimersInit( ) */
		__HAL_TIM_CLEAR_IT(&htim3,TIM_IT_UPDATE);
		__HAL_TIM_ENABLE_IT(&htim3,TIM_IT_UPDATE);
		__HAL_TIM_SET_COUNTER(&htim3,0);
		__HAL_TIM_ENABLE(&htim3);
}

inline void
vMBPortTimersDisable(  )//取消定时器中断
{
    
    
    /* Disable any pending timers. */
	__HAL_TIM_DISABLE(&htim3);
			__HAL_TIM_SET_COUNTER(&htim3,0);
			__HAL_TIM_DISABLE_IT(&htim3,TIM_IT_UPDATE);
			__HAL_TIM_CLEAR_IT(&htim3,TIM_IT_UPDATE);

}

/* Create an ISR which is called whenever the timer has expired. This function
 * must then call pxMBPortCBTimerExpired( ) to notify the protocol stack that
 * the timer has expired.
 */
void prvvTIMERExpiredISR( void )//modbus定时器动作,需要在中断内使用
{
    
    
    ( void )pxMBPortCBTimerExpired(  );
}

stm32f1xx_it.c

/* USER CODE BEGIN Header */
/**
  ******************************************************************************
  * @file    stm32f1xx_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 "stm32f1xx_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 */
extern void prvvUARTTxReadyISR(void);
extern void prvvUARTRxISR(void);
extern void prvvTIMERExpiredISR( void );

/* USER CODE END PFP */

/* Private user code ---------------------------------------------------------*/
/* USER CODE BEGIN 0 */

/* USER CODE END 0 */

/* External variables --------------------------------------------------------*/
extern DMA_HandleTypeDef hdma_i2c1_rx;
extern DMA_HandleTypeDef hdma_i2c1_tx;
extern I2C_HandleTypeDef hi2c1;
extern TIM_HandleTypeDef htim3;
extern UART_HandleTypeDef huart1;
/* USER CODE BEGIN EV */

/* USER CODE END EV */

/******************************************************************************/
/*           Cortex-M3 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 Memory management fault.
  */
void MemManage_Handler(void)
{
    
    
  /* USER CODE BEGIN MemoryManagement_IRQn 0 */

  /* USER CODE END MemoryManagement_IRQn 0 */
  while (1)
  {
    
    
    /* USER CODE BEGIN W1_MemoryManagement_IRQn 0 */
    /* USER CODE END W1_MemoryManagement_IRQn 0 */
  }
}

/**
  * @brief This function handles Prefetch fault, memory access fault.
  */
void BusFault_Handler(void)
{
    
    
  /* USER CODE BEGIN BusFault_IRQn 0 */

  /* USER CODE END BusFault_IRQn 0 */
  while (1)
  {
    
    
    /* USER CODE BEGIN W1_BusFault_IRQn 0 */
    /* USER CODE END W1_BusFault_IRQn 0 */
  }
}

/**
  * @brief This function handles Undefined instruction or illegal state.
  */
void UsageFault_Handler(void)
{
    
    
  /* USER CODE BEGIN UsageFault_IRQn 0 */

  /* USER CODE END UsageFault_IRQn 0 */
  while (1)
  {
    
    
    /* USER CODE BEGIN W1_UsageFault_IRQn 0 */
    /* USER CODE END W1_UsageFault_IRQn 0 */
  }
}

/**
  * @brief This function handles Debug monitor.
  */
void DebugMon_Handler(void)
{
    
    
  /* USER CODE BEGIN DebugMonitor_IRQn 0 */

  /* USER CODE END DebugMonitor_IRQn 0 */
  /* USER CODE BEGIN DebugMonitor_IRQn 1 */

  /* USER CODE END DebugMonitor_IRQn 1 */
}

/******************************************************************************/
/* STM32F1xx 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_stm32f1xx.s).                    */
/******************************************************************************/

/**
  * @brief This function handles DMA1 channel6 global interrupt.
  */
void DMA1_Channel6_IRQHandler(void)
{
    
    
  /* USER CODE BEGIN DMA1_Channel6_IRQn 0 */

  /* USER CODE END DMA1_Channel6_IRQn 0 */
  HAL_DMA_IRQHandler(&hdma_i2c1_tx);
  /* USER CODE BEGIN DMA1_Channel6_IRQn 1 */

  /* USER CODE END DMA1_Channel6_IRQn 1 */
}

/**
  * @brief This function handles DMA1 channel7 global interrupt.
  */
void DMA1_Channel7_IRQHandler(void)
{
    
    
  /* USER CODE BEGIN DMA1_Channel7_IRQn 0 */

  /* USER CODE END DMA1_Channel7_IRQn 0 */
  HAL_DMA_IRQHandler(&hdma_i2c1_rx);
  /* USER CODE BEGIN DMA1_Channel7_IRQn 1 */

  /* USER CODE END DMA1_Channel7_IRQn 1 */
}

/**
  * @brief This function handles TIM3 global interrupt.
  */
void TIM3_IRQHandler(void)
{
    
    
  /* USER CODE BEGIN TIM3_IRQn 0 */

  /* USER CODE END TIM3_IRQn 0 */
  HAL_TIM_IRQHandler(&htim3);
  /* USER CODE BEGIN TIM3_IRQn 1 */

  /* USER CODE END TIM3_IRQn 1 */
}

/**
  * @brief This function handles I2C1 event interrupt.
  */
void I2C1_EV_IRQHandler(void)
{
    
    
  /* USER CODE BEGIN I2C1_EV_IRQn 0 */

  /* USER CODE END I2C1_EV_IRQn 0 */
  HAL_I2C_EV_IRQHandler(&hi2c1);
  /* USER CODE BEGIN I2C1_EV_IRQn 1 */

  /* USER CODE END I2C1_EV_IRQn 1 */
}

/**
  * @brief This function handles USART1 global interrupt.
  */
void USART1_IRQHandler(void)
{
    
    
  /* USER CODE BEGIN USART1_IRQn 0 */

  /* USER CODE END USART1_IRQn 0 */
  HAL_UART_IRQHandler(&huart1);
  /* USER CODE BEGIN USART1_IRQn 1 */
	if(__HAL_UART_GET_IT_SOURCE(&huart1, UART_IT_RXNE)!= RESET) 
		{
    
    
			prvvUARTRxISR();//接收中断
		}

	if(__HAL_UART_GET_IT_SOURCE(&huart1, UART_IT_TXE)!= RESET) 
		{
    
    
			prvvUARTTxReadyISR();//发送中断
		}
	
  HAL_NVIC_ClearPendingIRQ(USART1_IRQn);
  HAL_UART_IRQHandler(&huart1);
  /* USER CODE END USART1_IRQn 1 */
}

/* USER CODE BEGIN 1 */
void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim)	//定时器中断回调函数,用于连接porttimer.c文件的函数
{
    
    
  /* NOTE : This function Should not be modified, when the callback is needed,
            the __HAL_TIM_PeriodElapsedCallback could be implemented in the user file
   */
  	prvvTIMERExpiredISR( );
}
/* USER CODE END 1 */

demo.c

/* ----------------------- Modbus includes ----------------------------------*/
#include "mb.h"
#include "mbport.h"
#include "AHT20-21_DEMO_V1_3.h" 

/* ----------------------- Defines ------------------------------------------*/
#define REG_INPUT_START 0
#define REG_INPUT_NREGS 5

/* ----------------------- Static variables ---------------------------------*/
static USHORT   usRegInputStart = REG_INPUT_START;
//static 
uint16_t   usRegInputBuf[REG_INPUT_NREGS];
uint16_t InputBuff[5];
uint32_t CT_data[2]={
    
    0,0};
	volatile int  c1,c2,t1,t2;

eMBErrorCode
eMBRegInputCB( UCHAR * pucRegBuffer, USHORT usAddress, USHORT usNRegs )
{
    
    
    eMBErrorCode    eStatus = MB_ENOERR;
    int             iRegIndex;
		int             i;
		AHT20_Read_CTdata_crc(CT_data);  //crc校验后,读取AHT20的温度和湿度数据 
		c1 = CT_data[0]*1000/1024/1024;  //计算得到湿度值c1(放大了10倍)
		t1 = CT_data[1]*2000/1024/1024-500;//计算得到温度值t1(放大了10倍)
		c2 = c1/10 + (c1/10)%10;
		t2 = t1/10 + (t1/10)%10;
		InputBuff[0] = t2;
		InputBuff[1] = c2;
		InputBuff[2] = 0x01;
		InputBuff[3] = 0x01;
		
    if( ( usAddress >= REG_INPUT_START )
        && ( usAddress + usNRegs <= REG_INPUT_START + REG_INPUT_NREGS ) )
    {
    
    
        iRegIndex = ( int )( usAddress - usRegInputStart );
				for(i=0;i<usNRegs;i++)
				{
    
    
					*pucRegBuffer=InputBuff[i+usAddress-1]>>8;
					pucRegBuffer++;
					*pucRegBuffer=InputBuff[i+usAddress-1]&0xff;
					pucRegBuffer++;
				}
    }
    else
    {
    
    
        eStatus = MB_ENOREG;
    }

    return eStatus;
}

eMBErrorCode
eMBRegHoldingCB( UCHAR * pucRegBuffer, USHORT usAddress, USHORT usNRegs,
                 eMBRegisterMode eMode )
{
    
    
    return MB_ENOREG;
}


eMBErrorCode
eMBRegCoilsCB( UCHAR * pucRegBuffer, USHORT usAddress, USHORT usNCoils,
               eMBRegisterMode eMode )
{
    
    
    return MB_ENOREG;
}

eMBErrorCode
eMBRegDiscreteCB( UCHAR * pucRegBuffer, USHORT usAddress, USHORT usNDiscrete )
{
    
    
    return MB_ENOREG;
}

创建任务,在Application/USER文件夹下新建app_rt_thread.c文件

在这里插入图片描述

添加以下代码

#include "rtthread.h"
#include "main.h"
#include "stdio.h"
#include "usart.h"
#include "AHT20-21_DEMO_V1_3.h" 
#include "mb.h"
#include "mbport.h"
 
struct rt_thread led1_thread;
rt_uint8_t rt_led1_thread_stack[128];
void led1_task_entry(void *parameter);
 
 
//初始化线程函数
void MX_RT_Thread_Init(void)
{
    
    
	//初始化LED1线程
	rt_thread_init(&led1_thread,"led1",led1_task_entry,RT_NULL,&rt_led1_thread_stack[0],sizeof(rt_led1_thread_stack),3,20);
	//开启线程调度
	rt_thread_startup(&led1_thread);
}
 
//主任务
void MX_RT_Thread_Process(void)
{
    
    
	( void )eMBPoll(  );//启动modbus侦听

}
 
//LED1任务
void led1_task_entry(void *parameter)
{
    
    
	while(1)
	{
    
    
		HAL_GPIO_WritePin(GPIOB,GPIO_PIN_15, GPIO_PIN_RESET);
		rt_thread_delay(500);
		HAL_GPIO_WritePin(GPIOB,GPIO_PIN_15, GPIO_PIN_SET);
		rt_thread_delay(500);
	}
}

找到Middlewares/RT-Thread/RTOS/kernel文件夹下的board.c文件,修改串口USART2为USART1

在这里插入图片描述

在这里插入图片描述

找到Application/User/Core里app_rt_thread.c下的rtconfig.h

在这里插入图片描述

mian.c

/* 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"
#include "dma.h"
#include "i2c.h"
#include "tim.h"
#include "usart.h"
#include "gpio.h"
#include "mb.h"
#include "mbport.h"
/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
#include <stdio.h>
#include "AHT20-21_DEMO_V1_3.h" 
/* USER CODE END Includes */

/* Private typedef -----------------------------------------------------------*/
/* USER CODE BEGIN PTD */
extern void MX_RT_Thread_Init(void);
extern void MX_RT_Thread_Process(void);
/* USER CODE END PTD */

/* Private define ------------------------------------------------------------*/
/* USER CODE BEGIN PD */
/* USER CODE END PD */

/* Private macro -------------------------------------------------------------*/
/* USER CODE BEGIN PM */

/* USER CODE END PM */

/* Private variables ---------------------------------------------------------*/

/* USER CODE BEGIN PV */

/* USER CODE END PV */

/* Private function prototypes -----------------------------------------------*/
void SystemClock_Config(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_DMA_Init();
  MX_I2C1_Init();
  MX_USART1_UART_Init();
  MX_TIM3_Init();
	AHT20_Init();
	eMBInit( MB_RTU, 0x01, 1, 115200, MB_PAR_NONE);//初始化modbus,走modbusRTU,从站地址为0x01,端口为1。
	eMBEnable(  );//使能modbus
  /* USER CODE BEGIN 2 */
 MX_RT_Thread_Init();
 
  /* USER CODE END 2 */

  /* Infinite loop */
  /* USER CODE BEGIN WHILE */
  while (1)
  {
    
    
    /* USER CODE END WHILE */
		( void )eMBPoll(  );//启动modbus侦听
    /* USER CODE BEGIN 3 */
  }
  /* USER CODE END 3 */
}

/**
  * @brief System Clock Configuration
  * @retval None
  */
void SystemClock_Config(void)
{
    
    
  RCC_OscInitTypeDef RCC_OscInitStruct = {
    
    0};
  RCC_ClkInitTypeDef RCC_ClkInitStruct = {
    
    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.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_DIV1;

  if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2) != HAL_OK)
  {
    
    
    Error_Handler();
  }
}

/* USER CODE BEGIN 4 */

/* 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 */

3 效果展示

将上述代码修改好后,编译烧录。

由于疫情原因返校回家,目前手上没有AHT20传感器,等返校后效果会补上。若连接传感器后,实现效果应为使用Modbusposs接收数据可以看到温度和湿度的数值,同时作为指示灯的小灯泡会闪烁。

总结

本次实验进一步学习了解了Modbus协议的应用,同时还完成了RT-Thread的移植。


参考:
https://blog.csdn.net/weixin_46129506/article/details/121914039
https://blog.csdn.net/qq_47281915/article/details/122328414
https://blog.csdn.net/weixin_56102526/article/details/121952050

猜你喜欢

转载自blog.csdn.net/apple_52030329/article/details/128437133