From 3db2a20a0e400a1c68a41f7f30d962909f8ed828 Mon Sep 17 00:00:00 2001 From: NeoZng Date: Wed, 4 Jan 2023 21:26:11 +0800 Subject: [PATCH] =?UTF-8?q?=E6=B7=BB=E5=8A=A0=E4=BA=86=E9=81=A5=E6=8E=A7?= =?UTF-8?q?=E5=99=A8=E7=9A=84=E7=A6=BB=E7=BA=BF=E6=A3=80=E6=B5=8B=E5=92=8C?= =?UTF-8?q?daemone=E7=9A=84=E8=AF=B4=E6=98=8E=E6=96=87=E6=A1=A3?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- application/application.md | 2 +- application/chassis/chassis.c | 22 +++++++++---------- application/cmd/robot_cmd.c | 2 +- application/robot_def.h | 2 +- bsp/bsp.md | 6 ++++- bsp/bsp_init.h | 1 + bsp/can/bsp_can.h | 2 ++ bsp/pwm/bsp_pwm.c | 7 +++--- bsp/usart/bsp_usart.c | 21 +++++++++++++++++- bsp/usart/bsp_usart.h | 16 ++++++++++++++ modules/daemon/daemon.md | 35 ++++++++++++++++++++++++++++-- modules/motor/DJImotor/dji_motor.c | 26 ++++++++++++---------- modules/referee/referee.c | 4 ++-- modules/remote/remote_control.c | 30 ++++++++++++++++++++----- 14 files changed, 135 insertions(+), 41 deletions(-) diff --git a/application/application.md b/application/application.md index a68e948..0cf386f 100644 --- a/application/application.md +++ b/application/application.md @@ -10,7 +10,7 @@ 在main函数中包含`robot.h`头文件,这是对整车的抽象。将`INStask`,`motortask`,`ledtask`,`monitortask`这四个task加入`freertos.c`中,创建对应的任务,设置合适的任务运行间隔;然后将`robottask`放入freertos.c中,同样以一定的频率运行。 在初始化实时系统之前,在`main()`中调用`RobotInit()`进行整车的初始化。 -INStask的运行频率为1kHz,motortask推荐的运行频率为200Hz\~500Hz,对于高实时性要求的电机可以提升到1kHz,不过要注意CAN总线的负载。ledtask的运行频率推荐为1kHz,monitortask的运行频率推荐为50\~100Hz;robottask的运行频率推荐为150Hz以上,应当高于视觉发送的频率,若后续使用插帧,应该保证不低过motortask太多。 +**关于运行的任务**,INStask的运行频率必须为1kHz,motortask推荐的运行频率为200Hz\~500Hz(详情见module/motor/motor_task.c),在MotorTask内部,对于高实时性要求的电机可以提升到1kHz,不过要注意CAN总线的负载。ledtask的运行频率推荐为1kHz,monitortask的运行频率为1kHz;robottask的运行频率推荐为150Hz以上,应当高于视觉发送的频率,若后续使用插帧,同样应该保证不低过motortask太多。 若使用双板,则在`robot_def.h`中给对应的开发板设定宏定义,如底盘板使用`#define CHASSIS_BOARD`,云台板使用`#define GIMBAL_BOARD`;单个开发板控制整车,则定义`#define ONE_BOARD`。在每个应用中,都已经使用编译预处理指令完成条件编译,会自动根据设定的宏切换功能。使用双板的时候,目前板间通信通过CAN完成,因此两个开发板会挂载在一条总线上,在两个开发板对这条总线的其他使用CAN的设备进行配置时注意**不要发生ID冲突**,还要注意**防止负载过大**。 diff --git a/application/chassis/chassis.c b/application/chassis/chassis.c index 3ba9d2a..e30a9fe 100644 --- a/application/chassis/chassis.c +++ b/application/chassis/chassis.c @@ -23,8 +23,8 @@ #include "arm_math.h" /* 根据robot_def.h中的macro自动计算的参数 */ -#define HALF_WHEEL_BASE (WHEEL_BASE / 2.0f) // 半轴距 -#define HALF_TRACK_WIDTH (TRACK_WIDTH / 2.0f) // 半轮距 +#define HALF_WHEEL_BASE (WHEEL_BASE / 2.0f) // 半轴距 +#define HALF_TRACK_WIDTH (TRACK_WIDTH / 2.0f) // 半轮距 #define PERIMETER_WHEEL (RADIUS_WHEEL * 2 * PI) // 轮子周长 /* 底盘应用包含的模块和信息存储,底盘是单例模式,因此不需要为底盘建立单独的结构体 */ @@ -35,16 +35,16 @@ static CANCommInstance *chasiss_can_comm; // 双板通信CAN comm attitude_t *Chassis_IMU_data; #endif // CHASSIS_BOARD #ifdef ONE_BOARD -static Publisher_t *chassis_pub; // 用于发布底盘的数据 -static Subscriber_t *chassis_sub; // 用于订阅底盘的控制命令 -#endif // ONE_BOARD +static Publisher_t *chassis_pub; // 用于发布底盘的数据 +static Subscriber_t *chassis_sub; // 用于订阅底盘的控制命令 +#endif // !ONE_BOARD static Chassis_Ctrl_Cmd_s chassis_cmd_recv; // 底盘接收到的控制命令 static Chassis_Upload_Data_s chassis_feedback_data; // 底盘回传的反馈数据 static referee_info_t *referee_data; // 裁判系统的数据 static SuperCapInstance *cap; // 超级电容 static DJIMotorInstance *motor_lf; // left right forward back -static DJIMotorInstance *motor_rf; +static DJIMotorInstance *motor_rf; static DJIMotorInstance *motor_lb; static DJIMotorInstance *motor_rb; @@ -104,8 +104,8 @@ void ChassisInit() SuperCap_Init_Config_s cap_conf = { .can_config = { .can_handle = &hcan2, - .tx_id = 0x302, - .rx_id = 0x301, + .tx_id = 0x302, // 超级电容默认接收id + .rx_id = 0x301, // 超级电容默认发送id,注意tx和rx在其他人看来是反的 }}; cap = SuperCapInit(&cap_conf); // 超级电容初始化 @@ -207,13 +207,13 @@ void ChassisTask() switch (chassis_cmd_recv.chassis_mode) { case CHASSIS_NO_FOLLOW: // 底盘不旋转,但维持全向机动,一般用于调整云台姿态 - chassis_cmd_recv.wz = 0; + chassis_cmd_recv.wz = 0; break; case CHASSIS_FOLLOW_GIMBAL_YAW: // 跟随云台,不单独设置pid,以误差角度平方为速度输出 - chassis_cmd_recv.wz = 0.05f * powf(chassis_cmd_recv.wz, 2.0f); + chassis_cmd_recv.wz = 0.05f * powf(chassis_cmd_recv.wz, 2.0f); break; case CHASSIS_ROTATE: // 自旋,同时保持全向机动;当前wz维持定值,后续增加不规则的变速策略 - // chassis_cmd_recv.wz=sin(t) + // chassis_cmd_recv.wz=sin(t) break; default: break; diff --git a/application/cmd/robot_cmd.c b/application/cmd/robot_cmd.c index e10d066..ebfac6b 100644 --- a/application/cmd/robot_cmd.c +++ b/application/cmd/robot_cmd.c @@ -19,7 +19,7 @@ static CANCommInstance *cmd_can_comm; // 双板通信 #ifdef ONE_BOARD static Publisher_t *chassis_cmd_pub; // 底盘控制消息发布者 static Subscriber_t *chassis_feed_sub; // 底盘反馈信息订阅者 -#endif // ONE_BOARD +#endif // ONE_BOARD static Chassis_Ctrl_Cmd_s chassis_cmd_send; // 发送给底盘应用的信息,包括控制信息和UI绘制相关 static Chassis_Upload_Data_s chassis_fetch_data; // 从底盘应用接收的反馈信息信息,底盘功率枪口热量与底盘运动状态等 diff --git a/application/robot_def.h b/application/robot_def.h index fd54a12..a4fe70d 100644 --- a/application/robot_def.h +++ b/application/robot_def.h @@ -209,6 +209,6 @@ typedef struct // ... } Shoot_Upload_Data_s; -#pragma pack() // 开启字节对齐 +#pragma pack() // 开启字节对齐,结束前面的#pragma pack(1) #endif // !ROBOT_DEF_H \ No newline at end of file diff --git a/bsp/bsp.md b/bsp/bsp.md index 5ba7067..c78fe95 100644 --- a/bsp/bsp.md +++ b/bsp/bsp.md @@ -7,4 +7,8 @@ BSP > 2. 增加外部中断支持 > 3. 增加软件中断支持 > 4. 增加硬件CRC支持 -> 5. 增加USB和虚拟串口支持 \ No newline at end of file +> 5. 增加USB和虚拟串口支持 + +bsp的功能是提供对片上外设的封装,即单片机芯片内部拥有的功能的封装。在开发板pcb上集成的模块应该放在module层而不是这里。 + +bsp应该提供几种接口。包括初始化接口,一般命名为`XXXRegister()`;调用此模块实现的必要功能,如通信型外设(CubeMX下的connectivity)提供接收和发送的接口,以及接收完成的数据回调函数。 \ No newline at end of file diff --git a/bsp/bsp_init.h b/bsp/bsp_init.h index 4fa60c4..72c3372 100644 --- a/bsp/bsp_init.h +++ b/bsp/bsp_init.h @@ -4,6 +4,7 @@ /** * @brief bsp层初始化统一入口,这里仅初始化必须的bsp组件,其他组件的初始化在各自的模块中进行 + * 需在实时系统启动前调用,目前由RobotoInit()调用 * */ void BSPInit(); diff --git a/bsp/can/bsp_can.h b/bsp/can/bsp_can.h index c24817a..7391fc2 100644 --- a/bsp/can/bsp_can.h +++ b/bsp/can/bsp_can.h @@ -57,6 +57,8 @@ void CANSetDLC(CANInstance *_instance, uint8_t length); * @brief transmit mesg through CAN device,通过can实例发送消息 * 发送前需要向CAN实例的tx_buff写入发送数据 * + * @attention 超时时间不应该超过调用此函数的任务的周期,否则会导致任务阻塞 + * * @param timeout 超时时间,单位为ms;后续改为us,获得更精确的控制 * @param _instance* can instance owned by module */ diff --git a/bsp/pwm/bsp_pwm.c b/bsp/pwm/bsp_pwm.c index 0331c90..eb51aca 100644 --- a/bsp/pwm/bsp_pwm.c +++ b/bsp/pwm/bsp_pwm.c @@ -14,7 +14,6 @@ void HAL_TIM_PWM_PulseFinishedCallback(TIM_HandleTypeDef *htim) { if (pwm_instance[i]->callback) // 如果有回调函数 pwm_instance[i]->callback(pwm_instance[i]); - return; // 一次只能有一个通道的中断,所以直接返回 } } @@ -34,9 +33,9 @@ PWMInstance *PWMRegister(PWM_Init_Config_s *config) pwm->pulse = config->pulse; pwm->callback = config->callback; pwm->id = config->id; - - HAL_TIM_PWM_Start(pwm->htim, pwm->channel); // 启动PWM - __HAL_TIM_SetCompare(pwm->htim, pwm->channel, pwm->pulse); // 设置占空比,初始为0 + // 启动PWM + HAL_TIM_PWM_Start(pwm->htim, pwm->channel); + __HAL_TIM_SetCompare(pwm->htim, pwm->channel, pwm->pulse); // 设置占空比 pwm_instance[idx++] = pwm; return pwm; diff --git a/bsp/usart/bsp_usart.c b/bsp/usart/bsp_usart.c index 4d0fcb5..31fb0b2 100644 --- a/bsp/usart/bsp_usart.c +++ b/bsp/usart/bsp_usart.c @@ -19,7 +19,9 @@ static USARTInstance *usart_instance[DEVICE_USART_CNT] = {NULL}; /** * @brief usart service will start automatically, after each module registered - * 串口服务会在每个实例注册之后自动启用 + * + * @todo 串口服务会在每个实例注册之后自动启用接收,当前实现为DMA接收,后续可能添加IT和BLOCKING接收 + * 可能还要将此函数修改为extern,使得module可以控制串口的启停 * * @param _instance instance owned by module,模块拥有的串口实例 */ @@ -55,6 +57,23 @@ void USARTSend(USARTInstance *_instance, uint8_t *send_buf, uint16_t send_size) HAL_UART_Transmit_DMA(_instance->usart_handle, send_buf, send_size); } +void USARTAbort(USARTInstance *_instance, USART_TRANSFER_MODE mode) +{ + switch (mode) + { + case USART_TRANSFER_TX: + // if(_instance.work_mode == USART_TX_DMA) + HAL_UART_AbortTransmit_IT(_instance->usart_handle); + break; + case USART_TRANSFER_RX: + // if(_instance.work_mode == USART_RX_DMA) + HAL_UART_AbortReceive_IT(_instance->usart_handle); + break; + case USART_TRANSFER_NONE: + break; + } +} + /** * @brief 每次dma/idle中断发生时,都会调用此函数.对于每个uart实例会调用对应的回调进行进一步的处理 * 例如:视觉协议解析/遥控器解析/裁判系统解析 diff --git a/bsp/usart/bsp_usart.h b/bsp/usart/bsp_usart.h index cb8ccfd..bde0667 100644 --- a/bsp/usart/bsp_usart.h +++ b/bsp/usart/bsp_usart.h @@ -10,6 +10,13 @@ // 模块回调函数,用于解析协议 typedef void (*usart_module_callback)(); +typedef enum +{ + USART_TRANSFER_NONE=0, + USART_TRANSFER_TX, + USART_TRANSFER_RX, +} USART_TRANSFER_MODE; + // 串口实例结构体,每个module都要包含一个实例 typedef struct { @@ -36,6 +43,7 @@ USARTInstance *USARTRegister(USART_Init_Config_s *init_config); /** * @brief 通过调用该函数可以发送一帧数据,需要传入一个usart实例,发送buff以及这一帧的长度 + * 当前默认为DMA发送,后续会增加中断发送和阻塞发送模式的选择 * * @param _instance 串口实例 * @param send_buf 待发送数据的buffer @@ -43,4 +51,12 @@ USARTInstance *USARTRegister(USART_Init_Config_s *init_config); */ void USARTSend(USARTInstance *_instance, uint8_t *send_buf, uint16_t send_size); +/** + * @brief 通过调用该函数终止串口的发送或者接收,通过传入mode参数来选择终止发送还是接收 + * + * @param _instance 串口实例 + * @param mode 选择终止发送还是接收的模式 + */ +void USARTAbort(USARTInstance *_instance,USART_TRANSFER_MODE mode); + #endif diff --git a/modules/daemon/daemon.md b/modules/daemon/daemon.md index 429f977..71be55f 100644 --- a/modules/daemon/daemon.md +++ b/modules/daemon/daemon.md @@ -1,5 +1,36 @@ -daemon +# daemon

neozng1@hnu.edu.cn

-用于监测模块和应用运行情况的module(和官方代码中的deteck task作用相同) \ No newline at end of file +用于监测模块和应用运行情况的module(和官方代码中的deteck task作用相同) + +## 使用范例 + +要使用该module,则包含`daemon.h`的头文件,并在使用daemon的文件中保留一个daemon的指针。 + +初始化的时候,要传入以下参数: + +```c +typedef struct +{ + uint16_t reload_count; // 实际上这是app唯一需要设置的值? + offline_callback callback; // 异常处理函数,当模块发生异常时会被调用 + void *owner_id; // id取拥有daemon的实例的地址,如DJIMotorInstance*,cast成void*类型 +} Daemon_Init_Config_s; +``` + +`reload_count`是”喂狗“时的重载值,一般根据你希望的离线容许时间和模块接收数据/访问数据的频率确定。 + +`daemon_task()`会在实时系统中以1kHz的频率运行,每次运行该任务,都会将所有daemon实例当前的count进行自减操作,当count减为零,则说明模块已经很久没有上线(处于deactivated状态,即没有收到数据,也没有进行其他读写操作)。 + +`offline_callback`是模块离线的回调函数,即当包含daemon的模块发生离线情况时,该函数会被调用以应对离线情况,如重启模块,重新初始化等。如果没有则传入`NULL`即可。 + +`owner_id`即模块取自身地址并通过强制类型转换化为`void*`类型,用于拥有多个实例的模块在`offline_callback`中区分自身。如多个电机都使用一个相同的`offline_callback`,那么在调用回调函数的时候就可以通过该指针来访问某个特定的电机。 + +> 这种方法也称作“parent pointer”,即**保存拥有指向自身的指针对象的地址**。这样就可以在特定的情况下通过自身来访问自己的父对象。 + + + +## 具体实现 + +即`DaemonTask()`,在操作系统中以1kHz运行。注释详细,请参见`daemon.c`。 \ No newline at end of file diff --git a/modules/motor/DJImotor/dji_motor.c b/modules/motor/DJImotor/dji_motor.c index f9c5af3..5ff014a 100644 --- a/modules/motor/DJImotor/dji_motor.c +++ b/modules/motor/DJImotor/dji_motor.c @@ -43,7 +43,8 @@ static void IDcrash_Handler(uint8_t conflict_motor_idx, uint8_t temp_motor_idx) } /** - * @brief 根据电调/拨码开关上的ID,计算发送ID和接收ID,并对电机进行分组以便处理多电机控制命令 + * @brief 根据电调/拨码开关上的ID,根据说明书的默认id分配方式计算发送ID和接收ID, + * 并对电机进行分组以便处理多电机控制命令 * * @param config */ @@ -69,8 +70,8 @@ static void MotorSenderGrouping(DJIMotorInstance *motor, CAN_Init_Config_s *conf } // 计算接收id并设置分组发送id - config->rx_id = 0x200 + motor_id + 1; - sender_enable_flag[motor_grouping] = 1; + config->rx_id = 0x200 + motor_id + 1; // 把ID+1,进行分组设置 + sender_enable_flag[motor_grouping] = 1; // 设置发送标志位,防止发送空帧 motor->message_num = motor_send_num; motor->sender_group = motor_grouping; @@ -94,8 +95,8 @@ static void MotorSenderGrouping(DJIMotorInstance *motor, CAN_Init_Config_s *conf motor_grouping = config->can_handle == &hcan1 ? 2 : 5; } - config->rx_id = 0x204 + motor_id + 1; - sender_enable_flag[motor_grouping] = 1; + config->rx_id = 0x204 + motor_id + 1; // 把ID+1,进行分组设置 + sender_enable_flag[motor_grouping] = 1; // 只要有电机注册到这个分组,置为1;在发送函数中会通过此标志判断是否有电机注册 motor->message_num = motor_send_num; motor->sender_group = motor_grouping; @@ -127,7 +128,7 @@ static void DecodeDJIMotor(CANInstance *_instance) // 这里对can instance的id进行了强制转换,从而获得电机的instance实例地址 measure = &((DJIMotorInstance *)_instance->id)->motor_measure; // measure要多次使用,保存指针减小访存开销 - // 解析数据并对电流和速度进行滤波 + // 解析数据并对电流和速度进行滤波,电机的反馈报文具体格式见电机说明手册 measure->last_ecd = measure->ecd; measure->ecd = ((uint16_t)rxbuff[0]) << 8 | rxbuff[1]; measure->angle_single_round = ECD_ANGLE_COEF_DJI * (float)measure->ecd; @@ -137,7 +138,7 @@ static void DecodeDJIMotor(CANInstance *_instance) CURRENT_SMOOTH_COEF * (float)((int16_t)(rxbuff[4] << 8 | rxbuff[5])); measure->temperate = rxbuff[6]; - // 多圈角度计算,计算的前提是两次采样间电机转过的角度小于180° + // 多圈角度计算,前提是两次采样间电机转过的角度小于180°,高速转动时可能会出现问题,自己画个图就清楚计算过程了 if (measure->ecd - measure->last_ecd > 4096) measure->total_round--; else if (measure->ecd - measure->last_ecd < -4096) @@ -152,8 +153,8 @@ DJIMotorInstance *DJIMotorInit(Motor_Init_Config_s *config) memset(instance, 0, sizeof(DJIMotorInstance)); // motor basic setting 电机基本设置 - instance->motor_type = config->motor_type; - instance->motor_settings = config->controller_setting_init_config; + instance->motor_type = config->motor_type; // 6020 or 2006 or 3508 + instance->motor_settings = config->controller_setting_init_config; // 正反转,闭环类型等 // motor controller init 电机控制器初始化 PID_Init(&instance->motor_controller.current_PID, &config->controller_param_init_config.current_PID); @@ -161,6 +162,7 @@ DJIMotorInstance *DJIMotorInit(Motor_Init_Config_s *config) PID_Init(&instance->motor_controller.angle_PID, &config->controller_param_init_config.angle_PID); instance->motor_controller.other_angle_feedback_ptr = config->controller_param_init_config.other_angle_feedback_ptr; instance->motor_controller.other_speed_feedback_ptr = config->controller_param_init_config.other_speed_feedback_ptr; + // 后续增加电机前馈控制器(速度和电流) // 电机分组,因为至多4个电机可以共用一帧CAN控制报文 MotorSenderGrouping(instance, &config->can_init_config); @@ -273,8 +275,8 @@ void DJIMotorControl() // 分组填入发送数据 group = motor->sender_group; num = motor->message_num; - sender_assignment[group].tx_buff[2 * num] = (uint8_t)(set >> 8); - sender_assignment[group].tx_buff[2 * num + 1] = (uint8_t)(set & 0x00ff); + sender_assignment[group].tx_buff[2 * num] = (uint8_t)(set >> 8); // 低八位 + sender_assignment[group].tx_buff[2 * num + 1] = (uint8_t)(set & 0x00ff); // 高八位 // 电机是否停止运行 if (motor->stop_flag == MOTOR_STOP) @@ -288,7 +290,7 @@ void DJIMotorControl() { if (sender_enable_flag[i]) { - CANTransmit(&sender_assignment[i],1); + CANTransmit(&sender_assignment[i], 1); } } } diff --git a/modules/referee/referee.c b/modules/referee/referee.c index 9b9075d..f59c2bb 100644 --- a/modules/referee/referee.c +++ b/modules/referee/referee.c @@ -98,10 +98,10 @@ static void JudgeReadData(uint8_t *ReadFromUsart) } } } - // 首地址加帧长度,指向CRC16下一字节,用来判断是否为0xA5,用来判断一个数据包是否有多帧数据 + // 首地址加帧长度,指向CRC16下一字节,用来判断是否为0xA5,从而判断一个数据包是否有多帧数据 if (*(ReadFromUsart + sizeof(xFrameHeader) + LEN_CMDID + referee_info.FrameHeader.DataLength + LEN_TAIL) == 0xA5) { - // 如果一个数据包出现了多帧数据,则再次读取 + // 如果一个数据包出现了多帧数据,则再次调用解析函数,直到所有数据包解析完毕 JudgeReadData(ReadFromUsart + sizeof(xFrameHeader) + LEN_CMDID + referee_info.FrameHeader.DataLength + LEN_TAIL); } } diff --git a/modules/remote/remote_control.c b/modules/remote/remote_control.c index f0df420..9537eae 100644 --- a/modules/remote/remote_control.c +++ b/modules/remote/remote_control.c @@ -3,13 +3,14 @@ #include "bsp_usart.h" #include "memory.h" #include "stdlib.h" +#include "daemon.h" #define REMOTE_CONTROL_FRAME_SIZE 18u // 遥控器接收的buffer大小 // 遥控器数据 static RC_ctrl_t rc_ctrl[2]; //[0]:当前数据TEMP,[1]:上一次的数据LAST.用于按键持续按下和切换的判断 // 遥控器拥有的串口实例,因为遥控器是单例,所以这里只有一个,就不封装了 static USARTInstance *rc_usart_instance; - +static DaemonInstance *rc_daemon_instance; /** * @brief 矫正遥控器摇杆的值,超过660或者小于-660的值都认为是无效值,置0 * @@ -79,13 +80,22 @@ static void sbus_to_rc(const uint8_t *sbus_buf) } /** - * @brief protocol resolve callback - * this func would be called when usart3 idle interrupt happens - * 对sbus_to_rc的简单封装,用于注册到bsp_usart的回调函数中 + * @brief 对sbus_to_rc的简单封装,用于注册到bsp_usart的回调函数中 + * */ static void RemoteControlRxCallback() { - sbus_to_rc(rc_usart_instance->recv_buff); + DaemonReload(rc_daemon_instance); // 先喂狗 + sbus_to_rc(rc_usart_instance->recv_buff); // 进行协议解析 +} + +/** + * @brief + * + */ +static void RCLostCallback() +{ + // @todo 遥控器丢失的处理 } RC_ctrl_t *RemoteControlInit(UART_HandleTypeDef *rc_usart_handle) @@ -95,5 +105,15 @@ RC_ctrl_t *RemoteControlInit(UART_HandleTypeDef *rc_usart_handle) conf.usart_handle = rc_usart_handle; conf.recv_buff_size = REMOTE_CONTROL_FRAME_SIZE; rc_usart_instance = USARTRegister(&conf); + + // 进行守护进程的注册,用于定时检查遥控器是否正常工作 + // @todo 当前守护进程直接在这里注册,后续考虑将其封装到遥控器的初始化函数中,即可以让用户决定reload_count的值(是否有必要?) + Daemon_Init_Config_s daemon_conf = { + .reload_count = 100, // 100ms,遥控器的接收频率实际上是1000/14Hz(大约70) + .callback = NULL, // 后续考虑重新启动遥控器对应串口的传输 + .owner_id = NULL, // 只有1个遥控器,不需要owner_id + }; + rc_daemon_instance = DaemonRegister(&daemon_conf); + return (RC_ctrl_t *)&rc_ctrl; } \ No newline at end of file