当前位置: 首页 > news >正文

rt-thread的红外遥控开源库使用(裸机版本)记录.

前言

  1. 本驱动运行stm32f407zgt6上已测试ok。
  2. 需要使用定时器驱动。
  3. 使用的是infrared开源库,在此基础上修改
  4. 红外使用的IO口为PA8
  5. 外设驱动使用cubemx生成
  6. 使用了TIM14和GPIO外部中断触发的方式
  7. 这里暂时只做红外接收的移植

infrared开源库(裸机版本)

infrared头文件

/** Copyright (c) 2006-2019, RT-Thread Development Team** SPDX-License-Identifier: Apache-2.0** Change Logs:* Date           Author       Notes* 2019-03-25     balanceTWK   the first version*/#ifndef __INFRARED__
#define __INFRARED__
#include "ringbuffer.h"
#include "decoder.h"#define CARRIER_WAVE         0xA
#define IDLE_SIGNAL          0xB
#define NO_SIGNAL            0x0
#define NEC_DEVIATION 100    // NEC 偏差
#define INFRARED_RECEIVE
// #define INFRARED_SEND
#define MAX_SIZE             5
#define INFRARED_BUFF_SIZE   500struct ir_raw_data
{uint32_t level : 4,us : 28;
};struct decoder_ops
{int (*init)(void);int (*deinit)(void);int (*read)(struct infrared_decoder_data* data);int (*write)(struct infrared_decoder_data* data);int (*decode)(size_t size);int (*control)(int cmd, void* arg);
};struct decoder_class
{char* name;struct decoder_ops* ops;void* user_data;
};struct infrared_class
{struct decoder_class* current_decoder;struct decoder_class* decoder_tab[MAX_SIZE];uint32_t count;struct rt_ringbuffer* ringbuff;size_t (*send)(struct ir_raw_data* data, size_t size);
};int driver_report_raw_data(uint8_t level, uint32_t us);struct infrared_class* infrared_init(void);
int infrared_deinit(void);int ir_decoder_register(struct decoder_class* decoder);int ir_select_decoder(const char* name);int decoder_read_data(struct ir_raw_data* data);
int decoder_write_data(struct ir_raw_data* data, size_t size);int infrared_read(const char* decoder_name, struct infrared_decoder_data* data);
int infrared_write(const char* decoder_name, struct infrared_decoder_data* data);#endif /* __INFRARED__ */

infrared 源文件

/** Copyright (c) 2006-2019, RT-Thread Development Team** SPDX-License-Identifier: Apache-2.0** Change Logs:* Date           Author       Notes* 2019-03-25     balanceTWK   the first version*/#include <infrared.h>static struct infrared_class infrared;struct decoder_class* ir_find_decoder(const char* name)
{for (uint8_t i = 0; i < infrared.count; i++){if (strcmp(infrared.decoder_tab[i]->name, name) == 0){return infrared.decoder_tab[i];}}return NULL;
}int ir_select_decoder(const char* name) /* Selective decoder */
{struct decoder_class* decoder = ir_find_decoder(name);if (decoder){if (infrared.current_decoder){infrared.current_decoder->ops->deinit();}infrared.current_decoder = decoder;if (infrared.current_decoder->ops->init){infrared.current_decoder->ops->init();}LOG_D("select decoder name:%s\n", infrared.decoder_tab[i]->name);return 0;}LOG_W("The decoder%s cannot be found", name);return -ERROR;
}int ir_decoder_register(struct decoder_class* decoder) /* Registered decoder */
{infrared.decoder_tab[infrared.count] = decoder;infrared.count++;return 0;
}int decoder_read_data(struct ir_raw_data* data)
{if(rt_ringbuffer_get(infrared.ringbuff, (uint8_t*)data, 4) == sizeof(struct ir_raw_data)){LOG_D("rt_ringbuffer get success | %01X:%d",data->level,data->us);return 0;}else{return -1;}
}int driver_report_raw_data(uint8_t level, uint32_t us) /* Low-level driver usage */
{struct ir_raw_data data;if (infrared.current_decoder){data.level = level;data.us = us;if( rt_ringbuffer_put(infrared.ringbuff, (uint8_t*)&data, sizeof(struct ir_raw_data)) == sizeof(struct ir_raw_data) ){LOG_D("it_ringbuffer put success | count:%d;0x%01X;us:%d",(rt_ringbuffer_data_len(&infrared.ir_ringbuff)/sizeof(struct ir_raw_data)),data.level,data.us);infrared.current_decoder->ops->decode(rt_ringbuffer_data_len(infrared.ringbuff)/4);}else{LOG_E("ir_ringbuffer put fail");}return 0;}return -ERROR;
}struct infrared_class* infrared_init(void) /* Initializes the necessary functions of the decoder */
{if(!infrared.ringbuff){infrared.ringbuff = rt_ringbuffer_create((INFRARED_BUFF_SIZE*(sizeof(struct ir_raw_data))));}return &infrared;
}int infrared_deinit(void) /* release resource */
{rt_ringbuffer_destroy(infrared.ringbuff);return 0;
}int decoder_write_data(struct ir_raw_data* data, size_t size)
{infrared.send(data, size);return 0;
}int infrared_read(const char* decoder_name, struct infrared_decoder_data* data)
{struct decoder_class* decoder;if (decoder_name){decoder = ir_find_decoder(decoder_name);}else{decoder = infrared.current_decoder;}if (decoder){return decoder->ops->read(data);}return -ERROR;
}int infrared_write(const char* decoder_name, struct infrared_decoder_data* data)
{struct decoder_class* decoder;if (decoder_name){decoder = ir_find_decoder(decoder_name);}else{decoder = infrared.current_decoder;}if (decoder){return decoder->ops->write(data);}return -ERROR;
}

decoder头文件

/** Copyright (c) 2006-2018, RT-Thread Development Team** SPDX-License-Identifier: Apache-2.0** Change Logs:* Date           Author            Notes* 2018-08-26     balanceTWK        the first version*/#ifndef __DECODER_H__
#define __DECODER_H__
#include <stm32f4xx_hal.h>
#define LOG_D(...)
#define LOG_W(...)
#define LOG_E(...)struct nec_data_struct
{uint8_t addr;uint8_t key;uint8_t repeat;
};struct infrared_decoder_data
{union {struct nec_data_struct    nec;          /* Temperature.         unit: dCelsius    */}data;
};#endif

nec_decoder头文件

/********************************************************************************* @file           : nec_decoder.h* @author         : shchl* @brief          : None* @version        : 1.0* @attention      : None* @date           : 25-6-14******************************************************************************
*/#ifndef NEC_DECODER_H
#define NEC_DECODER_H
int nec_decoder_register(void);
#endif //NEC_DECODER_H

nec_decoder源文件

/** Copyright (c) 2006-2019, RT-Thread Development Team** SPDX-License-Identifier: Apache-2.0** Change Logs:* Date           Author       Notes* 2019-03-25     balanceTWK   the first version*/#include <infrared.h>
#include "nec_decoder.h"#define NEC_BUFF_SIZE  32static struct decoder_class nec_decoder;
static struct rt_ringbuffer* ringbuff;static struct ir_raw_data* read_raw_data;
static struct ir_raw_data* write_raw_data;static int nec_decoder_init(void)
{if ((!ringbuff) || (!read_raw_data) || (write_raw_data)){ringbuff = rt_ringbuffer_create(sizeof(struct nec_data_struct) * NEC_BUFF_SIZE);read_raw_data = malloc(sizeof(struct ir_raw_data) * 200);write_raw_data = malloc(sizeof(struct ir_raw_data) * 100);if (ringbuff){nec_decoder.user_data = ringbuff;return 0;}}return -1;
}static int nec_decoder_deinit(void)
{rt_ringbuffer_destroy(ringbuff);free(read_raw_data);free(write_raw_data);return 0;
}static int nec_decoder_read(struct infrared_decoder_data* nec_data)
{if (rt_ringbuffer_get(ringbuff, (uint8_t*)&(nec_data->data.nec), sizeof(struct nec_data_struct)) == sizeof(structnec_data_struct)){LOG_D("NEC addr:0x%01X key:0x%01X repeat:%d", nec_data->data.nec.addr, nec_data->data.nec.key,nec_data->data.nec.repeat);return 0;}return -1;
}static int nec_decoder_control(int cmd, void* arg)
{return 0;
}static int nec_decoder_decode(size_t size)
{static uint8_t nec_state = 0;static struct ir_raw_data state_code[2];static struct nec_data_struct nec_data;static uint32_t command;uint8_t t1, t2;LOG_D("size:%d", size);if (nec_state == 0x01){if (size == 65){for (uint8_t i = 0; i < 65; i++){decoder_read_data(&read_raw_data[i]);if (read_raw_data[i].level == IDLE_SIGNAL){LOG_D("IDLE_SIGNAL,LINE:%d", __LINE__);if ((read_raw_data[i].us > (1690 - NEC_DEVIATION)) && (read_raw_data[i].us < (1690 +NEC_DEVIATION))){LOG_D(" 1 LINE:%d", __LINE__);command <<= 1;command |= 1;}else if ((read_raw_data[i].us > (560 - NEC_DEVIATION)) && (read_raw_data[i].us < (560 +NEC_DEVIATION))){LOG_D(" 0 LINE:%d", __LINE__);command <<= 1;command |= 0;}}else if ((i == 64) && ((read_raw_data[i].us > (560 - NEC_DEVIATION)) && (read_raw_data[i].us < (560 +NEC_DEVIATION)))){t1 = command >> 8;t2 = command;LOG_D("1 t1:0x%01X t2:0x%01X", t1, t2);if (t1 == (uint8_t)~t2){nec_data.key = t1;t1 = command >> 24;t2 = command >> 16;LOG_D("2 t1:0x%01X t2:0x%01X", t1, t2);if (t1 == (uint8_t)~t2){nec_data.addr = t1;nec_data.repeat = 0;rt_ringbuffer_put(ringbuff, (uint8_t*)&nec_data, sizeof(struct nec_data_struct));LOG_D("OK");nec_state = 0x00;}else{nec_state = 0x00;nec_data.addr = 0;nec_data.key = 0;nec_data.repeat = 0;}}else{nec_state = 0x00;nec_data.addr = 0;nec_data.key = 0;nec_data.repeat = 0;}}}}}else if (nec_state == 0x04){decoder_read_data(&state_code[1]);if ((state_code[1].level == IDLE_SIGNAL) && ((state_code[1].us > 4000) && (state_code[1].us < 5000)))/* if guidance code 4500us */{nec_state = 0x01;LOG_D("guidance");}else if ((state_code[1].level == IDLE_SIGNAL) && ((state_code[1].us > 2150) && (state_code[1].us < 2350)))/* if repetition code 2250us */{nec_data.repeat++;nec_state = 0x00;rt_ringbuffer_put(ringbuff, (uint8_t*)&nec_data, sizeof(struct nec_data_struct));LOG_D("repeat");}else{nec_data.repeat = 0;nec_state = 0x00;LOG_D("no guidance");state_code[0].level = NO_SIGNAL;state_code[1].level = NO_SIGNAL;return -1;}}else{decoder_read_data(&state_code[0]);if ((state_code[0].level == CARRIER_WAVE) && ((state_code[0].us > 8500) && (state_code[0].us < 9500)))/* if (guidance code or repetition code) */{nec_state = 0x04;}else{nec_state = 0x00;LOG_D("no 9000us:%d", state_code[0].us);return -1;}}return 0;
}static int nec_decoder_write(struct infrared_decoder_data* data)
{uint8_t addr, key;uint32_t data_buff;addr = data->data.nec.addr;key = data->data.nec.key;data_buff = ((addr & 0xFF) << 24) + ((~addr & 0xFF) << 16) + ((key & 0xff) << 8) + (~key & 0xFF);/* guidance code */write_raw_data[0].level = CARRIER_WAVE;write_raw_data[0].us = 9000;write_raw_data[1].level = IDLE_SIGNAL;write_raw_data[1].us = 4500;for (uint8_t index = 0; index < 64; index += 2){if (((data_buff << (index / 2)) & 0x80000000)) /* Logic 1 */{write_raw_data[2 + index].level = CARRIER_WAVE;write_raw_data[2 + index].us = 560;write_raw_data[2 + index + 1].level = IDLE_SIGNAL;write_raw_data[2 + index + 1].us = 1690;}else /* Logic 0 */{write_raw_data[2 + index].level = CARRIER_WAVE;write_raw_data[2 + index].us = 560;write_raw_data[2 + index + 1].level = IDLE_SIGNAL;write_raw_data[2 + index + 1].us = 560;}}/* epilog code */write_raw_data[66].level = CARRIER_WAVE;write_raw_data[66].us = 560;write_raw_data[67].level = IDLE_SIGNAL;write_raw_data[67].us = 43580;if (data->data.nec.repeat > 8){data->data.nec.repeat = 8;}/* repetition code */for (uint32_t i = 0; i < (4 * data->data.nec.repeat); i += 4){write_raw_data[68 + i].level = CARRIER_WAVE;write_raw_data[68 + i].us = 9000;write_raw_data[68 + i + 1].level = IDLE_SIGNAL;write_raw_data[68 + i + 1].us = 2250;write_raw_data[68 + i + 2].level = CARRIER_WAVE;write_raw_data[68 + i + 2].us = 560;write_raw_data[68 + i + 3].level = IDLE_SIGNAL;write_raw_data[68 + i + 3].us = 43580;}LOG_D("%d size:%d + %d", sizeof(struct ir_raw_data), 68, (data->data.nec.repeat) * 4);decoder_write_data(write_raw_data, 68 + (data->data.nec.repeat) * 4);HAL_Delay(200);return 0;
}int nec_decoder_register()
{static struct decoder_ops ops = {0};nec_decoder.name = "nec";ops.control = nec_decoder_control;ops.decode = nec_decoder_decode;ops.init = nec_decoder_init;ops.deinit = nec_decoder_deinit;ops.read = nec_decoder_read;ops.write = nec_decoder_write;nec_decoder.ops = &ops;ir_decoder_register(&nec_decoder);return 0;
}

infrared驱动文件(对接stm32)

drv_infrared 头文件

/** Copyright (c) 2006-2018, RT-Thread Development Team** SPDX-License-Identifier: Apache-2.0** Change Logs:* Date           Author            Notes* 2018-08-26     balanceTWK        the first version*/#ifndef __DRV_INFRARED_H__
#define __DRV_INFRARED_H__int drv_infrared_init(void);#endif

drv_infrared 源文件

/** Copyright (c) 2006-2019, RT-Thread Development Team** SPDX-License-Identifier: Apache-2.0** Change Logs:* Date           Author       Notes* 2019-03-25     balanceTWK   the first version*/#include "drv_hwtimer.h"
#include "infrared.h"
#include "drv_infrared.h"static struct infrared_class* infrared;#ifdef INFRARED_SEND/* Infrared transmission configuration parameters */
#define PWM_DEV_NAME              INFRARED_SEND_PWM         /* PWM name */
#define PWM_DEV_CHANNEL           INFRARED_PWM_DEV_CHANNEL
#define SEND_HWTIMER              INFRARED_SEND_HWTIMER     /* Timer name */
#define MAX_SEND_SIZE             INFRARED_MAX_SEND_SIZEstruct rt_device_pwm         *pwm_dev;
static rt_uint32_t  infrared_send_buf[MAX_SEND_SIZE];
static rt_device_t           send_time_dev ;
static rt_hwtimerval_t       timeout_s;static rt_err_t send_timeout_callback(rt_device_t dev, rt_size_t size)
{static rt_size_t i = 0;rt_pwm_disable(pwm_dev, PWM_DEV_CHANNEL);if ((infrared_send_buf[i] != 0x5A5A5A5A))/* Determine if it is a stop bit */{if ((infrared_send_buf[i] & 0xF0000000) == 0xA0000000) /* Determine if it is a carrier signal */{rt_pwm_enable(pwm_dev, PWM_DEV_CHANNEL);}timeout_s.sec = 0;timeout_s.usec = (infrared_send_buf[i] & 0x0FFFFFFF); /* Get the delay time */rt_device_write(send_time_dev, 0, &timeout_s, sizeof(timeout_s));i++;}else{i = 0;}return 0;
}rt_err_t infrared_send_init(void)
{rt_err_t ret = RT_EOK;rt_hwtimer_mode_t mode;rt_uint32_t freq = 1000000;pwm_dev = (struct rt_device_pwm *)rt_device_find(PWM_DEV_NAME);if (pwm_dev == RT_NULL){LOG_E("pwm sample run failed! can't find %s device!", PWM_DEV_NAME);return RT_ERROR;}rt_pwm_set(pwm_dev, PWM_DEV_CHANNEL, 26316, 8770);rt_pwm_disable(pwm_dev, PWM_DEV_CHANNEL);send_time_dev = rt_device_find(SEND_HWTIMER);if (send_time_dev == RT_NULL){LOG_E("hwtimer sample run failed! can't find %s device!", SEND_HWTIMER);return RT_ERROR;}ret = rt_device_open(send_time_dev, RT_DEVICE_OFLAG_RDWR);if (ret != RT_EOK){LOG_E("open %s device failed!\n", SEND_HWTIMER);return ret;}rt_device_set_rx_indicate(send_time_dev, send_timeout_callback);ret = rt_device_control(send_time_dev, HWTIMER_CTRL_FREQ_SET, &freq);if (ret != RT_EOK){LOG_E("set frequency failed! ret is :%d", ret);return ret;}mode = HWTIMER_MODE_ONESHOT;ret = rt_device_control(send_time_dev, HWTIMER_CTRL_MODE_SET, &mode);if (ret != RT_EOK){LOG_E("set mode failed! ret is :%d", ret);return ret;}return ret;
}static rt_size_t infrared_send(struct ir_raw_data* data, rt_size_t size)
{rt_size_t send_size;if(size >= MAX_SEND_SIZE){LOG_E("The length of the sent data exceeds the MAX_SEND_SIZE.");return 0;}for (send_size = 0; send_size < size; send_size++){infrared_send_buf[send_size] = (data[send_size].level<<28) + (data[send_size].us);}infrared_send_buf[size] = 0x5A5A5A5A;timeout_s.sec = 0;timeout_s.usec = 500;rt_device_write(send_time_dev, 0, &timeout_s, sizeof(timeout_s));rt_thread_mdelay(100);return send_size;
}#endif /* INFRARED_SEND */#ifdef INFRARED_RECEIVE
#define RECEIVE_HWTIMEER_SEC      0
#define RECEIVE_HWTIMEER_USEC     1000000static uint32_t diff_us;
static uint32_t receive_flag = 0x00000000;
static struct rt_hwtimer_device* receive_time_dev = NULL;void receive_pin_callback(void)
{static rt_hwtimerval_t receive_time;static uint32_t last_us = 0, now_us;if ((receive_flag & (1 << 0))){rt_hwtimer_read(receive_time_dev, &receive_time);now_us = (receive_time.sec * 1000000) + receive_time.usec;if (now_us >= last_us){diff_us = now_us - last_us;}else{diff_us = now_us + RECEIVE_HWTIMEER_SEC * 1000000 + RECEIVE_HWTIMEER_USEC;}if (HAL_GPIO_ReadPin(GPIOA,GPIO_PIN_8) == GPIO_PIN_SET){driver_report_raw_data(CARRIER_WAVE, diff_us);LOG_D("H%d", diff_us);}else{driver_report_raw_data(IDLE_SIGNAL, diff_us);LOG_D("L%d", diff_us);}last_us = now_us;}else{receive_time.sec = RECEIVE_HWTIMEER_SEC;receive_time.usec = RECEIVE_HWTIMEER_USEC;rt_hwtimer_write(receive_time_dev, &receive_time);receive_flag |= 1 << 0;last_us = 0;LOG_D("Start timer");}
}static int receive_timeout_callback(rt_hwtimer_t* rt_hwtimer)
{if (diff_us > (1000 * 1000)){rt_hwtimer_control(receive_time_dev, HWTIMER_CTRL_STOP, NULL);LOG_D("timeout and stop");receive_flag &= ~(1 << 0);}diff_us = diff_us + RECEIVE_HWTIMEER_SEC * 1000000 + RECEIVE_HWTIMEER_USEC;return 0;
}int infrared_receive_init(void)
{rt_hwtimer_mode_t mode;uint32_t freq = 100000;// 红外接收IO 初始化// 接收定时器初始化receive_time_dev = stm32_hwtimer_get(TIM14_INDEX);if (receive_time_dev == NULL){LOG_E("hwtimer sample run failed! can't find %s device!", RECEIVE_HWTIMER);return 1;}rt_hwtimer_init(receive_time_dev);rt_hwtimer_open(receive_time_dev);receive_time_dev->rx_indicate = receive_timeout_callback;rt_hwtimer_control(receive_time_dev, HWTIMER_CTRL_FREQ_SET, &freq);mode = HWTIMER_MODE_PERIOD;rt_hwtimer_control(receive_time_dev, HWTIMER_CTRL_MODE_SET, &mode);return 0;
}#endif /* INFRARED_RECEIVE */int drv_infrared_init()
{infrared = infrared_init();if (infrared == NULL){return -1;}#ifdef INFRARED_SENDinfrared_send_init();infrared->send = infrared_send;
#endif /* INFRARED_SEND */#ifdef INFRARED_RECEIVEinfrared_receive_init();
#endif /* INFRARED_RECEIVE */return 0;
}

测试

主函数

/* USER CODE BEGIN Header */
/********************************************************************************* @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 "dma.h"
#include "tim.h"
#include "usart.h"
#include "gpio.h"/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
#include "infrared.h"
#include "drv_hwtimer.h"
#include "nec_decoder.h"
#include "drv_infrared.h"/* USER CODE END Includes *//* Private typedef -----------------------------------------------------------*/
/* USER CODE BEGIN PTD *//* USER CODE END PTD *//* Private define ------------------------------------------------------------*/
/* USER CODE BEGIN PD *//* USER CODE END PD *//* Private macro -------------------------------------------------------------*/
/* USER CODE BEGIN PM *//* USER CODE END PM *//* Private variables ---------------------------------------------------------*//* USER CODE BEGIN PV *//* USER CODE END PV *//* Private function prototypes -----------------------------------------------*/
void SystemClock_Config(void);
/* USER CODE BEGIN PFP */static void infrared_test(void);
/* USER CODE END PFP *//* Private user code ---------------------------------------------------------*/
/* USER CODE BEGIN 0 */int receive_timeout_callback(rt_hwtimer_t* rt_hwtimer)
{printf("%d\r\n", HAL_GetTick());return 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_USART1_UART_Init();MX_TIM14_Init();/* USER CODE BEGIN 2 */// 开启串口dma接收usart1_open_receive();stm32_hwtimer_init();infrared_test();/* USER CODE END 2 *//* Infinite loop *//* USER CODE BEGIN WHILE */while (1){/* USER CODE END WHILE *//* USER CODE BEGIN 3 */HAL_Delay(1000);}/* USER CODE END 3 */
}/*** @brief System Clock Configuration* @retval None*/
void SystemClock_Config(void)
{RCC_OscInitTypeDef RCC_OscInitStruct = {0};RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};/** Configure the main internal regulator output voltage*/__HAL_RCC_PWR_CLK_ENABLE();__HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1);/** Initializes the RCC Oscillators according to the specified parameters* in the RCC_OscInitTypeDef structure.*/RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;RCC_OscInitStruct.HSEState = RCC_HSE_ON;RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;RCC_OscInitStruct.PLL.PLLM = 4;RCC_OscInitStruct.PLL.PLLN = 168;RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2;RCC_OscInitStruct.PLL.PLLQ = 4;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_DIV4;RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2;if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_5) != HAL_OK){Error_Handler();}
}/* USER CODE BEGIN 4 */
static void infrared_test(void)
{nec_decoder_register();drv_infrared_init();struct infrared_decoder_data infrared_data;ir_select_decoder("nec");while (1){/* 读取数据 */if (infrared_read("nec", &infrared_data) == 0){if (infrared_data.data.nec.repeat){printf("repeat%d\r\n", infrared_data.data.nec.repeat);}else{printf("APP addr:0x%02X key:0x%02X\r\n", infrared_data.data.nec.addr, infrared_data.data.nec.key);}}// HAL_Delay(10);__WFI();}
}/* 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 */

结果

在这里插入图片描述

相关文章:

  • Flutter 与原生技术(Objective-C/Swift,java)的关系
  • 【MFC】编辑框、下拉框、列表控件
  • 位运算详解之异或运算的奇妙操作
  • org.springframework.cloud.openfeign 组件解释
  • Spring Framework 执行链路设计
  • 大模型笔记1:大致了解大模型
  • MLLM常见概念通俗解析(五)
  • 【Redis】Redis的启航之路:Ubantu操作系统下安装Redis
  • ABP vNext 多语言与本地化:动态切换、资源继承与热更新
  • 微信小程序使用图片实现红包雨功能
  • error:MISCONF Redis is configured to save RDB snapshots
  • 计算机网络-自顶向下—第五章数据链路层重点复习笔记
  • 《高并发系统性能优化三板斧:缓存 + 异步 + 限流》
  • Nginx+keepalived主从,双主架构
  • git-build-package 工具代码详细解读
  • Git常用命令摘要
  • 青少年编程与数学 01-011 系统软件简介 19 SSMS 数据库管理工具
  • 【AS32系列MCU调试教程】性能优化:Eclipse环境下AS32芯片调试效率提升
  • Java 与 MySQL 性能优化:Linux服务器上MySQL性能指标解读与监控方法
  • Spring MVC 中日期格式转换的两种实用方法
  • 物流企业网站有哪些/免费推广引流软件
  • 旅游网站制作建设/广告联盟推广
  • 华为云怎么做网站/app开发网站
  • 做网站的模仿还要去量宽高吗/必应搜索引擎入口
  • 网页设计作品网站/seo如何优化
  • 网站建设公司苏州/网络推广一般怎么收费