将底层的封装统一为相同的格式

This commit is contained in:
NeoZeng 2022-11-28 17:54:07 +08:00
parent 8332422eac
commit f1301ab7de
17 changed files with 75 additions and 63 deletions

View File

@ -17,7 +17,8 @@
"main.h": "c",
"can.h": "c",
"bsp_can.h": "c",
"dji_motor.h": "c"
"dji_motor.h": "c",
"master_process.h": "c"
},
"C_Cpp.default.configurationProvider": "ms-vscode.makefile-tools",
"C_Cpp.intelliSenseEngineFallback": "enabled",

View File

@ -41,6 +41,7 @@
#include "referee.h"
#include "ins_task.h"
#include "can_comm.h"
#include "master_process.h"
/* USER CODE END Includes */
/* Private typedef -----------------------------------------------------------*/
@ -143,7 +144,8 @@ int main(void)
volatile float tx = 32;
RefereeInit(&huart6);
Vision_Recv_s* recv=VisionInit(&huart1);
Vision_Send_s send={.pitch=1,.roll=2,.yaw=3};
/* USER CODE END 2 */
/* Call init function for freertos objects (in freertos.c) */
@ -160,14 +162,13 @@ int main(void)
while (1)
{
/* USER CODE END WHILE */
// DJIMotorSetRef(djimotor, 10);
// MotorControlTask();
DJIMotorSetRef(djimotor, 10);
MotorControlTask();
HAL_Delay(10);
CANCommSend(in, (uint8_t*)&tx);
tx+=1;
rx=(sdf*)CANCommGet(in);
rx=(sdf*)CANCommGet(in);
VisionSend(&send);
// INS_Task();
/* USER CODE BEGIN 3 */
}

View File

@ -55,28 +55,30 @@ static void CANServiceInit()
HAL_CAN_ActivateNotification(&hcan2, CAN_IT_RX_FIFO1_MSG_PENDING);
}
/* -----------------------two extern callable function -----------------------*/
/* ----------------------- two extern callable function -----------------------*/
void CANRegister(can_instance *ins, can_instance_config_s* config)
can_instance* CANRegister(can_instance_config_s* config)
{
static uint8_t idx;
if (!idx)
{
CANServiceInit();
}
instance[idx] = ins;
instance[idx] = (can_instance*)malloc(sizeof(can_instance));
memset(instance[idx],0,sizeof(can_instance));
instance[idx]->txconf.StdId = config->tx_id;
instance[idx]->txconf.IDE = CAN_ID_STD;
instance[idx]->txconf.RTR = CAN_RTR_DATA;
instance[idx]->txconf.DLC = 0x08;
instance[idx]->txconf.DLC = 0x08; // 默认发送长度为8
instance[idx]->can_handle = config->can_handle;
instance[idx]->tx_id = config->tx_id;
instance[idx]->rx_id = config->rx_id;
instance[idx]->can_module_callback = config->can_module_callback;
CANAddFilter(instance[idx++]);
CANAddFilter(instance[idx]);
return instance[idx++];
}
void CANTransmit(can_instance *_instance)

View File

@ -51,7 +51,7 @@ void CANTransmit(can_instance *_instance);
* @param config init config
* @return can_instance* can instance owned by module
*/
void CANRegister(can_instance *instance, can_instance_config_s *config);
can_instance* CANRegister(can_instance_config_s *config);
/**
* @brief CAN发送报文的数据帧长度;8,,8

View File

@ -31,11 +31,19 @@ static void USARTServiceInit(usart_instance *_instance)
__HAL_DMA_DISABLE_IT(_instance->usart_handle->hdmarx, DMA_IT_HT);
}
void USARTRegister(usart_instance *_instance)
usart_instance* USARTRegister(USART_Init_Config_s *init_config)
{
static uint8_t instance_idx;
USARTServiceInit(_instance);
instance[instance_idx++] = _instance;
static uint8_t idx;
instance[idx]=(usart_instance*)malloc(sizeof(usart_instance));
memset(instance[idx],0,sizeof(usart_instance));
instance[idx]->module_callback=init_config->module_callback;
instance[idx]->recv_buff_size=init_config->recv_buff_size;
instance[idx]->usart_handle=init_config->usart_handle;
USARTServiceInit(instance[idx]);
return instance[idx++];
}
/* @todo 当前仅进行了形式上的封装,后续要进一步考虑是否将module的行为与bsp完全分离 */

View File

@ -20,12 +20,20 @@ typedef struct
usart_module_callback module_callback; // 解析收到的数据的回调函数
} usart_instance;
/* usart 初始化配置结构体 */
typedef struct
{
uint8_t recv_buff_size; // 模块接收一包数据的大小
UART_HandleTypeDef *usart_handle; // 实例对应的usart_handle
usart_module_callback module_callback; // 解析收到的数据的回调函数
} USART_Init_Config_s;
/**
* @brief .
*
* @param _instance module拥有的串口实例,,usart_instance的struct定义
* @param init_config
*/
void USARTRegister(usart_instance *_instance);
usart_instance* USARTRegister(USART_Init_Config_s *init_config);
/**
* @todo buff和size,?

View File

@ -28,7 +28,7 @@ static void CANCommRxCallback(can_instance *_instance)
{
for (size_t i = 0; i < idx; i++)
{
if (&can_comm_instance[i]->can_ins == _instance) // 遍历,找到对应的接收CAN COMM实例
if (can_comm_instance[i]->can_ins == _instance) // 遍历,找到对应的接收CAN COMM实例
{
/* 接收状态判断 */
if (_instance->rx_buff[0] == CAN_COMM_HEADER && can_comm_instance[i]->recv_state == 0) // 尚未开始接收且新的一包里有帧头
@ -91,7 +91,7 @@ CANCommInstance *CANCommInit(CANComm_Init_Config_s *comm_config)
can_comm_instance[idx]->raw_sendbuf[comm_config->send_data_len + CAN_COMM_OFFSET_BYTES - 1] = CAN_COMM_TAIL;
comm_config->can_config.can_module_callback = CANCommRxCallback;
CANRegister(&can_comm_instance[idx]->can_ins, &comm_config->can_config);
can_comm_instance[idx]->can_ins=CANRegister(&comm_config->can_config);
return can_comm_instance[idx++];
}
@ -106,9 +106,9 @@ void CANCommSend(CANCommInstance *instance, uint8_t *data)
for (size_t i = 0; i < instance->send_buf_len; i += 8)
{ // 如果是最后一包,send len将会小于8,要修改CAN的txconf中的DLC位,调用bsp_can提供的接口即可
send_len = instance->send_buf_len - i >= 8 ? 8 : instance->send_buf_len - i;
CANSetDLC(&instance->can_ins, send_len);
memcpy(instance->can_ins.tx_buff, instance->raw_sendbuf+i, send_len);
CANTransmit(&instance->can_ins);
CANSetDLC(instance->can_ins, send_len);
memcpy(instance->can_ins->tx_buff, instance->raw_sendbuf+i, send_len);
CANTransmit(instance->can_ins);
}
}

View File

@ -24,7 +24,7 @@
/* CAN comm 结构体, 拥有CAN comm的app应该包含一个CAN comm指针 */
typedef struct
{
can_instance can_ins;
can_instance* can_ins;
/* 发送部分 */
uint8_t send_data_len;
uint8_t send_buf_len;

View File

@ -15,7 +15,7 @@ static Vision_Recv_s recv_data;
// @todo:由于后续需要进行IMU-Cam的硬件触发采集控制,因此可能需要将发送设置为定时任务,或由IMU采集完成产生的中断唤醒的任务,
// 使得时间戳对齐. 因此,在send_data中设定其他的标志位数据,让ins_task填充姿态值.
// static Vision_Send_s send_data;
static usart_instance vision_usart_instance;
static usart_instance* vision_usart_instance;
/**
* @brief ,bsp_usart.c中被usart rx callback调用
@ -25,17 +25,18 @@ static usart_instance vision_usart_instance;
static void DecodeVision()
{
static uint16_t flag_register;
get_protocol_info(vision_usart_instance.recv_buff, &flag_register, &recv_data.pitch);
get_protocol_info(vision_usart_instance->recv_buff, &flag_register, &recv_data.pitch);
// TODO: code to resolve flag_register;
}
/* 视觉通信初始化 */
Vision_Recv_s* VisionInit(UART_HandleTypeDef *handle)
{
vision_usart_instance.module_callback = DecodeVision;
vision_usart_instance.recv_buff_size = VISION_RECV_SIZE;
vision_usart_instance.usart_handle = handle;
USARTRegister(&vision_usart_instance);
USART_Init_Config_s conf;
conf.module_callback = DecodeVision;
conf.recv_buff_size = VISION_RECV_SIZE;
conf.usart_handle = handle;
vision_usart_instance=USARTRegister(&conf);
return &recv_data;
}
@ -56,7 +57,7 @@ void VisionSend(Vision_Send_s *send)
// TODO: code to set flag_register
get_protocol_send_data(0x02, flag_register, &send->yaw, 3, send_buff, &tx_len);
USARTSend(&vision_usart_instance, send_buff, tx_len);
USARTSend(vision_usart_instance, send_buff, tx_len);
}

View File

@ -24,7 +24,7 @@ typedef enum
typedef enum
{
NONE = 0,
NO_TARGET_NUM = 0,
HERO1 = 1,
ENGINEER2 = 2,
INFANTRY3 = 3,

View File

@ -40,7 +40,7 @@ joint_instance *HTMotorInit(can_instance_config_s config)
{
static uint8_t idx;
joint_motor_info[idx] = (joint_instance *)malloc(sizeof(joint_instance));
CANRegister(joint_motor_info[idx++]->motor_can_instace, &config);
joint_motor_info[idx]->motor_can_instace =CANRegister(&config);
return joint_motor_info[idx++];
}

View File

@ -23,7 +23,7 @@ driven_instance *LKMotroInit(can_instance_config_s config)
static uint8_t idx;
driven_motor_info[idx] = (driven_instance *)malloc(sizeof(driven_instance));
config.can_module_callback = DecodeDriven;
CANRegister(driven_motor_info[idx]->motor_can_instance, &config);
driven_motor_info[idx]->motor_can_instance=CANRegister(&config);
return driven_motor_info[idx++];
}

View File

@ -78,7 +78,7 @@ static void MotorSenderGrouping(can_instance_config_s *config)
// 检查是否发生id冲突
for (size_t i = 0; i < idx; i++)
{
if (dji_motor_info[i]->motor_can_instance.can_handle == config->can_handle && dji_motor_info[i]->motor_can_instance.rx_id == config->rx_id)
if (dji_motor_info[i]->motor_can_instance->can_handle == config->can_handle && dji_motor_info[i]->motor_can_instance->rx_id == config->rx_id)
IDcrash_Handler(i, idx);
}
break;
@ -102,7 +102,7 @@ static void MotorSenderGrouping(can_instance_config_s *config)
for (size_t i = 0; i < idx; i++)
{
if (dji_motor_info[i]->motor_can_instance.can_handle == config->can_handle && dji_motor_info[i]->motor_can_instance.rx_id == config->rx_id)
if (dji_motor_info[i]->motor_can_instance->can_handle == config->can_handle && dji_motor_info[i]->motor_can_instance->rx_id == config->rx_id)
IDcrash_Handler(i, idx);
}
break;
@ -126,7 +126,7 @@ static void DecodeDJIMotor(can_instance *_instance)
for (size_t i = 0; i < DJI_MOTOR_CNT; i++)
{
if (&dji_motor_info[i]->motor_can_instance == _instance)
if (dji_motor_info[i]->motor_can_instance == _instance)
{
rxbuff = _instance->rx_buff;
measure = &dji_motor_info[i]->motor_measure;
@ -168,7 +168,7 @@ dji_motor_instance *DJIMotorInit(Motor_Init_Config_s *config)
MotorSenderGrouping(&config->can_init_config);
// register motor to CAN bus
config->can_init_config.can_module_callback = DecodeDJIMotor; // set callback
CANRegister(&dji_motor_info[idx]->motor_can_instance, &config->can_init_config);
dji_motor_info[idx]->motor_can_instance=CANRegister(&config->can_init_config);
return dji_motor_info[idx++];
}

View File

@ -53,7 +53,7 @@ typedef struct
Motor_Controller_s motor_controller;
/* the CAN instance own by motor instance*/
can_instance motor_can_instance;
can_instance* motor_can_instance;
/* sender assigment*/
uint8_t sender_group;

View File

@ -8,7 +8,7 @@
#define RE_RX_BUFFER_SIZE 200
// static usart_instance referee_usart_instance;
usart_instance referee_usart_instance;
static usart_instance* referee_usart_instance;
/**************裁判系统数据******************/
referee_info_t referee_info;
@ -17,15 +17,16 @@ uint16_t Judge_SelfClient_ID; // 发送者机器人对应的客户端ID
static void ReceiveCallback()
{
JudgeReadData(referee_usart_instance.recv_buff);
JudgeReadData(referee_usart_instance->recv_buff);
}
void RefereeInit(UART_HandleTypeDef *referee_usart_handle)
{
referee_usart_instance.module_callback = ReceiveCallback;
referee_usart_instance.usart_handle = referee_usart_handle;
referee_usart_instance.recv_buff_size = RE_RX_BUFFER_SIZE;
USARTRegister(&referee_usart_instance);
USART_Init_Config_s conf;
conf.module_callback = ReceiveCallback;
conf.usart_handle = referee_usart_handle;
conf.recv_buff_size = RE_RX_BUFFER_SIZE;
referee_usart_instance=USARTRegister(&conf);
}
/**

View File

@ -7,7 +7,7 @@
// 遥控器数据
static RC_ctrl_t rc_ctrl;
// 遥控器拥有的串口实例
static usart_instance rc_usart_instance;
static usart_instance* rc_usart_instance;
/**
* @brief remote control protocol resolution
@ -52,19 +52,15 @@ static void sbus_to_rc(volatile const uint8_t *sbus_buf, RC_ctrl_t *rc_ctrl)
*/
static void ReceiveCallback()
{
sbus_to_rc(rc_usart_instance.recv_buff, &rc_ctrl);
sbus_to_rc(rc_usart_instance->recv_buff, &rc_ctrl);
}
RC_ctrl_t *RC_init(UART_HandleTypeDef *rc_usart_handle)
{
rc_usart_instance.module_callback = ReceiveCallback;
rc_usart_instance.usart_handle = rc_usart_handle;
rc_usart_instance.recv_buff_size = REMOTE_CONTROL_FRAME_SIZE;
USARTRegister(&rc_usart_instance);
return &rc_ctrl;
}
const RC_ctrl_t *get_remote_control_point(void)
{
USART_Init_Config_s conf;
conf.module_callback = ReceiveCallback;
conf.usart_handle = rc_usart_handle;
conf.recv_buff_size = REMOTE_CONTROL_FRAME_SIZE;
rc_usart_instance = USARTRegister(&conf);
return &rc_ctrl;
}

View File

@ -75,10 +75,4 @@ typedef struct
*/
RC_ctrl_t *RC_init(UART_HandleTypeDef *rc_usart_handle);
/**
* @brief Get the remote control point object
*
* @return const RC_ctrl_t*
*/
const RC_ctrl_t *get_remote_control_point(void);
#endif