// app #include "robot_def.h" #include "robot_cmd.h" // module #include "remote_control.h" #include "ins_task.h" #include "master_process.h" #include "message_center.h" #include "general_def.h" #include "dji_motor.h" #include "auto_aim.h" #include "super_cap.h" #include "user_lib.h" #include "openmv.h" // bsp #include "bsp_dwt.h" #include "bsp_log.h" #include "referee_task.h" #include "vision_transfer.h" // 私有宏,自动将编码器转换成角度值 #define YAW_ALIGN_ANGLE (YAW_CHASSIS_ALIGN_ECD * ECD_ANGLE_COEF_DJI) // 对齐时的角度,0-360 #define PTICH_HORIZON_ANGLE (PITCH_HORIZON_ECD * ECD_ANGLE_COEF_DJI) // pitch水平时电机的角度,0-360 /* cmd应用包含的模块实例指针和交互信息存储*/ #ifdef GIMBAL_BOARD // 对双板的兼容,条件编译 #include "can_comm.h" #include "user_lib.h" static CANCommInstance *cmd_can_comm; // 双板通信 #endif #ifdef ONE_BOARD static Publisher_t *chassis_cmd_pub; // 底盘控制消息发布者 static Subscriber_t *chassis_feed_sub; // 底盘反馈信息订阅者 #endif // ONE_BOARD static Chassis_Ctrl_Cmd_s chassis_cmd_send; // 发送给底盘应用的信息,包括控制信息和UI绘制相关 static Chassis_Upload_Data_s chassis_fetch_data; // 从底盘应用接收的反馈信息信息,底盘功率枪口热量与底盘运动状态等 extern SuperCapInstance *cap; // 超级电容 static RC_ctrl_t *rc_data; // 遥控器数据,初始化时返回 static VT_ctrl_t *vt_data; // 图传链路下发的键鼠遥控数据 与遥控器数据格式保持一致 static Openmv_Information *om_data; //存放openmv数据 //static Vision_Recv_s *vision_recv_data; // 视觉接收数据指针,初始化时返回 //static Vision_Send_s vision_send_data; // 视觉发送数据 static RecievePacket_t *vision_recv_data; // 视觉接收数据指针,初始化时返回 static SendPacket_t vision_send_data; // 视觉发送数据 //自瞄相关信息 static Trajectory_Type_t trajectory_cal; static Aim_Select_Type_t aim_select; static uint32_t no_find_cnt; // 未发现目标计数 static uint8_t auto_aim_flag = 0; //辅助瞄准标志位 视野内有目标开启 目标丢失关闭 static uint8_t choose_amor_id = 0; static float yaw_err_for_test; static Publisher_t *gimbal_cmd_pub; // 云台控制消息发布者 static Subscriber_t *gimbal_feed_sub; // 云台反馈信息订阅者 static Gimbal_Ctrl_Cmd_s gimbal_cmd_send; // 传递给云台的控制信息 static Gimbal_Upload_Data_s gimbal_fetch_data; // 从云台获取的反馈信息 static Publisher_t *shoot_cmd_pub; // 发射控制消息发布者 static Subscriber_t *shoot_feed_sub; // 发射反馈信息订阅者 static Shoot_Ctrl_Cmd_s shoot_cmd_send; // 传递给发射的控制信息 static Shoot_Upload_Data_s shoot_fetch_data; // 从发射获取的反馈信息 static Robot_Status_e robot_state; // 机器人整体工作状态 static referee_info_t *referee_data; // 用于获取裁判系统的数据 static uint8_t loader_flag = 0; //拨弹模式选择标志位 static float test1; void RobotCMDInit() { rc_data = RemoteControlInit(&huart3); // 修改为对应串口,注意如果是自研板dbus协议串口需选用添加了反相器的那个 vision_recv_data = VisionInit(); // 视觉通信串口 vt_data = VTRefereeInit(&huart1); // 图传通信串口 todo 如果试验成功则openmv与主控通信使用huart1 referee_data = UITaskInit(&huart6, &ui_data); // 裁判系统初始化,会同时初始化UI todo为了先测试openmv与其通信先注释 // om_data = OpenmvInit(&huart6); gimbal_cmd_pub = PubRegister("gimbal_cmd", sizeof(Gimbal_Ctrl_Cmd_s)); gimbal_feed_sub = SubRegister("gimbal_feed", sizeof(Gimbal_Upload_Data_s)); shoot_cmd_pub = PubRegister("shoot_cmd", sizeof(Shoot_Ctrl_Cmd_s)); shoot_feed_sub = SubRegister("shoot_feed", sizeof(Shoot_Upload_Data_s)); #ifdef ONE_BOARD // 双板兼容 chassis_cmd_pub = PubRegister("chassis_cmd", sizeof(Chassis_Ctrl_Cmd_s)); chassis_feed_sub = SubRegister("chassis_feed", sizeof(Chassis_Upload_Data_s)); #endif // ONE_BOARD #ifdef GIMBAL_BOARD CANComm_Init_Config_s comm_conf = { .can_config = { .can_handle = &hcan1, .tx_id = 0x312, .rx_id = 0x311, }, .recv_data_len = sizeof(Chassis_Upload_Data_s), .send_data_len = sizeof(Chassis_Ctrl_Cmd_s), }; cmd_can_comm = CANCommInit(&comm_conf); #endif // GIMBAL_BOARD gimbal_cmd_send.pitch = 0; robot_state = ROBOT_READY; // 启动时机器人进入工作模式,后续加入所有应用初始化完成之后再进入 } /** * @brief 根据gimbal app传回的当前电机角度计算和零位的误差 * 单圈绝对角度的范围是0~360,说明文档中有图示 * */ static void CalcOffsetAngle() { // 别名angle提高可读性,不然太长了不好看,虽然基本不会动这个函数 static float angle; angle = gimbal_fetch_data.yaw_motor_single_round_angle; // 从云台获取的当前yaw电机单圈角度 #if YAW_ECD_GREATER_THAN_4096 // 如果大于180度 if (angle > YAW_ALIGN_ANGLE && angle <= 180.0f + YAW_ALIGN_ANGLE) chassis_cmd_send.offset_angle = angle - YAW_ALIGN_ANGLE; else if (angle > 180.0f + YAW_ALIGN_ANGLE) chassis_cmd_send.offset_angle = angle - YAW_ALIGN_ANGLE - 360.0f; else chassis_cmd_send.offset_angle = angle - YAW_ALIGN_ANGLE; #else // 小于180度 if (angle > YAW_ALIGN_ANGLE) chassis_cmd_send.offset_angle = angle - YAW_ALIGN_ANGLE; else if (angle <= YAW_ALIGN_ANGLE && angle >= YAW_ALIGN_ANGLE - 180.0f) chassis_cmd_send.offset_angle = angle - YAW_ALIGN_ANGLE; else chassis_cmd_send.offset_angle = angle - YAW_ALIGN_ANGLE + 360.0f; #endif } //功能:死亡后清除小陀螺的状态 static void death_check() { if (referee_data->GameRobotState.current_HP <= 0 || referee_data->GameRobotState.power_management_chassis_output == 0) { rc_data[TEMP].key_count[KEY_PRESS][Key_E] = 0; gimbal_cmd_send.yaw = gimbal_fetch_data.gimbal_imu_data.YawTotalAngle; } } static void auto_aim_mode() { trajectory_cal.v0 = 26; //弹速30 if (vision_recv_data->x == 0 && vision_recv_data->y == 0 && vision_recv_data->z == 0 && vision_recv_data->vx == 0 && vision_recv_data->vy == 0 && vision_recv_data->vz == 0) { aim_select.suggest_fire = 0; //未发现目标 no_find_cnt++; if (no_find_cnt >= 2000) { //gimbal_scan_flag = 1; //auto_aim_flag = 0; } //else //auto_aim_flag = 1; } else { //弹道解算 no_find_cnt = 0; auto_aim_flag = 1; choose_amor_id = auto_aim(&aim_select, &trajectory_cal, vision_recv_data); VisionSetAim(aim_select.aim_point[0], aim_select.aim_point[1], aim_select.aim_point[2]); float single_angle_yaw_now = gimbal_fetch_data.gimbal_imu_data.Yaw; float diff_yaw = trajectory_cal.cmd_yaw * 180 / PI - single_angle_yaw_now; float yaw_err = diff_yaw; yaw_err_for_test = yaw_err; if (diff_yaw > 180) diff_yaw -= 360; else if (diff_yaw < -180) diff_yaw += 360; gimbal_cmd_send.yaw = gimbal_fetch_data.gimbal_imu_data.YawTotalAngle + diff_yaw; gimbal_cmd_send.pitch = -trajectory_cal.cmd_pitch * 180 / PI; if (yaw_err <= 2) //3度 { aim_select.suggest_fire = 1; } else aim_select.suggest_fire = 0; } } /** * @brief 控制输入为遥控器(调试时)的模式和控制量设置 * */ static void RemoteControlSet() { if (switch_is_up(rc_data[TEMP].rc.switch_right))//右侧开关为上,换弹模式 { shoot_cmd_send.shoot_mode = SHOOT_ON; if(switch_is_up(rc_data[TEMP].rc.switch_left)) { shoot_cmd_send.TimingBeltMotorAngle += 0.1f*(float) rc_data[TEMP].rc.rocker_l1; //两个传送带遥控器数据,原为0.01 shoot_cmd_send.SpeedControlMotorAngle += 0.1f*(float) rc_data[TEMP].rc.rocker_r1; shoot_cmd_send.load_structure_mode=LOAD_STRUCTURE_OFF; shoot_cmd_send.load_servo_mode=LOAD_TRIGGER_OFF; } else if(switch_is_mid(rc_data[TEMP].rc.switch_left)) //平行四边形换弹结构开始工作 { shoot_cmd_send.load_structure_mode=LOAD_STRUCTURE_ON; shoot_cmd_send.load_servo_mode=LOAD_TRIGGER_OFF; } else if(switch_is_down(rc_data[TEMP].rc.switch_left)) //启动拨杆 { shoot_cmd_send.TimingBeltMotorAngle += 0.1*(float) rc_data[TEMP].rc.rocker_l1; shoot_cmd_send.load_servo_mode = LOAD_TRIGGER_ON; // osDelay(500); shoot_cmd_send.load_structure_mode=LOAD_STRUCTURE_OFF; } //待添加限位 //... // shoot_cmd_send.Yawmotor_angle -= 0.00025f * (float) rc_data[TEMP].rc.rocker_l_; //yaw电机测试 // float delta_yaw_total = shoot_cmd_send.Yawmotor_angle-shoot_fetch_data.yaw_motor_feedback.measure.total_angle; // float delta_yaw = theta_format(delta_yaw_total); // // shoot_cmd_send.Yawmotor_angle = shoot_fetch_data.yaw_motor_feedback.measure.total_angle + delta_yaw;//源代码是total_angle } if (switch_is_mid(rc_data[TEMP].rc.switch_right))//右侧拨杆为中,进入发射准备模式 { shoot_cmd_send.TimingBeltMotorAngle += 0.01f*(float) rc_data[TEMP].rc.rocker_l1; //两个传送带遥控器数据,原为0.01 shoot_cmd_send.SpeedControlMotorAngle += 0.1f*(float) rc_data[TEMP].rc.rocker_r1; } // 扳机控制,拨轮向上打为负,向下为正 // if (switch_is_mid(rc_data[TEMP].rc.switch_right)) //右侧拨杆为中触发 // shoot_cmd_send.trigger_mode = TRIGGER_ON; // else if (switch_is_down(rc_data[TEMP].rc.switch_right)) // shoot_cmd_send.trigger_mode = TRIGGER_OFF; } /** * @brief 紧急停止,包括遥控器左上侧拨轮打满/重要模块离线/双板通信失效等 * 停止的阈值'300'待修改成合适的值,或改为开关控制. * * @todo 后续修改为遥控器离线则电机停止(关闭遥控器急停),通过给遥控器模块添加daemon实现 * */ static void EmergencyHandler() { // 拨轮的向下拨超过一半进入急停模式.注意向打时下拨轮是正 if (rc_data[TEMP].rc.dial > 300 || robot_state == ROBOT_STOP) // 还需添加重要应用和模块离线的判断 { robot_state = ROBOT_STOP; gimbal_cmd_send.gimbal_mode = GIMBAL_ZERO_FORCE; chassis_cmd_send.chassis_mode = CHASSIS_ZERO_FORCE; shoot_cmd_send.shoot_mode = SHOOT_OFF; LOGERROR("[CMD] emergency stop!"); } // 拨轮向上拨动,启动机器人 if (rc_data[TEMP].rc.dial < -500) { //switch_is_up(rc_data[TEMP].rc.switch_right) robot_state = ROBOT_READY; shoot_cmd_send.shoot_mode = SHOOT_ON; gimbal_cmd_send.yaw = gimbal_fetch_data.gimbal_imu_data.YawTotalAngle; LOGINFO("[CMD] reinstate, robot ready"); } } /* 机器人核心控制任务,200Hz频率运行(必须高于视觉发送频率) */ void RobotCMDTask() { // 从其他应用获取回传数据 #ifdef ONE_BOARD SubGetMessage(chassis_feed_sub, (void *) &chassis_fetch_data); #endif // ONE_BOARD #ifdef GIMBAL_BOARD chassis_fetch_data = *(Chassis_Upload_Data_s *)CANCommGet(cmd_can_comm); #endif // GIMBAL_BOARD SubGetMessage(shoot_feed_sub, &shoot_fetch_data); SubGetMessage(gimbal_feed_sub, &gimbal_fetch_data); // update_ui_data(); // 根据gimbal的反馈值计算云台和底盘正方向的夹角,不需要传参,通过static私有变量完成 CalcOffsetAngle(); EmergencyHandler(); // 处理模块离线和遥控器急停等紧急情况 if (robot_state != ROBOT_STOP) { // 根据遥控器左侧开关,确定当前使用的控制模式为遥控器调试还是键鼠 if (switch_is_down(rc_data[TEMP].rc.switch_left) || switch_is_mid(rc_data[TEMP].rc.switch_left)||switch_is_up(rc_data[TEMP].rc.switch_left))// 遥控器左侧开关状态为[下],[中],遥控器控制 RemoteControlSet(); /* else if (switch_is_up(rc_data[TEMP].rc.switch_left) && switch_is_mid(rc_data[TEMP].rc.switch_right)) // 遥控器左侧开关状态为[上],键盘控制,遥控器右侧开关状态为[中],遥控器通道 MouseKeySet(); else if (switch_is_up(rc_data[TEMP].rc.switch_left) && switch_is_up(rc_data[TEMP].rc.switch_right)) // 遥控器左侧开关状态为[上],键盘控制,遥控器右侧开关状态为[上],图传链路通道 VTMouseKeySet(); */ } /* // 设置视觉发送数据,还需增加加速度和角速度数据 VisionSetFlag(!referee_data->referee_id.Robot_Color); //根据裁判系统反馈确定底盘功率上限 chassis_cmd_send.chassis_power_limit = referee_data->GameRobotState.chassis_power_limit; //根据裁判系统反馈确定缓冲功率 chassis_cmd_send.buffer_energy = referee_data->PowerHeatData.buffer_energy; //根据裁判系统反馈确定枪管热量控制 shoot_cmd_send.heat = referee_data->PowerHeatData.shooter_17mm_1_barrel_heat; shoot_cmd_send.heat_limit = referee_data->GameRobotState.shooter_barrel_heat_limit; shoot_cmd_send.heat_cool = referee_data->GameRobotState.shooter_barrel_cooling_value; if (referee_data->GameRobotState.power_management_chassis_output == 0) { chassis_cmd_send.chassis_mode = CHASSIS_ZERO_FORCE; } if (referee_data->GameRobotState.power_management_gimbal_output == 0) { gimbal_cmd_send.gimbal_mode = GIMBAL_ZERO_FORCE; } if (referee_data->GameRobotState.power_management_shooter_output == 0) { shoot_cmd_send.shoot_mode = SHOOT_OFF; } */ // death_check(); // 推送消息,双板通信,视觉通信等 // 其他应用所需的控制数据在remotecontrolsetmode和mousekeysetmode中完成设置 #ifdef ONE_BOARD PubPushMessage(chassis_cmd_pub, (void *) &chassis_cmd_send); #endif // ONE_BOARD #ifdef GIMBAL_BOARD CANCommSend(cmd_can_comm, (void *)&chassis_cmd_send); #endif // GIMBAL_BOARD PubPushMessage(shoot_cmd_pub, (void *) &shoot_cmd_send); PubPushMessage(gimbal_cmd_pub, (void *) &gimbal_cmd_send); }