MODBUS transplantation STM32, STM32 respectively arranged to make the host and slave

MODBUS transplantation STM32, STM32 respectively arranged to make the host and slave

Recently taught himself MODBUS communication protocol, also find a lot of information from the Internet, they were also made from their own machine and host configuration, now with the operation

  1. MCU using STM32F103C8T6
  2. Realize the function, the host reads and writes are realized from the operation of the machine
  3. Host to use an external interrupt send data to achieve operational

First, the slave configuration

1.1, configure the system functions to achieve timing 1MS

72MHZ clock to initialize the system

/******************************************************************************
  * @brief  选择外部时钟或者内部时钟并进行倍频
  * @param  
	RCC_PLLSource:PLL时钟源 :
						可以选择:RCC_PLLSource_HSI_Div2、RCC_PLLSource_HSE_Div2、RCC_PLLSource_HSE_Div1
	PLLMUL:PLL输入时钟的倍频系数 
	          范围:RCC_CFGR_PLLMULL2~16
						PLL时钟根据时钟和倍频来确定,选择内部时钟最高64M
  * @retval 
 ******************************************************************************/
void SysClock_Configuration(uint32_t RCC_PLLSource, uint32_t PLLMUL)
{
	__IO uint32_t HSEStatus = 0;
	
	RCC_ClocksTypeDef get_rcc_clock; 
	
  RCC_DeInit();     // Resets the RCC clock configuration to the default reset state.
 
	if(RCC_PLLSource_HSI_Div2 != RCC_PLLSource)   //选择外部时钟
		{	      
		RCC_HSEConfig(RCC_HSE_ON);   			 //打开外部时钟
		if(RCC_WaitForHSEStartUp() == SUCCESS)    //等待外部时钟开启
			{
				HSEStatus = 1;			
			}
		else
			{                                           //外部时钟打开失败
				RCC_PLLSource = RCC_PLLSource_HSI_Div2;	//自动选择内部时钟
				PLLMUL = RCC_CFGR_PLLMULL16;		   //配频到64MHZ
				RCC_HSEConfig(RCC_HSE_OFF);	            //关闭外部时钟
				RCC_HSICmd(ENABLE);	                    //打开内部时钟
			}
	}
	else
		{	                                       //内部时钟
		   RCC_PLLSource = RCC_PLLSource_HSI_Div2; //自动选择内部时钟
		   PLLMUL = RCC_CFGR_PLLMULL16;            //倍频到64MHZ
		   RCC_HSEConfig(RCC_HSE_OFF);	           //关闭外部时钟
		   RCC_HSICmd(ENABLE);	                   //打开内部时钟
		
	  }
	
	RCC_HCLKConfig(RCC_SYSCLK_Div1);             //HCLK(AHB)时钟为系统时钟1分频			
	RCC_PCLK1Config(RCC_HCLK_Div2);              //PCLK(APB1)时钟为HCLK时钟2分频 
	RCC_PCLK2Config(RCC_HCLK_Div1);              //PCLK(APB2)时钟为HCLK时钟1分频	
 
	//0-24MHz时,取FLASH_Latency_0;
	//24-48MHz,取FLASH_Latency_1;
	//48-72MHz时,取FLASH_Latency_2。
	FLASH_SetLatency(FLASH_Latency_2);          //不用到可以不配置
	FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable); 
 
	RCC_PLLConfig(RCC_PLLSource, PLLMUL);     	//PLL时钟配置,时钟源 * PLLMUL	
	 
	RCC_PLLCmd(ENABLE);                         //开启PLL时钟,并等待PLL时钟准备好
	while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET);
	RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);  //选择PLL时钟为系统时钟
   
	while(RCC_GetSYSCLKSource() != 0x08);  //Wait till PLL is used as system clock source
	RCC_ClockSecuritySystemCmd(ENABLE);	   //打开时钟安全系统
  
	RCC_GetClocksFreq(&get_rcc_clock);     //仿真的时候就可以在结构体get_rcc_clock中看见各个外设的时钟了
}

Clock Configuration TIM3

NVIC containing the function

#include “USART.h”
#include “TIMER.h”

// 使用TIM3,对MODBUS协议定时
#define MODBUS_TIM                   TIM3             
#define MODBUS_TIM_APBxClock_FUN     RCC_APB1PeriphClockCmd
#define MODBUS_TIM_CLK               RCC_APB1Periph_TIM3
#define MODBUS_TIM_IRQ               TIM3_IRQn
#define MODBUS_TIM_IRQHandler        TIM3_IRQHandler
#define MODBUS_TIM_Period            (1000-1)
#define MODBUS_TIM_Prescaler         (72-1)
/******************************************************************************
  * @brief  MODBUS_TIM_Config:TIM3初始化
  * @param  
  * @retval 
 ******************************************************************************/
void MODBUS_TIM_Config(void)
{
  TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
  MODBUS_TIM_APBxClock_FUN(MODBUS_TIM_CLK, ENABLE);      //开启定时器时钟,即内部时钟CK_INT=72M
  TIM_TimeBaseStructure.TIM_Period=MODBUS_TIM_Period;        //自动重装载寄存器周的值(计数值)
  // 累计TIM_Period 个频率后产生一个更新或者中断
  // 时钟预分频数为71,则驱动计数器的时钟CK_CNT = CK_INT / (71+1)=1M
  TIM_TimeBaseStructure.TIM_Prescaler= MODBUS_TIM_Prescaler;
  TIM_TimeBaseStructure.TIM_ClockDivision=TIM_CKD_DIV1;     // 时钟分频因子 ,基本定时器没有,不用管
  TIM_TimeBaseStructure.TIM_CounterMode=TIM_CounterMode_Up; // 计数器计数模式,基本定时器只能向上计数,没有计数模式的设置
  TIM_TimeBaseStructure.TIM_RepetitionCounter=0;            // 重复计数器的值,基本定时器没有,不用管
  TIM_TimeBaseInit(MODBUS_TIM,&TIM_TimeBaseStructure);      // 初始化定时器
  TIM_ClearFlag(MODBUS_TIM,TIM_FLAG_Update);                // 清除计数器中断标志位
  TIM_ITConfig(MODBUS_TIM,TIM_IT_Update,ENABLE);            // 开启计数器中断
  TIM_Cmd(MODBUS_TIM, ENABLE);                              // 使能计数器
 }
/******************************************************************************
  * @brief  ALL_NVIC_Init:配置各个中断优先级
  * @param  
  * @retval 
 ******************************************************************************/


void ALL_NVIC_Init(void)
{
	NVIC_InitTypeDef NVIC_InitStructure;
	NVIC_PriorityGroupConfig(NVIC_PriorityGroup_1);             // 设置中断组为1	
	NVIC_InitStructure.NVIC_IRQChannel = MODBUS_TIM_IRQ ;       // 设置中断来源
	NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 1;   // 设置主优先级为 1
	NVIC_InitStructure.NVIC_IRQChannelSubPriority = 3;          // 设置抢占优先级为3
	NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
	NVIC_Init(&NVIC_InitStructure);
}

Configuration Interrupt function timer interrupt function placed in MODBUS_USART.c

/******************************************************************************
  * @brief  MODBUS_TIM_IRQHandler:MODBUS定时器中断函数
  * @param  
  * @retval 
 ******************************************************************************/
void MODBUS_TIM_IRQHandler (void)       //定时器中断函数
{
	if ( TIM_GetITStatus( MODBUS_TIM, TIM_IT_Update) != RESET )
		{
	   TIM_ClearITPendingBit(MODBUS_TIM , TIM_FLAG_Update);//清除中断标志位
		}
}

The main function

int main(void)
{ 

	SysClock_Configuration(RCC_PLLSource_HSE_Div1,RCC_CFGR_PLLMULL9);//设置系统时钟,外部设置为72MHZ,内部设置为64MHZ
    MODBUS_TIM_Config();
     ALL_NVIC_Init();
}

Whether to run the program at the breakpoint, runs as follows:

Here Insert Picture Description

1.2, configure the system to achieve serial reception interrupt function

Use USART2: PA2 and PA3, configure the serial port GPIO

// 串口2-USART2
#define MODBUS_USART                            USART2
#define MODBUS_USART_CLK                        RCC_APB1Periph_USART2
#define MODBUS_USART_APBxClkCmd                 RCC_APB1PeriphClockCmd
#define MODBUS_USART_BAUDRATE                   9600
// USART GPIO 引脚宏定义
#define MODBUS_USART_GPIO_CLK                   RCC_APB2Periph_GPIOA
#define MODBUS_USART_GPIO_APBxClkCmd            RCC_APB2PeriphClockCmd

#define MODBUS_USART_TX_GPIO_PORT               GPIOA
#define MODBUS_USART_TX_GPIO_PIN                GPIO_Pin_2
#define MODBUS_USART_RX_GPIO_PORT               GPIOA
#define MODBUS_USART_RX_GPIO_PIN                GPIO_Pin_3
// USART GPIO 中断
#define MODBUS_USART_IRQ                        USART2_IRQn
#define MODBUS_USART_IRQHandler                 USART2_IRQHandler
/******************************************************************************
* @brief  MODBUS_USART_Config:MODBUS配置串口模式
  * @param  无
  * @retval 无
 ******************************************************************************/

void MODBUS_USART_Config(void)
{
	GPIO_InitTypeDef GPIO_InitStructure;
	USART_InitTypeDef USART_InitStructure;
	
	MODBUS_USART_GPIO_APBxClkCmd(MODBUS_USART_GPIO_CLK, ENABLE);	  // 打开串口GPIO 的时钟	
	MODBUS_USART_APBxClkCmd(MODBUS_USART_CLK, ENABLE);	            // 打开串口外设的时钟	
	// 将USART1 Tx 的GPIO 配置为推挽复用模式
  GPIO_InitStructure.GPIO_Pin = MODBUS_USART_TX_GPIO_PIN;
  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
  GPIO_Init(MODBUS_USART_TX_GPIO_PORT, &GPIO_InitStructure);		
	// 将USART Rx 的GPIO 配置为浮空输入模式
  GPIO_InitStructure.GPIO_Pin = MODBUS_USART_RX_GPIO_PIN;
  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
  GPIO_Init(MODBUS_USART_RX_GPIO_PORT, &GPIO_InitStructure);	
	// 配置串口的工作参数
	USART_InitStructure.USART_BaudRate = MODBUS_USART_BAUDRATE;	  // 配置波特率
	USART_InitStructure.USART_WordLength = USART_WordLength_8b;	  // 配置 针数据字长
	USART_InitStructure.USART_StopBits = USART_StopBits_1;	      // 配置停止位
	USART_InitStructure.USART_Parity = USART_Parity_No ;	        // 配置校验位
	USART_InitStructure.USART_HardwareFlowControl =USART_HardwareFlowControl_None;	// 配置硬件流控制
	USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx;	         // 配置工作模式,收发一起
	USART_Init(MODBUS_USART, &USART_InitStructure);	                         // 完成串口的初始化配置	
	USART_ITConfig(MODBUS_USART, USART_IT_RXNE, ENABLE);	                 // 使能串口接收中断
	USART_Cmd(MODBUS_USART, ENABLE);	                                     // 使能串口
}
/******************************************************************************
  * @brief  ALL_NVIC_Init:配置各个中断优先级
  * @param  
  * @retval 
 ******************************************************************************/
void ALL_NVIC_Init(void)
{
	NVIC_InitTypeDef NVIC_InitStructure;
	NVIC_PriorityGroupConfig(NVIC_PriorityGroup_1);             // 设置中断组为1

	NVIC_InitStructure.NVIC_IRQChannel = MODBUS_USART_IRQ ;       // 设置中断来源
	NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 1;    // 设置主优先级为 1
	NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;           // 设置抢占优先级为0
	NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
	NVIC_Init(&NVIC_InitStructure);	
}

Configure the serial port to send character function, then send the data to prepare for

/******************************************************************************
  * @brief  Usart_SendByte:发送一个字符 
  * @param  
  * @retval 
 ******************************************************************************/

void Usart_SendByte( USART_TypeDef * pUSARTx, uint8_t ch)
{
  USART_SendData(pUSARTx,ch);                                    // 发送一个字节数据到USART 
while (USART_GetFlagStatus(pUSARTx, USART_FLAG_TXE) == RESET);   // 等待发送数据寄存器为空 
}

Configure the serial port receive interrupt function

/******************************************************************************
  * @brief  MODBUS_USART_IRQHandler:MODBUS串口中断函数
  * @param  
  * @retval 
 ******************************************************************************/

 void MODBUS_USART_IRQHandler(void)
{
  uint8_t ucTemp;
  if (USART_GetITStatus(MODBUS_USART,USART_IT_RXNE)!=RESET)  //判断是否有数据接收
  {} 
}

The main function

int main(void)
{ 

	SysClock_Configuration(RCC_PLLSource_HSE_Div1,RCC_CFGR_PLLMULL9);//设置系统时钟,外部设置为72MHZ,内部设置为64MHZ
	MODBUS_USART_Config();
    ALL_NVIC_Init();

}

Assistant is configured with the serial 9600BT / s, the transmission data

1.3, after receiving the data configuration of the system to achieve the function of delay 3.5T

In the configuration delay 3.5T functions simultaneously, MODBUS structure used to store configuration data, and establish MODBUS.c MODBUS.h

Nested Relations

#include “stm32f10x.h”
#include “modbusCRC.h”
#include “USART.h”

typedef struct
{
 unsigned char   myadd;          //本设备的地址
 unsigned char   rcbuf[100];     //MODBUS接收缓冲区
 unsigned int    timout;         //MODbus的数据断续时间	
 unsigned char   recount;        //MODbus端口已经收到的数据个数
 unsigned char   timrun;         //MODbus定时器是否计时的标志
 unsigned char   reflag;         //收到一帧数据的标志
 unsigned char   Sendbuf[100];   //MODbus发送缓冲区	
}MODBUS;

Serial Configuration receiver function

/******************************************************************************
  * @brief  MODBUS_USART_IRQHandler:MODBUS串口中断函数
  * @param  
  * @retval 
 ******************************************************************************/

 void MODBUS_USART_IRQHandler(void)
{
  uint8_t ucTemp;
  if (USART_GetITStatus(MODBUS_USART,USART_IT_RXNE)!=RESET)  //判断是否有数据接收
	{
		  ucTemp = USART_ReceiveData( MODBUS_USART ); //将接收的一个字节保存		
		  modbus.rcbuf[modbus.recount++]=ucTemp;     //保存到MODBUS的接收缓存区		
		  modbus.timout=0;			  //串口接收数据的过程中,定时器不计时		
		  if(modbus.recount==1)   //收到主机发来的一帧数据的第一字节
			  {
			    modbus.timrun=1;   	//启动定时
			  }
  }
}

Configuration Timer function

/******************************************************************************
  * @brief  MODBUS_TIM_IRQHandler:MODBUS定时器中断函数
  * @param  
  * @retval 
 ******************************************************************************/
void MODBUS_TIM_IRQHandler (void)   //定时器中断函数
{
	if ( TIM_GetITStatus( MODBUS_TIM, TIM_IT_Update) != RESET )
		{
	    if(modbus.timrun!=0)        //串口发送数据是否结束,结束就让定时器定时
		  {
	     modbus.timout++;           //定时器定时1毫秒,并开始记时
	   TIM_ClearITPendingBit(MODBUS_TIM , TIM_FLAG_Update);//清除中断标志位
		}
}

Combination of serial and timer run the program, sending assistant with the serial assistant, whether to enter the debugger breakpoint

1.4, the function of the configuration data processing system

The basic configuration of the timing we will MODBUS here configured, but the data has not been processed, then we deal with the data, verification and debugging assistant with MODBUS

Which contains MODBUS

#include “modbusCRC.h”
#include “USART.h”

Which contains MODBUS_USART

#include “USART.h”
#include “MODBUS.h”
#include “TIMER.h”

Register defined in MODBUS

unsigned int Reg[]={0x0000,   //本设备寄存器中的值
           0x1111,
           0x2222,
           0x3333,
           0x4444,
           0x5555,
           0x0006,
           0x0007,
           0x0008,
           0x0009,
           0x000A,	
          };	

Comprising the MODBUS function, the function does not explain one by one can look in which no transmission error handler code, function code practical enough

/******************************************************************************
  * @brief  Modbud_fun3:3号功能码处理  ---主机要读取本从机的寄存器
  * @param  
  * @retval 
 ******************************************************************************/
void Modbud_fun3(void)                           
{
  u16 Regadd;
	u16 Reglen;
	u16 byte;
	u16 i,j;
	u16 crc;
	Regadd=modbus.rcbuf[2]*256+modbus.rcbuf[3];  //得到要读取的寄存器的首地址
	Reglen=modbus.rcbuf[4]*256+modbus.rcbuf[5];  //得到要读取的寄存器的数量
	i=0;
	
	modbus.Sendbuf[i++]=modbus.myadd;           //发送本设备地址
  modbus.Sendbuf[i++]=0x03;                   //发送功能码      
  byte=Reglen*2;                              //要返回的数据字节数
  //modbus.Sendbuf[i++]=byte/256;  
	modbus.Sendbuf[i++]=byte%256;               //发送要返回的数据字节数         
	
	for(j=0;j<Reglen;j++)
	{
	  modbus.Sendbuf[i++]=Reg[Regadd+j]/256;    //发送读取数据字节数的高位 
		modbus.Sendbuf[i++]=Reg[Regadd+j]%256;  //发送读取数据字节数的低位 
	}
	crc=crc16(modbus.Sendbuf,i);                //CRC校验
	modbus.Sendbuf[i++]=crc/256;                //发送CRC的值高位
	modbus.Sendbuf[i++]=crc%256;                //发送CRC的值低位
	
	for(j=0;j<i;j++)                            //通过串口逐个发送
   Usart_SendByte( MODBUS_USART,modbus.Sendbuf[j]);
}
/******************************************************************************
  * @brief  Modbud_fun6:6号功能码处理,写寄存器
  * @param  
  * @retval 
 ******************************************************************************/

void Modbud_fun6()                             
{
  unsigned int Regadd;
	unsigned int val;
	unsigned int i,crc,j;
	i=0;
  Regadd=modbus.rcbuf[2]*256+modbus.rcbuf[3];  //得到要修改的地址 
	val=modbus.rcbuf[4]*256+modbus.rcbuf[5];   //修改后的值
	Reg[Regadd]=val;                           //修改本设备相应的寄存器
	//以下为回应主机
	modbus.Sendbuf[i++]=modbus.myadd;          //发送本设备地址
  modbus.Sendbuf[i++]=0x06;                    //发送功能码 
  modbus.Sendbuf[i++]=Regadd/256;              //发送修改地址高位
	modbus.Sendbuf[i++]=Regadd%256;            //发送修改地址低位
	modbus.Sendbuf[i++]=val/256;               //发送修改的值高位
	modbus.Sendbuf[i++]=val%256;               //发送修改的值低位
	crc=crc16(modbus.Sendbuf,i);               //校验地址、功能码、地址、数据
	modbus.Sendbuf[i++]=crc/256;               //发送CRC的值高位
	modbus.Sendbuf[i++]=crc%256;               //发送CRC的值低位
	
	for(j=0;j<i;j++)                             //通过串口逐个发送
   Usart_SendByte( MODBUS_USART,modbus.Sendbuf[j]);
}
/******************************************************************************
  * @brief  Mosbus_Event:MODBUS处理数据程序
  * @param  
  * @retval 
 ******************************************************************************/

void Mosbus_Event(void)
{
	unsigned int crc;
	unsigned int rccrc;
	unsigned char i=0;
  if(modbus.reflag==0)      //没有收到MODbus的数据包
	{
	  return ;                //没有收到处理指令,继续等待下一条数据
	}
	while(modbus.rcbuf[i++]!=modbus.myadd);
		
	crc= crc16(&modbus.rcbuf[0], modbus.recount-2);                             //计算校验码
  rccrc=modbus.rcbuf[modbus.recount-2]*256 + modbus.rcbuf[modbus.recount-1];  //收到的校验码
  if(crc ==  rccrc)                                                           //数据包符合CRC校验规则
	{ 
	  if(modbus.rcbuf[0] == modbus.myadd)         //确认数据包是否是发给本设备的 
		{
		  switch(modbus.rcbuf[1])                   //分析功能码
			{
			  case 0:     break;
			  case 1:     break;
		    case 2:     break;
		    case 3:     Modbud_fun3();    break;   //3号功能码处理
		    case 4:     break;
		    case 5:     break;
		    case 6:     Modbud_fun6();     break;  //6号功能码处理
	      case 7:     break;			
        //....				
			}
		}
		else if(modbus.rcbuf[0] == 0)             //广播地址,不处理
		{
		}
	}                                          //数据包不符合CRC校验规则
	modbus.recount=0;                          //清除缓存计数
  modbus.reflag=0;	                         //重新开始执行处理函数
}

It comprises the following functions MODBUS_USART

/******************************************************************************
  * @brief  MODBUS_Init:MODBUS初始化
  * @param  
  * @retval 
 ******************************************************************************/
void MODBUS_Init(void)
{
	MODBUS_TIM_Config();
	MODBUS_USART_Config();
	modbus.myadd=4;        //初始化本从设备的地址
	modbus.timrun=0;       //初始化MODbus定时器停止计时
}
/******************************************************************************
  * @brief  MODBUS_USART_IRQHandler:MODBUS串口中断函数
  * @param  
  * @retval 
 ******************************************************************************/
 void MODBUS_USART_IRQHandler(void)
{
  uint8_t ucTemp;
  if (USART_GetITStatus(MODBUS_USART,USART_IT_RXNE)!=RESET)  //判断是否有数据接收
	{
			ucTemp = USART_ReceiveData( MODBUS_USART ); //将接收的一个字节保存
		
		  modbus.rcbuf[modbus.recount++]=ucTemp;     //保存到MODBUS的接收缓存区
		
		  modbus.timout=0;			  //串口接收数据的过程中,定时器不计时
		
		  if(modbus.recount==1)   //收到主机发来的一帧数据的第一字节
			  {
			    modbus.timrun=1;   	//启动定时
			  }
  }
}
/******************************************************************************
  * @brief  MODBUS_TIM_IRQHandler:MODBUS定时器中断函数
  * @param  
  * @retval 
 ******************************************************************************/
void MODBUS_TIM_IRQHandler (void)   //定时器中断函数
{
	if ( TIM_GetITStatus( MODBUS_TIM, TIM_IT_Update) != RESET )
		{
	    if(modbus.timrun!=0)        //串口发送数据是否结束,结束就让定时器定时
		  {
	     modbus.timout++;           //定时器定时1毫秒,并开始记时
			 if(modbus.timout>=8)       //间隔时间达到了时间,假设为8T,实际3.5T即可
				{
					modbus.timrun=0;        //关闭定时器--停止定时
					modbus.reflag=1;        //收到一帧数据,开始处理数据
				}
			}
	   TIM_ClearITPendingBit(MODBUS_TIM , TIM_FLAG_Update);//清除中断标志位
		}
}

The main function

int main(void)
{ 
	SysClock_Configuration(RCC_PLLSource_HSE_Div1,RCC_CFGR_PLLMULL9);//设置系统时钟,外部设置为72MHZ,内部设置为64MHZ
	MODBUS_Init();
    ALL_NVIC_Init();
	while(1)
	Mosbus_Event();
}

MODBUS run debugging assistant, configure 9600TB / s, is set to address 4

Send: 04 06 00 00 00 01 48 5F

No. 0 indicates a write to register 1

Return: 04 06 00 00 00 01 48 5F

Send: 04 03 00 00 00 01 84 5F

It represents the value of a register after reading the address number 0

Return: 04 03 02 00 01 B5 84

Second, configure host

2.1, configure the system functions to achieve timing 1MS

As the configuration click to jump

2.2, configure the system to realize the serial receive interrupt function

As the configuration click to jump

2.3, and configure an external interrupt function USART1

USART1 configuration, used to view data, this port is only used to view the data without interruption configured to receive

// 串口1-USART1
#define DEBUG1_USART                            USART1
#define DEBUG1_USART_CLK                        RCC_APB2Periph_USART1
#define DEBUG1_USART_APBxClkCmd                 RCC_APB2PeriphClockCmd
#define DEBUG1_USART_BAUDRATE                   9600
// USART GPIO 引脚宏定义
#define DEBUG1_USART_GPIO_CLK                   RCC_APB2Periph_GPIOA
#define DEBUG1_USART_GPIO_APBxClkCmd            RCC_APB2PeriphClockCmd
#define DEBUG1_USART_TX_GPIO_PORT               GPIOA
#define DEBUG1_USART_TX_GPIO_PIN                GPIO_Pin_9
#define DEBUG1_USART_RX_GPIO_PORT               GPIOA
#define DEBUG1_USART_RX_GPIO_PIN                GPIO_Pin_10
/******************************************************************************
* @brief  DEBUG_USART_Init:配置串口调试
  * @param  无
  * @retval 无
 ******************************************************************************/
void DEBUG_USART_Init(void)
{
	GPIO_InitTypeDef GPIO_InitStructure;
	USART_InitTypeDef USART_InitStructure;
	DEBUG1_USART_GPIO_APBxClkCmd(DEBUG1_USART_GPIO_CLK, ENABLE);	  // 打开串口GPIO 的时钟	
	DEBUG1_USART_APBxClkCmd(DEBUG1_USART_CLK, ENABLE);	            // 打开串口外设的时钟	
	// 将USART1 Tx 的GPIO 配置为推挽复用模式
  GPIO_InitStructure.GPIO_Pin = DEBUG1_USART_TX_GPIO_PIN;
  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
  GPIO_Init(DEBUG1_USART_TX_GPIO_PORT, &GPIO_InitStructure);		
	// 将USART Rx 的GPIO 配置为浮空输入模式
  GPIO_InitStructure.GPIO_Pin = DEBUG1_USART_RX_GPIO_PIN;
  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
  GPIO_Init(DEBUG1_USART_RX_GPIO_PORT, &GPIO_InitStructure);	
	// 配置串口的工作参数
	USART_InitStructure.USART_BaudRate = DEBUG1_USART_BAUDRATE;	  // 配置波特率
	USART_InitStructure.USART_WordLength = USART_WordLength_8b;	  // 配置 针数据字长
	USART_InitStructure.USART_StopBits = USART_StopBits_1;	      // 配置停止位
	USART_InitStructure.USART_Parity = USART_Parity_No ;	      // 配置校验位
	USART_InitStructure.USART_HardwareFlowControl =USART_HardwareFlowControl_None;	// 配置硬件流控制
	USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx;	       // 配置工作模式,收发一起
	USART_Init(DEBUG1_USART, &USART_InitStructure);	                       // 完成串口的初始化配置	
	USART_ITConfig(DEBUG1_USART, USART_IT_RXNE, ENABLE);	               // 使能串口接收中断
	USART_Cmd(DEBUG1_USART, ENABLE);	                                   // 使能串口
}

External interrupt configuration, using the function keys PA0

//引脚定义
#define KEY_UP_INT_GPIO_PORT           GPIOA
#define KEY_UP_INT_GPIO_CLK           (RCC_APB2Periph_GPIOA|RCC_APB2Periph_AFIO)
#define KEY_UP_INT_GPIO_PIN            GPIO_Pin_0
#define KEY_UP_INT_EXTI_PORTSOURCE     GPIO_PortSourceGPIOA
#define KEY_UP_INT_EXTI_PINSOURCE      GPIO_PinSource0

#define KEY_UP_INT_EXTI_LINE           EXTI_Line0
#define KEY_UP_INT_EXTI_IRQ            EXTI0_IRQn
#define KEY_UP_IRQHandler              EXTI0_IRQHandler
void EXTI_Key_Config(void)
{
	GPIO_InitTypeDef GPIO_InitStructure;
	EXTI_InitTypeDef EXTI_InitStructure;

	RCC_APB2PeriphClockCmd(KEY_UP_INT_GPIO_CLK,ENABLE);    //开启按键GPIO 口的时钟
 /*--------------------------KEY1 配置---------------------*/
	GPIO_InitStructure.GPIO_Pin = KEY_UP_INT_GPIO_PIN;     // 选择按键用到的GPIO 
	GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPD;  // 配置为下拉输入,因为浮空输入其他的管脚对他的干扰很大 
	GPIO_Init(KEY_UP_INT_GPIO_PORT, &GPIO_InitStructure);
	GPIO_EXTILineConfig(KEY_UP_INT_EXTI_PORTSOURCE,KEY_UP_INT_EXTI_PINSOURCE);// 选择EXTI 的信号源 	
	EXTI_InitStructure.EXTI_Line = KEY_UP_INT_EXTI_LINE;
	EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt;   // EXTI 为中断模式 
	EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Rising;//上升沿中断
	EXTI_InitStructure.EXTI_LineCmd = ENABLE;             //使能中断 
	EXTI_Init(&EXTI_InitStructure);
}

It should be the main point, using the pull-down way, not by way of floating input

Configure the external interrupt function in MODBUS_USART

/******************************************************************************
  * @brief  MODBUS_TIM_IRQHandler:MODBUS定时器中断函数
  * @param  
  * @retval 
 ******************************************************************************/
void MODBUS_TIM_IRQHandler (void)   //定时器中断函数
{
	if ( TIM_GetITStatus( MODBUS_TIM, TIM_IT_Update) != RESET )
		{
	    if(modbus.timrun!=0)        //串口发送数据是否结束,结束就让定时器定时
		  {
	     modbus.timout++;           //定时器定时1毫秒,并开始记时
			 if(modbus.timout>=8)       //间隔时间达到了时间,假设为8T,实际3.5T即可
				{
					modbus.timrun=0;        //关闭定时器--停止定时
					modbus.reflag=1;        //收到一帧数据,开始处理数据
				}
			}
	   TIM_ClearITPendingBit(MODBUS_TIM , TIM_FLAG_Update);//清除中断标志位
		}
}

 /******************************************************************************
  * @brief  KEY_UP_IRQHandler:外部发送数据方式
  * @param  
  * @retval 
 ******************************************************************************/
void KEY_UP_IRQHandler(void)
{

	if (EXTI_GetITStatus(KEY_UP_INT_EXTI_LINE) != RESET)   //确保是否产生了EXTI Line 中断
		{
		
	  Usart_SendByte( DEBUG1_USART,modbus.myadd);
		Usart_SendByte( DEBUG1_USART,0x03);
		Usart_SendByte( DEBUG1_USART,0x00);
		Usart_SendByte( DEBUG1_USART,0x00);
		Usart_SendByte( DEBUG1_USART,0x00);
		Usart_SendByte( DEBUG1_USART,0x02);
	  Usart_SendByte( DEBUG1_USART,0xC4);
		Usart_SendByte( DEBUG1_USART,0x5E);	
			
		Usart_SendByte( MODBUS_USART,modbus.myadd);
		Usart_SendByte( MODBUS_USART,0x03);
		Usart_SendByte( MODBUS_USART,0x00);
		Usart_SendByte( MODBUS_USART,0x00);
		Usart_SendByte( MODBUS_USART,0x00);
		Usart_SendByte( MODBUS_USART,0x02);
	  Usart_SendByte( MODBUS_USART,0xC4);
		Usart_SendByte( MODBUS_USART,0x5E);	

		EXTI_ClearITPendingBit(KEY_UP_INT_EXTI_LINE);        //清除中断标志位
		}
}

Open USART2 serial transmit data, receive data USART1

Back to the write command from the data processing unit

Send: 04 06 00 00 00 01 48 5F

Write address register 00 00 1

Returns: 0001

Returns the read instruction from the data processing unit

Send: 04 03 02 00 01 B5 84

D 00 00 register address read 1

Returns: 0001

2.4, configure the system to achieve the function of receiving the data delay 3.5T

As the configuration click to jump

2.5, the function of the configuration data processing system

This place and different from machine

/******************************************************************************
  * @brief  Modbud_fun3:3号功能码处理  ---主机要读取从机的寄存器后,将信息保存到主机指定长度的寄存器
  * @param  
  * @retval 
 ******************************************************************************/
void Modbud_fun3(void)                           
{
  unsigned int Regadd=0,i=0,j,Reglen;                                   
	Reglen=modbus.rcbuf[2];                         //得到读取的寄存器的数量
	for(i=0;i<Reglen;i++)                           //处理读取的数据保存到主机相应寄存器
	{                                               //数据从寄存器的第一个保存到指定数量
	Reg[Regadd]=modbus.rcbuf[3+i]*256;              //将数据高位保存寄存器
	Usart_SendByte( DEBUG1_USART,Reg[Regadd]/256);  //发送到另一个串口显示	
  i++;		                                        //数据增加,处理低位
    Reg[Regadd]=Reg[Regadd]+modbus.rcbuf[i+3];      //发送到另一个串口显示	
	Usart_SendByte( DEBUG1_USART,Reg[Regadd]%256);  //将数据低位保存寄存器
	Regadd++;		                               //处理完高位和低位数据,进行下一个数据
	}
}
/******************************************************************************
  * @brief  Modbud_fun6:6号功能码处理,主机向从机指定寄存器写数据,写完后,返回修改的数据
  * @param  
  * @retval 
 ******************************************************************************/
void Modbud_fun6()                             
{
  unsigned int Regadd,i=0,crc,j,val;             
	Regadd=modbus.rcbuf[2]*256+modbus.rcbuf[3];        //得到要更改寄存器的地址
	Reg[Regadd]=modbus.rcbuf[4]*256+modbus.rcbuf[5];   //将从机修改的数据再保存到主机寄存器中
  Usart_SendByte( DEBUG1_USART,Reg[Regadd]/256);     //另一个串口显示修改的数据
	Usart_SendByte( DEBUG1_USART,Reg[Regadd]%256);     //另一个串口显示修改的数据
}

The main function is as follows

int main(void)
{ 
	SysClock_Configuration(RCC_PLLSource_HSE_Div1,RCC_CFGR_PLLMULL9);//设置系统时钟,外部设置为72MHZ,内部设置为64MHZ
	MODBUS_Init();
  ALL_NVIC_Init();
	Usart_SendByte( DEBUG1_USART,0x32);
	CODE_End();
	while(1)
	Mosbus_Event();
}

Third, the host command is issued to the slave

3.1, write command to send the host and slave

The connection from the serial port of the host machine, press the button of the host, the host port to see whether there is another data receiving

Key interrupt function configuration

		Usart_SendByte( DEBUG1_USART,modbus.myadd);
		Usart_SendByte( DEBUG1_USART,0x06);
		Usart_SendByte( DEBUG1_USART,0x00);
		Usart_SendByte( DEBUG1_USART,0x00);
		Usart_SendByte( DEBUG1_USART,0xFF);
		Usart_SendByte( DEBUG1_USART,0xFF);
	    Usart_SendByte( DEBUG1_USART,0x88);
		Usart_SendByte( DEBUG1_USART,0x2F);			

		Usart_SendByte( MODBUS_USART,modbus.myadd);
		Usart_SendByte( MODBUS_USART,0x06);
		Usart_SendByte( MODBUS_USART,0x00);
		Usart_SendByte( MODBUS_USART,0x00);
		Usart_SendByte( MODBUS_USART,0xFF);
		Usart_SendByte( MODBUS_USART,0xFF);
	    Usart_SendByte( MODBUS_USART,0x88);
	    Usart_SendByte( MODBUS_USART,0x2F);	

Corresponds to the master to the slave send data: 0x04 0x06 0x00 0x00 0xFF 0xFF 0x88

Return: 0xFF 0xFF

3.2, delivers a read command from the host machine at

The connection from the serial port of the host machine, press the button of the host, the host port to see whether there is another data receiving

	    Usart_SendByte( MODBUS_USART,modbus.myadd);
		Usart_SendByte( MODBUS_USART,0x03);
		Usart_SendByte( MODBUS_USART,0x00);
		Usart_SendByte( MODBUS_USART,0x00);
		Usart_SendByte( MODBUS_USART,0x00);
		Usart_SendByte( MODBUS_USART,0x01);
	    Usart_SendByte( MODBUS_USART,0x84);
		Usart_SendByte( MODBUS_USART,0x5F);	
		
	    Usart_SendByte( DEBUG1_USART,modbus.myadd);
		Usart_SendByte( DEBUG1_USART,0x03);
		Usart_SendByte( DEBUG1_USART,0x00);
		Usart_SendByte( DEBUG1_USART,0x00);
		Usart_SendByte( DEBUG1_USART,0x00);
	 	Usart_SendByte( DEBUG1_USART,0x01);
	    Usart_SendByte( DEBUG1_USART,0x84);
		Usart_SendByte( DEBUG1_USART,0x5F);	

Here Insert Picture Description

Corresponds to the master to the slave send data: 0x04 0x06 0x00 0x00 0x01 0x84 0x5F

Return: 0x00 0x00

00 is due to return here after commissioning process before the completion of Step 3.1 is reset to the original value caused.

Released six original articles · won praise 6 · views 1603

Guess you like

Origin blog.csdn.net/xiaoxiaodawei/article/details/105352113