一、S.BUS协议
工作电压:4.8-10V
SBUS 信号模式: 接收机指示灯为蓝色,R9DS 的 第 9 通道输出 SBUS 信号, 同时原来的 1 通道 输出独立 3 通道 PWM 信号,原来的 2-6 通道输出 6-10 通道的独立 PWM 信号,7-8 通道无信号,共 计 10 个通道的信号。
SUBS的信号类似于一个串口发送,但与平时使用的串口有些许区别。
注意:SBUS信号与串口发送是相反 ---串口(1)==信号(0) 串口(0) == 信号(1)。所以必须采用硬件 取反稳定。(本文章硬件不足,采用STM32F103C8T6模拟取反)。
配置:波特率:100K(100000),数据位:9bit,奇偶校验位:偶校验(even),停止位:2位
数据:SBUS一次传输25字节数据data[25],由data[0] = 0x0f 开始,到data[25] = 0x00结束,
中间 data[1]----data[22]是有效的16个通道数据。data[23]数据校验位。
数据解析:有效数据是data[1]----data[22]共22个字节[1字节(Byte)等于8位(bit)]
8*22=176(bit)。22字节中包含16个通道数据176/16=11(bit),每11位包含一通道数据。
二、端口配置(STM32F103C8T6)
1. 串口配置(STM32CubeMX)
USART1:
波特率:100000,数据位:9bit,奇偶校验位:even,停止位:2位
开启中断设置最高优先级
USART2:
波特率:115200,数据位:8bit,奇偶校验:无,停止位:1位
USART2用于发送信息,所以就不设置中断。
2. PWM(舵机)配置
3. 模拟串口的硬件取反(再开一个STM32CubeMX)
STM32F103C8T6的PC13连接着LED灯,便于观察。
PC14输入不上拉下拉是用与输入R9DS的信号,将信号取反用PC13输出
三、硬件连接
右边两个为舵机,VCC都接5V。
四、程序
1. 串口重定向
//用USART2将数据传出 int fputc(int ch, FILE *f) { HAL_UART_Transmit(&huart2, (uint8_t *)&ch, 1, 0xffff); return ch; }
2. 中断接收SBUS协议数据
uint8_t rx[1]; //用于接收一个字节的数据 uint8_t SBUS_data[25]; //保存0x0f开头的所有数据 uint8_t SBUS_init = 0; //表示数据有效开始接收 uint8_t SBUS_end = 0; //表示数据结尾,停止接收 int SBUS_cnt=0; //记录接收了多少的字节数 int i=0; void HAL_UART_RxCpltCallback(UART_HandleTypeDef *huart) { if(huart->Instance == USART1){ i=1; ///表示触发一次中断接收 if(rx[0] == 0x0f && SBUS_init == 0){ //当识别到为0x0f开始时 SBUS_data[0] = rx[0]; SBUS_cnt++; SBUS_init=1; //开启接收 } if(SBUS_init == 1 && SBUS_cnt<=23){ //保存中间数据 SBUS_data[SBUS_cnt] = rx[0]; SBUS_cnt++; //记录位数 } if(SBUS_init == 1 && SBUS_end == 0 && rx[0] == 0x00 && SBUS_cnt==24){// 结束 SBUS_data[SBUS_cnt] = rx[0]; SBUS_end=1; } } }
3. 数据解析
uint16_t SBUS_thoroughfare[16] = {0}; void Sbus_Data_Count(uint8_t *buf) //将8*22=176字节重新放入到SBUS_thoroughfare通道数据中 { SBUS_thoroughfare[ 0] = ((int16_t)buf[ 2] >> 0 | ((int16_t)buf[ 3] << 8 )) & 0x07FF; SBUS_thoroughfare[ 1] = ((int16_t)buf[ 3] >> 3 | ((int16_t)buf[ 4] << 5 )) & 0x07FF; SBUS_thoroughfare[ 2] = ((int16_t)buf[ 4] >> 6 | ((int16_t)buf[ 5] << 2 ) | (int16_t)buf[ 6] << 10 ) & 0x07FF; SBUS_thoroughfare[ 3] = ((int16_t)buf[ 6] >> 1 | ((int16_t)buf[ 7] << 7 )) & 0x07FF; SBUS_thoroughfare[ 4] = ((int16_t)buf[ 7] >> 4 | ((int16_t)buf[ 8] << 4 )) & 0x07FF; SBUS_thoroughfare[ 5] = ((int16_t)buf[ 8] >> 7 | ((int16_t)buf[ 9] << 1 ) | (int16_t)buf[10] << 9 ) & 0x07FF; SBUS_thoroughfare[ 6] = ((int16_t)buf[10] >> 2 | ((int16_t)buf[11] << 6 )) & 0x07FF; SBUS_thoroughfare[ 7] = ((int16_t)buf[11] >> 5 | ((int16_t)buf[12] << 3 )) & 0x07FF; SBUS_thoroughfare[ 8] = ((int16_t)buf[13] << 0 | ((int16_t)buf[14] << 8 )) & 0x07FF; SBUS_thoroughfare[ 9] = ((int16_t)buf[14] >> 3 | ((int16_t)buf[15] << 5 )) & 0x07FF; SBUS_thoroughfare[10] = ((int16_t)buf[15] >> 6 | ((int16_t)buf[16] << 2 ) | (int16_t)buf[17] << 10 ) & 0x07FF; SBUS_thoroughfare[11] = ((int16_t)buf[17] >> 1 | ((int16_t)buf[18] << 7 )) & 0x07FF; SBUS_thoroughfare[12] = ((int16_t)buf[18] >> 4 | ((int16_t)buf[19] << 4 )) & 0x07FF; SBUS_thoroughfare[13] = ((int16_t)buf[19] >> 7 | ((int16_t)buf[20] << 1 ) | (int16_t)buf[21] << 9 ) & 0x07FF; SBUS_thoroughfare[14] = ((int16_t)buf[21] >> 2 | ((int16_t)buf[22] << 6 )) & 0x07FF; SBUS_thoroughfare[15] = ((int16_t)buf[22] >> 5 | ((int16_t)buf[23] << 3 )) & 0x07FF; } //将接收到的数据装入数组 输入1将输出各通道数据 //注意:STM32F103C8T6开启数据输出后一会将程序卡死, //所以如果要观察数据可以一个一个输出尝试在实际使用中不开启串口输出 void SBUS_thoroughfare_analysis(int n){ Sbus_Data_Count(SBUS_data); //解析数据 //通道1 左300 - 1650 //通道2 (上)300 -1650 //通道3 (下)300 - 1650 //通道4 (左)300 -1650 if(n==1){ printf("====================================== "); printf("yes: head=0x0F, flag=0x00, end=0x00 "); printf("head: %d ", SBUS_data[0]); printf(" %4d, %4d, %4d, %4d ", SBUS_thoroughfare[0], SBUS_thoroughfare[1], SBUS_thoroughfare[2], SBUS_thoroughfare[3]); printf(" %4d, %4d, %4d, %4d ", SBUS_thoroughfare[4], SBUS_thoroughfare[5], SBUS_thoroughfare[6], SBUS_thoroughfare[7]); printf(" %4d, %4d, %4d, %4d ", SBUS_thoroughfare[8], SBUS_thoroughfare[9], SBUS_thoroughfare[10], SBUS_thoroughfare[11]); printf(" %4d, %4d, %4d, %4d ", SBUS_thoroughfare[12], SBUS_thoroughfare[13], SBUS_thoroughfare[14], SBUS_thoroughfare[15]); printf("flag: %4d ", SBUS_data[23]); printf("end : %4d ", SBUS_data[24]); printf("====================================== "); } //printf("%d ",SBUS_thoroughfare[5]); //printf(" %4d, %4d, %4d, %4d ", SBUS_thoroughfare[0], SBUS_thoroughfare[1], SBUS_thoroughfare[2], SBUS_thoroughfare[3]); }
4. 数据与PWM连接
if(i==1){ i=0; //HAL_UART_Transmit(&huart2,&data, 3, 0xff); if(SBUS_end == 1){ //HAL_UART_Transmit(&huart2, SBUS_data, 25, 0xff); SBUS_thoroughfare_analysis(0);//HAL_UART_Transmit(&huart2, (uint8_t *)" ", 5, 0xff); //printf("%d ",SBUS_data[0]); SBUS_end=0; SBUS_init=0; SBUS_cnt=0; //HAL_Delay(100); } HAL_UART_Receive_IT(&huart1, rx, 1); //发生接收中断后,中断使能位会清除,故此处再调用此函数使能接收中断 } //将数据大小限制在500-1500便于与舵机对齐 if(SBUS_thoroughfare[5]>=1000){ if(SBUS_thoroughfare[0] < 500) SBUS_thoroughfare[0] = 500; if(SBUS_thoroughfare[0] > 1500) SBUS_thoroughfare[0] = 1500; if(SBUS_thoroughfare[1] < 500) SBUS_thoroughfare[0] = 500; if(SBUS_thoroughfare[1] > 1500) SBUS_thoroughfare[0] = 1500; __HAL_TIM_SET_COMPARE(&htim2,TIM_CHANNEL_2,(SBUS_thoroughfare[0] -500)*2+500);//0-180 __HAL_TIM_SET_COMPARE(&htim2,TIM_CHANNEL_1,(SBUS_thoroughfare[1] -500)*2+500);//0-180 } else{ if(SBUS_thoroughfare[3] < 500) SBUS_thoroughfare[0] = 500; if(SBUS_thoroughfare[3] > 1500) SBUS_thoroughfare[0] = 1500; __HAL_TIM_SET_COMPARE(&htim2,TIM_CHANNEL_2,(SBUS_thoroughfare[3] -500)*2+500);//0-180 if(SBUS_thoroughfare[2] < 500) SBUS_thoroughfare[0] = 500; if(SBUS_thoroughfare[2] > 1500) SBUS_thoroughfare[0] = 1500; //SBUS_thoroughfare[2] = 1500 - SBUS_thoroughfare[2]; __HAL_TIM_SET_COMPARE(&htim2,TIM_CHANNEL_1,(SBUS_thoroughfare[2] -500)*2+500);//0-180 }
5. 信号处理总程序(main.c)
/* USER CODE BEGIN Header */ /** ****************************************************************************** * @file : main.c * @brief : Main program body ****************************************************************************** * @attention * * Copyright (c) 2024 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 "tim.h" #include "usart.h" #include "gpio.h" /* Private includes ----------------------------------------------------------*/ /* USER CODE BEGIN Includes */ /* USER CODE END Includes */ /* Private typedef -----------------------------------------------------------*/ /* USER CODE BEGIN PTD */ #include <stdio.h> /* 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 */ //uint8_t data[25]; uint8_t rx[1]; //用于接收一个字节的数据 uint8_t SBUS_data[25]; //保存0x0f开头的所有数据 uint8_t SBUS_init = 0; //表示数据有效开始接收 uint8_t SBUS_end = 0; //表示数据结尾,停止接收 int SBUS_cnt=0; //记录接收了多少的字节数 int i=0; void HAL_UART_RxCpltCallback(UART_HandleTypeDef *huart) { if(huart->Instance == USART1){ i=1; if(rx[0] == 0x0f && SBUS_init == 0){ //当识别到为0x0f开始时 SBUS_data[0] = rx[0]; SBUS_cnt++; SBUS_init=1; //开启接收 } if(SBUS_init == 1 && SBUS_cnt<=23){ //保存中间数据 SBUS_data[SBUS_cnt] = rx[0]; SBUS_cnt++; //记录位数 } if(SBUS_init == 1 && SBUS_end == 0 && rx[0] == 0x00 && SBUS_cnt==24){// 结束 SBUS_data[SBUS_cnt] = rx[0]; SBUS_end=1; } } } //int binaryToDecimal(uint16_t binary) { // int decimal = 0; // int base = 1; // while (binary > 0) { // int lastDigit = binary & 1; // 获取最低位的值 // decimal += lastDigit * base; // base *= 2; // binary >>= 1; // 右移一位,将下一位作为最低位 // } // return decimal; //} int fputc(int ch, FILE *f) { HAL_UART_Transmit(&huart2, (uint8_t *)&ch, 1, 0xffff); return ch; } uint16_t SBUS_thoroughfare[16] = {0}; void Sbus_Data_Count(uint8_t *buf) //将8*22=176字节重新放入到SBUS_thoroughfare通道数据中 { SBUS_thoroughfare[ 0] = ((int16_t)buf[ 2] >> 0 | ((int16_t)buf[ 3] << 8 )) & 0x07FF; SBUS_thoroughfare[ 1] = ((int16_t)buf[ 3] >> 3 | ((int16_t)buf[ 4] << 5 )) & 0x07FF; SBUS_thoroughfare[ 2] = ((int16_t)buf[ 4] >> 6 | ((int16_t)buf[ 5] << 2 ) | (int16_t)buf[ 6] << 10 ) & 0x07FF; SBUS_thoroughfare[ 3] = ((int16_t)buf[ 6] >> 1 | ((int16_t)buf[ 7] << 7 )) & 0x07FF; SBUS_thoroughfare[ 4] = ((int16_t)buf[ 7] >> 4 | ((int16_t)buf[ 8] << 4 )) & 0x07FF; SBUS_thoroughfare[ 5] = ((int16_t)buf[ 8] >> 7 | ((int16_t)buf[ 9] << 1 ) | (int16_t)buf[10] << 9 ) & 0x07FF; SBUS_thoroughfare[ 6] = ((int16_t)buf[10] >> 2 | ((int16_t)buf[11] << 6 )) & 0x07FF; SBUS_thoroughfare[ 7] = ((int16_t)buf[11] >> 5 | ((int16_t)buf[12] << 3 )) & 0x07FF; SBUS_thoroughfare[ 8] = ((int16_t)buf[13] << 0 | ((int16_t)buf[14] << 8 )) & 0x07FF; SBUS_thoroughfare[ 9] = ((int16_t)buf[14] >> 3 | ((int16_t)buf[15] << 5 )) & 0x07FF; SBUS_thoroughfare[10] = ((int16_t)buf[15] >> 6 | ((int16_t)buf[16] << 2 ) | (int16_t)buf[17] << 10 ) & 0x07FF; SBUS_thoroughfare[11] = ((int16_t)buf[17] >> 1 | ((int16_t)buf[18] << 7 )) & 0x07FF; SBUS_thoroughfare[12] = ((int16_t)buf[18] >> 4 | ((int16_t)buf[19] << 4 )) & 0x07FF; SBUS_thoroughfare[13] = ((int16_t)buf[19] >> 7 | ((int16_t)buf[20] << 1 ) | (int16_t)buf[21] << 9 ) & 0x07FF; SBUS_thoroughfare[14] = ((int16_t)buf[21] >> 2 | ((int16_t)buf[22] << 6 )) & 0x07FF; SBUS_thoroughfare[15] = ((int16_t)buf[22] >> 5 | ((int16_t)buf[23] << 3 )) & 0x07FF; } //将接收到的数据装入数组 输入1将输出各通道数据 //注意:STM32F103C8T6开启数据输出后一会将程序卡死, //所以如果要观察数据可以一个一个输出尝试在实际使用中不开启串口输出 void SBUS_thoroughfare_analysis(int n){ Sbus_Data_Count(SBUS_data); //解析数据 //通道1 左300 - 1650 //通道2 (上)300 -1650 //通道3 (下)300 - 1650 //通道4 (左)300 -1650 if(n==1){ printf("====================================== "); printf("yes: head=0x0F, flag=0x00, end=0x00 "); printf("head: %d ", SBUS_data[0]); printf(" %4d, %4d, %4d, %4d ", SBUS_thoroughfare[0], SBUS_thoroughfare[1], SBUS_thoroughfare[2], SBUS_thoroughfare[3]); printf(" %4d, %4d, %4d, %4d ", SBUS_thoroughfare[4], SBUS_thoroughfare[5], SBUS_thoroughfare[6], SBUS_thoroughfare[7]); printf(" %4d, %4d, %4d, %4d ", SBUS_thoroughfare[8], SBUS_thoroughfare[9], SBUS_thoroughfare[10], SBUS_thoroughfare[11]); printf(" %4d, %4d, %4d, %4d ", SBUS_thoroughfare[12], SBUS_thoroughfare[13], SBUS_thoroughfare[14], SBUS_thoroughfare[15]); printf("flag: %4d ", SBUS_data[23]); printf("end : %4d ", SBUS_data[24]); printf("====================================== "); } //printf("%d ",SBUS_thoroughfare[5]); //printf(" %4d, %4d, %4d, %4d ", SBUS_thoroughfare[0], SBUS_thoroughfare[1], SBUS_thoroughfare[2], SBUS_thoroughfare[3]); } /* 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_USART1_UART_Init(); MX_USART2_UART_Init(); MX_TIM2_Init(); /* USER CODE BEGIN 2 */ HAL_UART_Receive_IT(&huart1, rx, 1); HAL_TIM_PWM_Start(&htim2,TIM_CHANNEL_1); HAL_TIM_PWM_Start(&htim2,TIM_CHANNEL_2); __HAL_TIM_SET_COMPARE(&htim2,TIM_CHANNEL_2,1500);//0-180°此时对应45° __HAL_TIM_SET_COMPARE(&htim2,TIM_CHANNEL_1,1500);//0-180°此时对应45° /* USER CODE END 2 */ /* Infinite loop */ /* USER CODE BEGIN WHILE */ while (1) { /* USER CODE END WHILE */ /* USER CODE BEGIN 3 */ //HAL_UART_Transmit(&huart2,(uint8_t *)"hijok ", 10, 0xff); if(i==1){ i=0; //HAL_UART_Transmit(&huart2,&data, 3, 0xff); if(SBUS_end == 1){ //HAL_UART_Transmit(&huart2, SBUS_data, 25, 0xff); SBUS_thoroughfare_analysis(0);//HAL_UART_Transmit(&huart2, (uint8_t *)" ", 5, 0xff); //printf("%d ",SBUS_data[0]); SBUS_end=0; SBUS_init=0; SBUS_cnt=0; //HAL_Delay(100); } HAL_UART_Receive_IT(&huart1, rx, 1); //发生接收中断后,中断使能位会清除,故此处再调用此函数使能接收中断 } //将数据大小限制在500-1500便于与舵机对齐 if(SBUS_thoroughfare[5]>=1000){ if(SBUS_thoroughfare[0] < 500) SBUS_thoroughfare[0] = 500; if(SBUS_thoroughfare[0] > 1500) SBUS_thoroughfare[0] = 1500; if(SBUS_thoroughfare[1] < 500) SBUS_thoroughfare[0] = 500; if(SBUS_thoroughfare[1] > 1500) SBUS_thoroughfare[0] = 1500; __HAL_TIM_SET_COMPARE(&htim2,TIM_CHANNEL_2,(SBUS_thoroughfare[0] -500)*2+500);//0-180 __HAL_TIM_SET_COMPARE(&htim2,TIM_CHANNEL_1,(SBUS_thoroughfare[1] -500)*2+500);//0-180 } else{ if(SBUS_thoroughfare[3] < 500) SBUS_thoroughfare[0] = 500; if(SBUS_thoroughfare[3] > 1500) SBUS_thoroughfare[0] = 1500; __HAL_TIM_SET_COMPARE(&htim2,TIM_CHANNEL_2,(SBUS_thoroughfare[3] -500)*2+500);//0-180 if(SBUS_thoroughfare[2] < 500) SBUS_thoroughfare[0] = 500; if(SBUS_thoroughfare[2] > 1500) SBUS_thoroughfare[0] = 1500; //SBUS_thoroughfare[2] = 1500 - SBUS_thoroughfare[2]; __HAL_TIM_SET_COMPARE(&htim2,TIM_CHANNEL_1,(SBUS_thoroughfare[2] -500)*2+500);//0-180 } } /* 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_HSI; RCC_OscInitStruct.HSIState = RCC_HSI_ON; RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT; RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE; 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_HSI; RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1; RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1; if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_0) != 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 ", file, line) */ /* USER CODE END 6 */ } #endif /* USE_FULL_ASSERT */
6. 模拟取反(新的一个STM32F103C8T6板)
//将其放入在while中,将一直将接收机的信号取反并输出 //如果接收和处理在同一块板子上将导致数据的不准确 if(HAL_GPIO_ReadPin(GPIOC,GPIO_PIN_14) == 0) HAL_GPIO_WritePin(GPIOC,GPIO_PIN_13,GPIO_PIN_SET); else HAL_GPIO_WritePin(GPIOC,GPIO_PIN_13,GPIO_PIN_RESET);
7. 模拟取反总程序(main.c)
/* USER CODE BEGIN Header */ /** ****************************************************************************** * @file : main.c * @brief : Main program body ****************************************************************************** * @attention * * Copyright (c) 2024 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 "gpio.h" /* Private includes ----------------------------------------------------------*/ /* USER CODE BEGIN Includes */ /* USER CODE END Includes */ /* Private typedef -----------------------------------------------------------*/ /* USER CODE BEGIN PTD */ /* USER CODE END PTD */ /* Private define ------------------------------------------------------------*/ /* USER CODE BEGIN PD */ /* USER CODE END PD */ /* Private macro -------------------------------------------------------------*/ /* USER CODE BEGIN PM */ /* USER CODE END PM */ /* Private variables ---------------------------------------------------------*/ /* 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(); /* USER CODE BEGIN 2 */ /* USER CODE END 2 */ /* Infinite loop */ /* USER CODE BEGIN WHILE */ while (1) { /* USER CODE END WHILE */ /* USER CODE BEGIN 3 */ if(HAL_GPIO_ReadPin(GPIOC,GPIO_PIN_14) == 0) HAL_GPIO_WritePin(GPIOC,GPIO_PIN_13,GPIO_PIN_SET); else HAL_GPIO_WritePin(GPIOC,GPIO_PIN_13,GPIO_PIN_RESET); } /* 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_HSI; RCC_OscInitStruct.HSIState = RCC_HSI_ON; RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT; RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE; 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_HSI; RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1; RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1; if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_0) != 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 ", file, line) */ /* USER CODE END 6 */ } #endif /* USE_FULL_ASSERT */
五、效果演示
<iframe id="I9SxIX0u-1705914719097" frameborder="0" src="//i2.wp.com/live.csdn.net/v/embed/360935" allowfullscreen="true" data-mediaembed="csdn"></iframe>
六、参考资料
1. 提取码:0X78 工程链接
2. R9DS接收机说明书
3. 乐迪AT9S Pro遥控器说明书
4. 深度解析FUTABA的SBUS协议
5. R9DS接收机SMBUS数据解析
6. SBUS协议解析图解
7. 【SBUS】一文看懂SBUS协议
8. STM32-HAL库串口DMA空闲中断的正确使用方式+解析SBUS信号