Merge from captain chen

This commit is contained in:
NeoZng 2023-03-23 18:57:54 +08:00
parent 41d033e3f8
commit 59e21dc25d
19 changed files with 161 additions and 127 deletions

4
.vscode/launch.json vendored
View File

@ -6,7 +6,7 @@
{ {
"name": "Debug-DAP", "name": "Debug-DAP",
"cwd": "${workspaceRoot}", "cwd": "${workspaceRoot}",
"executable": "${workspaceRoot}\\build\\${workspaceFolderBasename}.elf", // ,vscode "executable": "${workspaceRoot}\\build\\basic_framework.elf", // ,vscode
"request": "launch", "request": "launch",
"type": "cortex-debug", "type": "cortex-debug",
//使J-link GDB Server;GBD ServerSVD //使J-link GDB Server;GBD ServerSVD
@ -28,7 +28,7 @@
{ {
"name": "Debug-Jlink", "name": "Debug-Jlink",
"cwd": "${workspaceFolder}", "cwd": "${workspaceFolder}",
"executable": "${workspaceRoot}\\build\\${workspaceFolderBasename}.elf", "executable": "${workspaceRoot}\\build\\basic_framework.elf",
"request": "launch", "request": "launch",
"type": "cortex-debug", "type": "cortex-debug",
"device": "STM32F407IG", "device": "STM32F407IG",

4
.vscode/tasks.json vendored
View File

@ -15,7 +15,7 @@
{ {
"label": "download dap", "label": "download dap",
"type": "shell", // ,command "type": "shell", // ,command
"command":"mingw32-make download_dap", // "mingw32-make -j24 && mingw32-make download_dap", "command":"mingw32-make download_dap", // "mingw32-make -j24 ; mingw32-make download_dap",
"group": { // ,,使. "group": { // ,,使.
"kind": "build", "kind": "build",
"isDefault": false, "isDefault": false,
@ -24,7 +24,7 @@
{ {
"label": "download jlink", "label": "download jlink",
"type": "shell", "type": "shell",
"command":"mingw32-make download_jlink", // "mingw32-make -j24 && mingw32-make download_dap" "command":"mingw32-make download_jlink", // "mingw32-make -j24 ; mingw32-make download_dap"
"group": { "group": {
"kind": "build", "kind": "build",
"isDefault": false, "isDefault": false,

View File

@ -31,7 +31,6 @@
#include "daemon.h" #include "daemon.h"
#include "robot.h" #include "robot.h"
/* USER CODE END Includes */ /* USER CODE END Includes */
/* Private typedef -----------------------------------------------------------*/ /* Private typedef -----------------------------------------------------------*/
@ -133,7 +132,7 @@ void MX_FREERTOS_Init(void) {
/* USER CODE BEGIN RTOS_THREADS */ /* USER CODE BEGIN RTOS_THREADS */
/* add threads, ... */ /* add threads, ... */
/* USER CODE END RTOS_THREADS */ /* USER CODE END RTOS_THREADS */
} }
/* USER CODE BEGIN Header_StartDefaultTask */ /* USER CODE BEGIN Header_StartDefaultTask */

View File

@ -600,7 +600,7 @@ Project.SetOSPlugin(“plugin_name”)
2. 变量watch窗口这里的变量不会实时更新只有在暂停或遇到断点的时候才会更新。若希望实时查看在这里右键选择需要动态查看的变量选择Graph他就会出现在**窗口8**的位置。 2. 变量watch窗口这里的变量不会实时更新只有在暂停或遇到断点的时候才会更新。若希望实时查看在这里右键选择需要动态查看的变量选择Graph他就会出现在**窗口8**的位置。
如果不需要可视化查看变量变化的趋势,但是想不赞同查看变量的值请右键点击变量选择一个合适的refresh rate 如果不需要可视化查看变量变化的趋势,但是想不暂停查看变量的值请右键点击变量选择一个合适的refresh rate
![image-20221119173731119](assets/image-20221119173731119.png) ![image-20221119173731119](assets/image-20221119173731119.png)

View File

@ -68,16 +68,20 @@ void ChassisInit()
.can_init_config.can_handle = &hcan1, .can_init_config.can_handle = &hcan1,
.controller_param_init_config = { .controller_param_init_config = {
.speed_PID = { .speed_PID = {
.Kp = 10, .Kp = 4.5,//9
.Ki = 0, .Ki = 0,//0.02
.Kd = 0, .Kd = 0.01,//0.01
.MaxOut = 4000, .IntegralLimit = 3000,
.Improve = PID_Trapezoid_Intergral | PID_Integral_Limit |PID_Derivative_On_Measurement,
.MaxOut = 12000,
}, },
.current_PID = { .current_PID = {
.Kp = 1, .Kp = 0.4,//0.7
.Ki = 0, .Ki = 0,//0.1
.Kd = 0, .Kd = 0,
.MaxOut = 4000, .IntegralLimit = 3000,
.Improve = PID_Trapezoid_Intergral | PID_Integral_Limit |PID_Derivative_On_Measurement,
.MaxOut = 15000,
}, },
}, },
.controller_setting_init_config = { .controller_setting_init_config = {
@ -89,20 +93,20 @@ void ChassisInit()
.motor_type = M3508, .motor_type = M3508,
}; };
// @todo: 当前还没有设置电机的正反转,仍然需要手动添加reference的正负号,需要电机module的支持,待修改. // @todo: 当前还没有设置电机的正反转,仍然需要手动添加reference的正负号,需要电机module的支持,待修改.
chassis_motor_config.can_init_config.tx_id = 4; chassis_motor_config.can_init_config.tx_id = 1;
chassis_motor_config.controller_setting_init_config.reverse_flag = MOTOR_DIRECTION_NORMAL; chassis_motor_config.controller_setting_init_config.motor_reverse_flag = MOTOR_DIRECTION_REVERSE;
motor_lf = DJIMotorInit(&chassis_motor_config); motor_lf = DJIMotorInit(&chassis_motor_config);
chassis_motor_config.can_init_config.tx_id = 3, chassis_motor_config.can_init_config.tx_id = 2;
chassis_motor_config.controller_setting_init_config.reverse_flag = MOTOR_DIRECTION_NORMAL; chassis_motor_config.controller_setting_init_config.motor_reverse_flag = MOTOR_DIRECTION_REVERSE;
motor_rf = DJIMotorInit(&chassis_motor_config); motor_rf = DJIMotorInit(&chassis_motor_config);
chassis_motor_config.can_init_config.tx_id = 1, chassis_motor_config.can_init_config.tx_id = 4;
chassis_motor_config.controller_setting_init_config.reverse_flag = MOTOR_DIRECTION_NORMAL; chassis_motor_config.controller_setting_init_config.motor_reverse_flag = MOTOR_DIRECTION_REVERSE;
motor_lb = DJIMotorInit(&chassis_motor_config); motor_lb = DJIMotorInit(&chassis_motor_config);
chassis_motor_config.can_init_config.tx_id = 2, chassis_motor_config.can_init_config.tx_id = 3;
chassis_motor_config.controller_setting_init_config.reverse_flag = MOTOR_DIRECTION_NORMAL; chassis_motor_config.controller_setting_init_config.motor_reverse_flag = MOTOR_DIRECTION_REVERSE;
motor_rb = DJIMotorInit(&chassis_motor_config); motor_rb = DJIMotorInit(&chassis_motor_config);
// referee_data = RefereeInit(&huart6); // 裁判系统初始化 // referee_data = RefereeInit(&huart6); // 裁判系统初始化
@ -153,7 +157,7 @@ static void MecanumCalculate()
{ {
vt_lf = -chassis_vx - chassis_vy - chassis_cmd_recv.wz * LF_CENTER; vt_lf = -chassis_vx - chassis_vy - chassis_cmd_recv.wz * LF_CENTER;
vt_rf = -chassis_vx + chassis_vy - chassis_cmd_recv.wz * RF_CENTER; vt_rf = -chassis_vx + chassis_vy - chassis_cmd_recv.wz * RF_CENTER;
vt_lb = chassis_vx - chassis_vy - chassis_cmd_recv.wz * LB_CENTER; vt_lb = chassis_vx - chassis_vy -chassis_cmd_recv.wz * LB_CENTER;
vt_rb = chassis_vx + chassis_vy - chassis_cmd_recv.wz * RB_CENTER; vt_rb = chassis_vx + chassis_vy - chassis_cmd_recv.wz * RB_CENTER;
} }
@ -220,10 +224,10 @@ void ChassisTask()
chassis_cmd_recv.wz = 0; chassis_cmd_recv.wz = 0;
break; break;
case CHASSIS_FOLLOW_GIMBAL_YAW: // 跟随云台,不单独设置pid,以误差角度平方为速度输出 case CHASSIS_FOLLOW_GIMBAL_YAW: // 跟随云台,不单独设置pid,以误差角度平方为速度输出
chassis_cmd_recv.wz = 0.05f * powf(chassis_cmd_recv.wz, 2.0f); chassis_cmd_recv.wz = -1.5*chassis_cmd_recv.offset_angle*abs(chassis_cmd_recv.offset_angle);
break; break;
case CHASSIS_ROTATE: // 自旋,同时保持全向机动;当前wz维持定值,后续增加不规则的变速策略 case CHASSIS_ROTATE: // 自旋,同时保持全向机动;当前wz维持定值,后续增加不规则的变速策略
// chassis_cmd_recv.wz=sin(t) chassis_cmd_recv.wz=4000;
break; break;
default: default:
break; break;

View File

@ -21,7 +21,7 @@ static CANCommInstance *cmd_can_comm; // 双板通信
#ifdef ONE_BOARD #ifdef ONE_BOARD
static Publisher_t *chassis_cmd_pub; // 底盘控制消息发布者 static Publisher_t *chassis_cmd_pub; // 底盘控制消息发布者
static Subscriber_t *chassis_feed_sub; // 底盘反馈信息订阅者 static Subscriber_t *chassis_feed_sub; // 底盘反馈信息订阅者
#endif // ONE_BOARD #endif // ONE_BOARD
static Chassis_Ctrl_Cmd_s chassis_cmd_send; // 发送给底盘应用的信息,包括控制信息和UI绘制相关 static Chassis_Ctrl_Cmd_s chassis_cmd_send; // 发送给底盘应用的信息,包括控制信息和UI绘制相关
static Chassis_Upload_Data_s chassis_fetch_data; // 从底盘应用接收的反馈信息信息,底盘功率枪口热量与底盘运动状态等 static Chassis_Upload_Data_s chassis_fetch_data; // 从底盘应用接收的反馈信息信息,底盘功率枪口热量与底盘运动状态等
@ -68,6 +68,7 @@ void RobotCMDInit()
}; };
cmd_can_comm = CANCommInit(&comm_conf); cmd_can_comm = CANCommInit(&comm_conf);
#endif // GIMBAL_BOARD #endif // GIMBAL_BOARD
gimbal_cmd_send.pitch = 0;
robot_state = ROBOT_READY; // 启动时机器人进入工作模式,后续加入所有应用初始化完成之后再进入 robot_state = ROBOT_READY; // 启动时机器人进入工作模式,后续加入所有应用初始化完成之后再进入
} }
@ -80,9 +81,9 @@ void RobotCMDInit()
static void CalcOffsetAngle() static void CalcOffsetAngle()
{ {
// 别名angle提高可读性,不然太长了不好看,虽然基本不会动这个函数 // 别名angle提高可读性,不然太长了不好看,虽然基本不会动这个函数
static float angle; static float angle;
angle = gimbal_fetch_data.yaw_motor_single_round_angle; // 从云台获取的当前yaw电机单圈角度 angle = gimbal_fetch_data.yaw_motor_single_round_angle; // 从云台获取的当前yaw电机单圈角度
#if YAW_ECD_GREATER_THAN_4096 // 如果大于180度 #if YAW_ECD_GREATER_THAN_4096 // 如果大于180度
if (angle > YAW_ALIGN_ANGLE && angle <= 180.0f + YAW_ALIGN_ANGLE) if (angle > YAW_ALIGN_ANGLE && angle <= 180.0f + YAW_ALIGN_ANGLE)
chassis_cmd_send.offset_angle = angle - YAW_ALIGN_ANGLE; chassis_cmd_send.offset_angle = angle - YAW_ALIGN_ANGLE;
else if (angle > 180.0f + YAW_ALIGN_ANGLE) else if (angle > 180.0f + YAW_ALIGN_ANGLE)
@ -107,9 +108,15 @@ static void RemoteControlSet()
{ {
// 控制底盘和云台运行模式,云台待添加,云台是否始终使用IMU数据? // 控制底盘和云台运行模式,云台待添加,云台是否始终使用IMU数据?
if (switch_is_down(rc_data[TEMP].rc.switch_right)) // 右侧开关状态[下],底盘跟随云台 if (switch_is_down(rc_data[TEMP].rc.switch_right)) // 右侧开关状态[下],底盘跟随云台
chassis_cmd_send.chassis_mode = CHASSIS_FOLLOW_GIMBAL_YAW; {
chassis_cmd_send.chassis_mode = CHASSIS_ROTATE;
gimbal_cmd_send.gimbal_mode = GIMBAL_GYRO_MODE;
}
else if (switch_is_mid(rc_data[TEMP].rc.switch_right)) // 右侧开关状态[中],底盘和云台分离,底盘保持不转动 else if (switch_is_mid(rc_data[TEMP].rc.switch_right)) // 右侧开关状态[中],底盘和云台分离,底盘保持不转动
{
chassis_cmd_send.chassis_mode = CHASSIS_NO_FOLLOW; chassis_cmd_send.chassis_mode = CHASSIS_NO_FOLLOW;
gimbal_cmd_send.gimbal_mode = GIMBAL_FREE_MODE;
}
// 云台参数,确定云台控制数据 // 云台参数,确定云台控制数据
if (switch_is_mid(rc_data[TEMP].rc.switch_left)) // 左侧开关状态为[中],视觉模式 if (switch_is_mid(rc_data[TEMP].rc.switch_left)) // 左侧开关状态为[中],视觉模式
@ -120,9 +127,8 @@ static void RemoteControlSet()
// 左侧开关状态为[下],或视觉未识别到目标,纯遥控器拨杆控制 // 左侧开关状态为[下],或视觉未识别到目标,纯遥控器拨杆控制
if (switch_is_down(rc_data[TEMP].rc.switch_left) || vision_recv_data->target_state == NO_TARGET) if (switch_is_down(rc_data[TEMP].rc.switch_left) || vision_recv_data->target_state == NO_TARGET)
{ // 按照摇杆的输出大小进行角度增量,增益系数需调整 { // 按照摇杆的输出大小进行角度增量,增益系数需调整
gimbal_cmd_send.yaw += 0.0015f * (float)rc_data[TEMP].rc.rocker_l_; gimbal_cmd_send.yaw += 0.005f * (float)rc_data[TEMP].rc.rocker_l_;
gimbal_cmd_send.pitch += 0.002f * (float)rc_data[TEMP].rc.rocker_l1; gimbal_cmd_send.pitch += 0.001f * (float)rc_data[TEMP].rc.rocker_l1;
gimbal_cmd_send.gimbal_mode = GIMBAL_FREE_MODE;
} }
// 底盘参数,目前没有加入小陀螺(调试似乎暂时没有必要),系数需要调整 // 底盘参数,目前没有加入小陀螺(调试似乎暂时没有必要),系数需要调整
@ -131,7 +137,7 @@ static void RemoteControlSet()
// 发射参数 // 发射参数
if (switch_is_up(rc_data[TEMP].rc.switch_right)) // 右侧开关状态[上],弹舱打开 if (switch_is_up(rc_data[TEMP].rc.switch_right)) // 右侧开关状态[上],弹舱打开
; // 弹舱舵机控制,待添加servo_motor模块,开启 ; // 弹舱舵机控制,待添加servo_motor模块,开启
else else
; // 弹舱舵机控制,待添加servo_motor模块,关闭 ; // 弹舱舵机控制,待添加servo_motor模块,关闭
@ -146,7 +152,7 @@ static void RemoteControlSet()
else else
shoot_cmd_send.load_mode = LOAD_STOP; shoot_cmd_send.load_mode = LOAD_STOP;
// 射频控制,固定每秒1发,后续可以根据左侧拨轮的值大小切换射频, // 射频控制,固定每秒1发,后续可以根据左侧拨轮的值大小切换射频,
shoot_cmd_send.shoot_rate = 1; shoot_cmd_send.shoot_rate = 8;
} }
/** /**
@ -162,7 +168,7 @@ static void MouseKeySet()
/** /**
* @brief ,/线/ * @brief ,/线/
* '300',. * '300',.
* *
* @todo 线(),daemon实现 * @todo 线(),daemon实现
* *
*/ */
@ -171,16 +177,16 @@ static void EmergencyHandler()
// 拨轮的向下拨超过一半进入急停模式.注意向打时下拨轮是正 // 拨轮的向下拨超过一半进入急停模式.注意向打时下拨轮是正
if (rc_data[TEMP].rc.dial > 300 || robot_state == ROBOT_STOP) // 还需添加重要应用和模块离线的判断 if (rc_data[TEMP].rc.dial > 300 || robot_state == ROBOT_STOP) // 还需添加重要应用和模块离线的判断
{ {
robot_state = ROBOT_STOP; robot_state = ROBOT_STOP; // 机器人状态保持急停
gimbal_cmd_send.gimbal_mode = GIMBAL_ZERO_FORCE; gimbal_cmd_send.gimbal_mode = GIMBAL_ZERO_FORCE; // 云台模式改为零力矩
chassis_cmd_send.chassis_mode = CHASSIS_ZERO_FORCE; chassis_cmd_send.chassis_mode = CHASSIS_ZERO_FORCE; // 底盘模式改为零力矩
shoot_cmd_send.shoot_mode = SHOOT_OFF; shoot_cmd_send.shoot_mode = SHOOT_OFF; // 射击模式改为关闭
} }
// 遥控器右侧开关为[上],恢复正常运行 // 遥控器右侧开关为[上],恢复正常运行
if (switch_is_up(rc_data[TEMP].rc.switch_right)) if (switch_is_up(rc_data[TEMP].rc.switch_right))
{ {
robot_state = ROBOT_READY; robot_state = ROBOT_READY; // 机器人状态改为准备就绪
shoot_cmd_send.shoot_mode = SHOOT_ON; shoot_cmd_send.shoot_mode = SHOOT_ON; // 射击模式改为开启
} }
} }
@ -199,7 +205,6 @@ void RobotCMDTask()
// 根据gimbal的反馈值计算云台和底盘正方向的夹角,不需要传参,通过static私有变量完成 // 根据gimbal的反馈值计算云台和底盘正方向的夹角,不需要传参,通过static私有变量完成
CalcOffsetAngle(); CalcOffsetAngle();
// 根据遥控器左侧开关,确定当前使用的控制模式为遥控器调试还是键鼠 // 根据遥控器左侧开关,确定当前使用的控制模式为遥控器调试还是键鼠
if (switch_is_down(rc_data[TEMP].rc.switch_left)) // 遥控器左侧开关状态为[下],遥控器控制 if (switch_is_down(rc_data[TEMP].rc.switch_left)) // 遥控器左侧开关状态为[下],遥控器控制
RemoteControlSet(); RemoteControlSet();
@ -209,8 +214,8 @@ void RobotCMDTask()
EmergencyHandler(); // 处理模块离线和遥控器急停等紧急情况 EmergencyHandler(); // 处理模块离线和遥控器急停等紧急情况
// 设置视觉发送数据,还需增加加速度和角速度数据 // 设置视觉发送数据,还需增加加速度和角速度数据
vision_send_data.bullet_speed = chassis_fetch_data.bullet_speed; vision_send_data.bullet_speed = 15;
vision_send_data.enemy_color = chassis_fetch_data.enemy_color; vision_send_data.enemy_color = 0;
vision_send_data.pitch = gimbal_fetch_data.gimbal_imu_data.Pitch; vision_send_data.pitch = gimbal_fetch_data.gimbal_imu_data.Pitch;
vision_send_data.yaw = gimbal_fetch_data.gimbal_imu_data.Yaw; vision_send_data.yaw = gimbal_fetch_data.gimbal_imu_data.Yaw;
vision_send_data.roll = gimbal_fetch_data.gimbal_imu_data.Roll; vision_send_data.roll = gimbal_fetch_data.gimbal_imu_data.Roll;

View File

@ -1,6 +1,7 @@
//
#include "gimbal.h" #include "gimbal.h"
#include "robot_def.h" #include "robot_def.h"
//
#include "dji_motor.h" #include "dji_motor.h"
#include "ins_task.h" #include "ins_task.h"
#include "message_center.h" #include "message_center.h"
@ -54,8 +55,8 @@ void GimbalInit()
.cali_mode=BMI088_CALIBRATE_ONLINE_MODE, .cali_mode=BMI088_CALIBRATE_ONLINE_MODE,
.work_mode=BMI088_BLOCK_PERIODIC_MODE, .work_mode=BMI088_BLOCK_PERIODIC_MODE,
}; };
// imu=BMI088Register(&imu_config); // imu=BMI088Register(&imu_config);
// gimba_IMU_data = INS_Init(); // IMU先初始化,获取姿态数据指针赋给yaw电机的其他数据来源 gimba_IMU_data = INS_Init(); // IMU先初始化,获取姿态数据指针赋给yaw电机的其他数据来源
// YAW // YAW
Motor_Init_Config_s yaw_config = { Motor_Init_Config_s yaw_config = {
.can_init_config = { .can_init_config = {
@ -64,60 +65,68 @@ void GimbalInit()
}, },
.controller_param_init_config = { .controller_param_init_config = {
.angle_PID = { .angle_PID = {
.Kp = 20, .Kp = 8, //8
.Ki = 0, .Ki = 0,
.Kd = 0, .Kd = 0,
.MaxOut = 2000, .DeadBand = 0.1,
.DeadBand = 0.3, .Improve = PID_Trapezoid_Intergral | PID_Integral_Limit |PID_Derivative_On_Measurement,
.IntegralLimit = 100,
.MaxOut = 500,
}, },
.speed_PID = { .speed_PID = {
.Kp = 10, .Kp = 50,//40
.Ki = 0, .Ki = 200,
.Kd = 0, .Kd = 0,
.MaxOut = 4000, .Improve = PID_Trapezoid_Intergral |PID_Integral_Limit |PID_Derivative_On_Measurement,
.IntegralLimit = 3000,
.MaxOut = 20000,
}, },
.other_angle_feedback_ptr = &gimba_IMU_data->YawTotalAngle, .other_angle_feedback_ptr = &gimba_IMU_data->YawTotalAngle,
// 还需要增加角速度额外反馈指针,注意方向,ins_task.md中有c板的bodyframe坐标系说明 // 还需要增加角速度额外反馈指针,注意方向,ins_task.md中有c板的bodyframe坐标系说明
// .other_speed_feedback_ptr=&gimba_IMU_data.wz; .other_speed_feedback_ptr=&gimba_IMU_data->Gyro[2],
}, },
.controller_setting_init_config = { .controller_setting_init_config = {
.angle_feedback_source = MOTOR_FEED, .angle_feedback_source = OTHER_FEED,
.speed_feedback_source = MOTOR_FEED, .speed_feedback_source = OTHER_FEED,
.outer_loop_type = ANGLE_LOOP, .outer_loop_type = ANGLE_LOOP,
.close_loop_type = ANGLE_LOOP | SPEED_LOOP, .close_loop_type = ANGLE_LOOP | SPEED_LOOP,
.reverse_flag = MOTOR_DIRECTION_NORMAL, .motor_reverse_flag = MOTOR_DIRECTION_NORMAL,
}, },
.motor_type = GM6020}; .motor_type = GM6020};
// PITCH // PITCH
Motor_Init_Config_s pitch_config = { Motor_Init_Config_s pitch_config = {
.can_init_config = { .can_init_config = {
.can_handle = &hcan1, .can_handle = &hcan2,
.tx_id = 2, .tx_id = 2,
}, },
.controller_param_init_config = { .controller_param_init_config = {
.angle_PID = { .angle_PID = {
.Kp = 30, .Kp =10,//10
.Ki = 0, .Ki = 0,
.Kd = 0, .Kd = 0,
.MaxOut = 4000, .Improve = PID_Trapezoid_Intergral | PID_Integral_Limit |PID_Derivative_On_Measurement,
.DeadBand = 0.3, .IntegralLimit =100,
.MaxOut = 500,
}, },
.speed_PID = { .speed_PID = {
.Kp = 10, .Kp=50,//50
.Ki = 0, .Ki =350,//350
.Kd = 0, .Kd =0,//0.1
.MaxOut = 4000, .Improve = PID_Trapezoid_Intergral | PID_Integral_Limit |PID_Derivative_On_Measurement,
.IntegralLimit =2500,
.MaxOut = 20000,
}, },
.other_angle_feedback_ptr = &gimba_IMU_data->Pitch, .other_angle_feedback_ptr = &gimba_IMU_data->Pitch,
// 还需要增加角速度额外反馈指针,注意方向,ins_task.md中有c板的bodyframe坐标系说明 // 还需要增加角速度额外反馈指针,注意方向,ins_task.md中有c板的bodyframe坐标系说明
// .other_speed_feedback_ptr=&gimba_IMU_data.wy, .other_speed_feedback_ptr=(&gimba_IMU_data->Gyro[0]),
}, },
.controller_setting_init_config = { .controller_setting_init_config = {
.angle_feedback_source = MOTOR_FEED, .angle_feedback_source = OTHER_FEED,
.speed_feedback_source = MOTOR_FEED, .speed_feedback_source = OTHER_FEED,
.outer_loop_type = ANGLE_LOOP, .outer_loop_type = ANGLE_LOOP,
.close_loop_type = ANGLE_LOOP | SPEED_LOOP, .close_loop_type = SPEED_LOOP | ANGLE_LOOP,
.reverse_flag = MOTOR_DIRECTION_NORMAL, .motor_reverse_flag = MOTOR_DIRECTION_NORMAL,
}, },
.motor_type = GM6020, .motor_type = GM6020,
}; };
@ -160,10 +169,10 @@ void GimbalTask()
case GIMBAL_FREE_MODE: // 后续删除,或加入云台追地盘的跟随模式(响应速度更快) case GIMBAL_FREE_MODE: // 后续删除,或加入云台追地盘的跟随模式(响应速度更快)
DJIMotorEnable(yaw_motor); DJIMotorEnable(yaw_motor);
DJIMotorEnable(pitch_motor); DJIMotorEnable(pitch_motor);
DJIMotorChangeFeed(yaw_motor, ANGLE_LOOP, MOTOR_FEED); DJIMotorChangeFeed(yaw_motor, ANGLE_LOOP, OTHER_FEED);
DJIMotorChangeFeed(yaw_motor, SPEED_LOOP, MOTOR_FEED); DJIMotorChangeFeed(yaw_motor, SPEED_LOOP, OTHER_FEED);
DJIMotorChangeFeed(pitch_motor, ANGLE_LOOP, MOTOR_FEED); DJIMotorChangeFeed(pitch_motor, ANGLE_LOOP, OTHER_FEED);
DJIMotorChangeFeed(pitch_motor, SPEED_LOOP, MOTOR_FEED); DJIMotorChangeFeed(pitch_motor, SPEED_LOOP, OTHER_FEED);
DJIMotorSetRef(yaw_motor, gimbal_cmd_recv.yaw); // yaw和pitch会在robot_cmd中处理好多圈和单圈 DJIMotorSetRef(yaw_motor, gimbal_cmd_recv.yaw); // yaw和pitch会在robot_cmd中处理好多圈和单圈
DJIMotorSetRef(pitch_motor, gimbal_cmd_recv.pitch); DJIMotorSetRef(pitch_motor, gimbal_cmd_recv.pitch);
break; break;

View File

@ -34,21 +34,25 @@
/* 机器人重要参数定义,注意根据不同机器人进行修改,浮点数需要以.0或f结尾,无符号以u结尾 */ /* 机器人重要参数定义,注意根据不同机器人进行修改,浮点数需要以.0或f结尾,无符号以u结尾 */
// 云台参数 // 云台参数
#define YAW_CHASSIS_ALIGN_ECD 4000 // 云台和底盘对齐指向相同方向时的电机编码器值,若对云台有机械改动需要修改 #define YAW_CHASSIS_ALIGN_ECD 2711 // 云台和底盘对齐指向相同方向时的电机编码器值,若对云台有机械改动需要修改
#define YAW_ECD_GREATER_THAN_4096 0 // ALIGN_ECD值是否大于4096,是为1,否为0;用于计算云台偏转角度 #define YAW_ECD_GREATER_THAN_4096 0 // ALIGN_ECD值是否大于4096,是为1,否为0;用于计算云台偏转角度
#define PITCH_HORIZON_ECD 0 // 云台处于水平位置时编码器值,若对云台有机械改动需要修改 #define PITCH_HORIZON_ECD 3412 // 云台处于水平位置时编码器值,若对云台有机械改动需要修改
// 发射参数 // 发射参数
#define ONE_BULLET_DELTA_ANGLE 0 // 发射一发弹丸拨盘转动的距离,由机械设计图纸给出 #define ONE_BULLET_DELTA_ANGLE 36 // 发射一发弹丸拨盘转动的距离,由机械设计图纸给出
#define REDUCTION_RATIO_LOADER 49.0f // 拨盘电机的减速比,英雄需要修改为3508的19.0f #define REDUCTION_RATIO_LOADER 49.0f // 拨盘电机的减速比,英雄需要修改为3508的19.0f
#define NUM_PER_CIRCLE 1 // 拨盘一圈的装载量 #define NUM_PER_CIRCLE 10 // 拨盘一圈的装载量
// 机器人底盘修改的参数,单位为mm(毫米) // 机器人底盘修改的参数,单位为mm(毫米)
#define WHEEL_BASE 300 // 纵向轴距(前进后退方向) #define WHEEL_BASE 350 // 纵向轴距(前进后退方向)
#define TRACK_WIDTH 300 // 横向轮距(左右平移方向) #define TRACK_WIDTH 300 // 横向轮距(左右平移方向)
#define CENTER_GIMBAL_OFFSET_X 0 // 云台旋转中心距底盘几何中心的距离,前后方向,云台位于正中心时默认设为0 #define CENTER_GIMBAL_OFFSET_X 0 // 云台旋转中心距底盘几何中心的距离,前后方向,云台位于正中心时默认设为0
#define CENTER_GIMBAL_OFFSET_Y 0 // 云台旋转中心距底盘几何中心的距离,左右方向,云台位于正中心时默认设为0 #define CENTER_GIMBAL_OFFSET_Y 0 // 云台旋转中心距底盘几何中心的距离,左右方向,云台位于正中心时默认设为0
#define RADIUS_WHEEL 60 // 轮子半径 #define RADIUS_WHEEL 60 // 轮子半径
#define REDUCTION_RATIO_WHEEL 19.0f // 电机减速比,因为编码器量测的是转子的速度而不是输出轴的速度故需进行转换 #define REDUCTION_RATIO_WHEEL 19.0f // 电机减速比,因为编码器量测的是转子的速度而不是输出轴的速度故需进行转换
#define GYRO2GIMBAL_DIR_YAW 1 //陀螺仪数据相较于云台的yaw的方向,1为相同,-1为相反
#define GYRO2GIMBAL_DIR_PITCH 1 //陀螺仪数据相较于云台的pitch的方向,1为相同,-1为相反
#define GYRO2GIMBAL_DIR_ROLL 1 //陀螺仪数据相较于云台的roll的方向,1为相同,-1为相反
// 检查是否出现主控板定义冲突,只允许一个开发板定义存在,否则编译会自动报错 // 检查是否出现主控板定义冲突,只允许一个开发板定义存在,否则编译会自动报错
#if (defined(ONE_BOARD) && defined(CHASSIS_BOARD)) || \ #if (defined(ONE_BOARD) && defined(CHASSIS_BOARD)) || \
(defined(ONE_BOARD) && defined(GIMBAL_BOARD)) || \ (defined(ONE_BOARD) && defined(GIMBAL_BOARD)) || \

View File

@ -26,20 +26,23 @@ void ShootInit()
Motor_Init_Config_s friction_config = { Motor_Init_Config_s friction_config = {
.can_init_config = { .can_init_config = {
.can_handle = &hcan2, .can_handle = &hcan2,
.tx_id = 6,
}, },
.controller_param_init_config = { .controller_param_init_config = {
.speed_PID = { .speed_PID = {
.Kp = 10, .Kp = 0,//20
.Ki = 0, .Ki = 0,//1
.Kd = 0, .Kd = 0,
.MaxOut = 2000, .Improve = PID_Integral_Limit,
.IntegralLimit = 10000,
.MaxOut = 15000,
}, },
.current_PID = { .current_PID = {
.Kp = 1, .Kp = 0,//0.7
.Ki = 0, .Ki = 0,//0.1
.Kd = 0, .Kd = 0,
.MaxOut = 2000, .Improve = PID_Integral_Limit,
.IntegralLimit = 10000,
.MaxOut = 15000,
}, },
}, },
.controller_setting_init_config = { .controller_setting_init_config = {
@ -48,47 +51,52 @@ void ShootInit()
.outer_loop_type = SPEED_LOOP, .outer_loop_type = SPEED_LOOP,
.close_loop_type = SPEED_LOOP | CURRENT_LOOP, .close_loop_type = SPEED_LOOP | CURRENT_LOOP,
.reverse_flag = MOTOR_DIRECTION_NORMAL, .motor_reverse_flag = MOTOR_DIRECTION_NORMAL,
}, },
.motor_type = M3508}; .motor_type = M3508};
friction_config.can_init_config.tx_id = 1,
friction_l = DJIMotorInit(&friction_config); friction_l = DJIMotorInit(&friction_config);
friction_config.can_init_config.tx_id = 5; // 右摩擦轮,改txid和方向就行 friction_config.can_init_config.tx_id = 2; // 右摩擦轮,改txid和方向就行
friction_config.controller_setting_init_config.reverse_flag = MOTOR_DIRECTION_NORMAL; friction_config.controller_setting_init_config.motor_reverse_flag = MOTOR_DIRECTION_REVERSE;
friction_r = DJIMotorInit(&friction_config); friction_r = DJIMotorInit(&friction_config);
// 拨盘电机 // 拨盘电机
Motor_Init_Config_s loader_config = { Motor_Init_Config_s loader_config = {
.can_init_config = { .can_init_config = {
.can_handle = &hcan2, .can_handle = &hcan2,
.tx_id = 7, .tx_id = 3,
}, },
.controller_param_init_config = { .controller_param_init_config = {
.angle_PID = { .angle_PID = {
// 如果启用位置环来控制发弹,需要较大的I值保证输出力矩的线性度否则出现接近拨出的力矩大幅下降 // 如果启用位置环来控制发弹,需要较大的I值保证输出力矩的线性度否则出现接近拨出的力矩大幅下降
.Kp = 10, .Kp = 0,//10
.Ki = 0, .Ki = 0,
.Kd = 0, .Kd = 0,
.MaxOut = 200, .MaxOut = 200,
}, },
.speed_PID = { .speed_PID = {
.Kp = 1, .Kp = 0,//10
.Ki = 0, .Ki = 0,//1
.Kd = 0, .Kd = 0,
.MaxOut = 2000, .Improve = PID_Integral_Limit,
.IntegralLimit = 5000,
.MaxOut = 5000,
}, },
.current_PID = { .current_PID = {
.Kp = 1, .Kp = 0,//0.7
.Ki = 0, .Ki = 0,//0.1
.Kd = 0, .Kd = 0,
.MaxOut = 3000, .Improve = PID_Integral_Limit,
.IntegralLimit = 5000,
.MaxOut = 5000,
}, },
}, },
.controller_setting_init_config = { .controller_setting_init_config = {
.angle_feedback_source = MOTOR_FEED, .speed_feedback_source = MOTOR_FEED, .angle_feedback_source = MOTOR_FEED, .speed_feedback_source = MOTOR_FEED,
.outer_loop_type = SPEED_LOOP, // 初始化成SPEED_LOOP,让拨盘停在原地,防止拨盘上电时乱转 .outer_loop_type = SPEED_LOOP, // 初始化成SPEED_LOOP,让拨盘停在原地,防止拨盘上电时乱转
.close_loop_type = ANGLE_LOOP | SPEED_LOOP, .close_loop_type = CURRENT_LOOP | SPEED_LOOP,
.reverse_flag = MOTOR_DIRECTION_NORMAL, // 注意方向设置为拨盘的拨出的击发方向 .motor_reverse_flag = MOTOR_DIRECTION_NORMAL, // 注意方向设置为拨盘的拨出的击发方向
}, },
.motor_type = M2006 // 英雄使用m3508 .motor_type = M2006 // 英雄使用m3508
}; };
@ -120,8 +128,8 @@ void ShootTask()
// 如果上一次触发单发或3发指令的时间加上不应期仍然大于当前时间(尚未休眠完毕),直接返回即可 // 如果上一次触发单发或3发指令的时间加上不应期仍然大于当前时间(尚未休眠完毕),直接返回即可
// 单发模式主要提供给能量机关激活使用(以及英雄的射击大部分处于单发) // 单发模式主要提供给能量机关激活使用(以及英雄的射击大部分处于单发)
if (hibernate_time + dead_time > DWT_GetTimeline_ms()) // if (hibernate_time + dead_time > DWT_GetTimeline_ms())
return; // return;
// 若不在休眠状态,根据robotCMD传来的控制模式进行拨盘电机参考值设定和模式切换 // 若不在休眠状态,根据robotCMD传来的控制模式进行拨盘电机参考值设定和模式切换
switch (shoot_cmd_recv.load_mode) switch (shoot_cmd_recv.load_mode)
@ -182,8 +190,8 @@ void ShootTask()
DJIMotorSetRef(friction_r, 0); DJIMotorSetRef(friction_r, 0);
break; break;
default: // 当前为了调试设定的默认值4000,因为还没有加入裁判系统无法读取弹速. default: // 当前为了调试设定的默认值4000,因为还没有加入裁判系统无法读取弹速.
DJIMotorSetRef(friction_l, 1000); DJIMotorSetRef(friction_l, 30000);
DJIMotorSetRef(friction_r, 1000); DJIMotorSetRef(friction_r, 30000);
break; break;
} }
} }

View File

@ -46,8 +46,8 @@ USARTInstance *USARTRegister(USART_Init_Config_s *init_config);
/** /**
* @brief ,usart实例.lost callback的情况(使daemon) * @brief ,usart实例.lost callback的情况(使daemon)
* *
* @param _instance * @param _instance
*/ */
void USARTServiceInit(USARTInstance *_instance); void USARTServiceInit(USARTInstance *_instance);
@ -66,7 +66,7 @@ void USARTSend(USARTInstance *_instance, uint8_t *send_buf, uint16_t send_size,U
/** /**
* @brief ,IT/DMA发送 * @brief ,IT/DMA发送
* *
* @param _instance * @param _instance
* @return uint8_t ready 1, busy 0 * @return uint8_t ready 1, busy 0
*/ */

View File

@ -65,10 +65,10 @@ typedef struct
// improve parameter // improve parameter
PID_Improvement_e Improve; PID_Improvement_e Improve;
float IntegralLimit; // 积分限幅 float IntegralLimit; // 积分限幅
float CoefA; // 变速积分 For Changing Integral float CoefA; // 变速积分 For Changing Integral
float CoefB; // 变速积分 ITerm = Err*((A-abs(err)+B)/A) when B<|err|<A+B float CoefB; // 变速积分 ITerm = Err*((A-abs(err)+B)/A) when B<|err|<A+B
float Output_LPF_RC; // 输出滤波器 RC = 1/omegac float Output_LPF_RC; // 输出滤波器 RC = 1/omegac
float Derivative_LPF_RC; // 微分滤波器系数 float Derivative_LPF_RC; // 微分滤波器系数
//----------------------------------- //-----------------------------------
@ -113,6 +113,7 @@ typedef struct // config parameter
float CoefB; // ITerm = Err*((A-abs(err)+B)/A) when B<|err|<A+B float CoefB; // ITerm = Err*((A-abs(err)+B)/A) when B<|err|<A+B
float Output_LPF_RC; // RC = 1/omegac float Output_LPF_RC; // RC = 1/omegac
float Derivative_LPF_RC; float Derivative_LPF_RC;
} PID_Init_Config_s; } PID_Init_Config_s;
/** /**

View File

@ -17,7 +17,7 @@
#include "bsp_temperature.h" #include "bsp_temperature.h"
#include "spi.h" #include "spi.h"
#include "user_lib.h" #include "user_lib.h"
#include "general_def.h"
static INS_t INS; static INS_t INS;
static IMU_Param_t IMU_Param; static IMU_Param_t IMU_Param;
static PIDInstance TempCtrl = {0}; static PIDInstance TempCtrl = {0};
@ -118,7 +118,6 @@ void INS_Task(void)
} }
BodyFrameToEarthFrame(INS.MotionAccel_b, INS.MotionAccel_n, INS.q); // 转换回导航系n BodyFrameToEarthFrame(INS.MotionAccel_b, INS.MotionAccel_n, INS.q); // 转换回导航系n
// 获取最终数据
INS.Yaw = QEKF_INS.Yaw; INS.Yaw = QEKF_INS.Yaw;
INS.Pitch = QEKF_INS.Pitch; INS.Pitch = QEKF_INS.Pitch;
INS.Roll = QEKF_INS.Roll; INS.Roll = QEKF_INS.Roll;

View File

@ -33,8 +33,6 @@ static void DecodeVision()
DaemonReload(vision_daemon_instance); // 喂狗 DaemonReload(vision_daemon_instance); // 喂狗
get_protocol_info(vision_usart_instance->recv_buff, &flag_register, (uint8_t *)&recv_data.pitch); get_protocol_info(vision_usart_instance->recv_buff, &flag_register, (uint8_t *)&recv_data.pitch);
// TODO: code to resolve flag_register; // TODO: code to resolve flag_register;
PrintLog("decode vision");
} }
/** /**

View File

@ -4,7 +4,7 @@
#include "bsp_usart.h" #include "bsp_usart.h"
#include "seasky_protocol.h" #include "seasky_protocol.h"
#define VISION_RECV_SIZE 36u // 当前为固定值,36字节 #define VISION_RECV_SIZE 18u // 当前为固定值,36字节
#define VISION_SEND_SIZE 36u #define VISION_SEND_SIZE 36u
#pragma pack(1) #pragma pack(1)

View File

@ -233,7 +233,8 @@ void DJIMotorControl()
motor_controller = &motor->motor_controller; motor_controller = &motor->motor_controller;
motor_measure = &motor->motor_measure; motor_measure = &motor->motor_measure;
pid_ref = motor_controller->pid_ref; // 保存设定值,防止motor_controller->pid_ref在计算过程中被修改 pid_ref = motor_controller->pid_ref; // 保存设定值,防止motor_controller->pid_ref在计算过程中被修改
if (motor_setting->motor_reverse_flag == MOTOR_DIRECTION_REVERSE)
pid_ref*= -1; // 设置反转
// pid_ref会顺次通过被启用的闭环充当数据的载体 // pid_ref会顺次通过被启用的闭环充当数据的载体
// 计算位置环,只有启用位置环且外层闭环为位置时会计算速度环输出 // 计算位置环,只有启用位置环且外层闭环为位置时会计算速度环输出
if ((motor_setting->close_loop_type & ANGLE_LOOP) && motor_setting->outer_loop_type == ANGLE_LOOP) if ((motor_setting->close_loop_type & ANGLE_LOOP) && motor_setting->outer_loop_type == ANGLE_LOOP)
@ -265,8 +266,7 @@ void DJIMotorControl()
// 获取最终输出 // 获取最终输出
set = (int16_t)pid_ref; set = (int16_t)pid_ref;
if (motor_setting->reverse_flag == MOTOR_DIRECTION_REVERSE)
set *= -1; // 设置反转
// 分组填入发送数据 // 分组填入发送数据
group = motor->sender_group; group = motor->sender_group;

View File

@ -142,7 +142,7 @@ Motor_Init_Config_s config = {
.outer_loop_type = SPEED_LOOP, .outer_loop_type = SPEED_LOOP,
.close_loop_type = SPEED_LOOP | CURRENT_LOOP, .close_loop_type = SPEED_LOOP | CURRENT_LOOP,
.speed_feedback_source = MOTOR_FEED, .speed_feedback_source = MOTOR_FEED,
.reverse_flag = MOTOR_DIRECTION_NORMAL}, .motor_reverse_flag = MOTOR_DIRECTION_NORMAL},
// 电流环和速度环PID参数的设置,不采用计算优化则不需要传入Improve参数 // 电流环和速度环PID参数的设置,不采用计算优化则不需要传入Improve参数
// 不使用其他数据来源(如IMU),不需要传入反馈数据变量指针 // 不使用其他数据来源(如IMU),不需要传入反馈数据变量指针
.controller_param_init_config = {.current_PID = {.Improve = 0, .controller_param_init_config = {.current_PID = {.Improve = 0,
@ -245,7 +245,7 @@ typedef struct
{ {
Closeloop_Type_e outer_loop_type; Closeloop_Type_e outer_loop_type;
Closeloop_Type_e close_loop_type; Closeloop_Type_e close_loop_type;
Reverse_Flag_e reverse_flag; Motor_Reverse_Flag_e motor_reverse_flag;
Feedback_Source_e angle_feedback_source; Feedback_Source_e angle_feedback_source;
Feedback_Source_e speed_feedback_source; Feedback_Source_e speed_feedback_source;
} Motor_Control_Setting_s; } Motor_Control_Setting_s;
@ -272,14 +272,14 @@ typedef struct
> 注意务必分清串级控制多环和外层闭环的区别。前者是为了提高内环的性能使得其能更好地跟随外环参考值而后者描述的是系统真实的控制目标闭环目标。如3508没有电流环仍然可以对速度完成闭环对于高层的应用来说它们本质上不关心电机内部是否还有电流环它们只把外层闭环为速度的电机当作一个**速度伺服执行器****外层闭环**描述的就是真正的闭环目标。 > 注意务必分清串级控制多环和外层闭环的区别。前者是为了提高内环的性能使得其能更好地跟随外环参考值而后者描述的是系统真实的控制目标闭环目标。如3508没有电流环仍然可以对速度完成闭环对于高层的应用来说它们本质上不关心电机内部是否还有电流环它们只把外层闭环为速度的电机当作一个**速度伺服执行器****外层闭环**描述的就是真正的闭环目标。
- 为了避开恼人的正负号,提高代码的可维护性,在初始化电机时设定`reverse_flag`使得所有电机都按照你想要的方向旋转,其定义如下: - 为了避开恼人的正负号,提高代码的可维护性,在初始化电机时设定`motor_reverse_flag`使得所有电机都按照你想要的方向旋转,其定义如下:
```c ```c
typedef enum typedef enum
{ {
MOTOR_DIRECTION_NORMAL = 0, MOTOR_DIRECTION_NORMAL = 0,
MOTOR_DIRECTION_REVERSE = 1 MOTOR_DIRECTION_REVERSE = 1
} Reverse_Flag_e; } Motor_Reverse_Flag_e;
``` ```
- `speed_feedback_source`以及`angle_feedback_source`是指示电机反馈来源的标志位。一般情况下电机使用自身的编码器作为控制反馈量。但在某些时候如小陀螺模式云台电机会使用IMU的姿态数据作为反馈数据来源。其定义如下 - `speed_feedback_source`以及`angle_feedback_source`是指示电机反馈来源的标志位。一般情况下电机使用自身的编码器作为控制反馈量。但在某些时候如小陀螺模式云台电机会使用IMU的姿态数据作为反馈数据来源。其定义如下
@ -437,7 +437,7 @@ Motor_Init_Config_s config = {
.outer_loop_type = SPEED_LOOP, .outer_loop_type = SPEED_LOOP,
.close_loop_type = SPEED_LOOP | ANGLE_LOOP, .close_loop_type = SPEED_LOOP | ANGLE_LOOP,
.speed_feedback_source = MOTOR_FEED, .speed_feedback_source = MOTOR_FEED,
.reverse_flag = MOTOR_DIRECTION_NORMAL .motor_reverse_flag = MOTOR_DIRECTION_NORMAL
}, },
.controller_param_init_config = { .controller_param_init_config = {
.angle_PID = { .angle_PID = {

View File

@ -134,7 +134,7 @@ void HTMotorControl()
} }
set = pid_ref; set = pid_ref;
if (setting->reverse_flag == MOTOR_DIRECTION_REVERSE) if (setting->motor_reverse_flag == MOTOR_DIRECTION_REVERSE)
set *= -1; set *= -1;
LIMIT_MIN_MAX(set, T_MIN, T_MAX); // 限幅,实际上这似乎和pid输出限幅重复了 LIMIT_MIN_MAX(set, T_MIN, T_MAX); // 限幅,实际上这似乎和pid输出限幅重复了

View File

@ -113,7 +113,7 @@ void LKMotorControl()
} }
set = pid_ref; set = pid_ref;
if (setting->reverse_flag == MOTOR_DIRECTION_REVERSE) if (setting->motor_reverse_flag == MOTOR_DIRECTION_REVERSE)
set *= -1; set *= -1;
// 这里随便写的,为了兼容多电机命令.后续应该将tx_id以更好的方式表达电机id,单独使用一个CANInstance,而不是用第一个电机的CANInstance // 这里随便写的,为了兼容多电机命令.后续应该将tx_id以更好的方式表达电机id,单独使用一个CANInstance,而不是用第一个电机的CANInstance
memcpy(sender_instance->tx_buff + (motor->motor_can_ins->tx_id - 0x280) * 2, &set, sizeof(uint16_t)); memcpy(sender_instance->tx_buff + (motor->motor_can_ins->tx_id - 0x280) * 2, &set, sizeof(uint16_t));

View File

@ -54,8 +54,14 @@ typedef enum
{ {
MOTOR_DIRECTION_NORMAL = 0, MOTOR_DIRECTION_NORMAL = 0,
MOTOR_DIRECTION_REVERSE = 1 MOTOR_DIRECTION_REVERSE = 1
} Reverse_Flag_e; } Motor_Reverse_Flag_e;
/* 反馈量正反标志 */
typedef enum
{
FEEDBACK_DIRECTION_NORMAL = 0,
FEEDBACK_DIRECTION_REVERSE = 1
} Feedback_Reverse_Flag_e;
typedef enum typedef enum
{ {
MOTOR_STOP = 0, MOTOR_STOP = 0,
@ -67,7 +73,8 @@ typedef struct
{ {
Closeloop_Type_e outer_loop_type; // 最外层的闭环,未设置时默认为最高级的闭环 Closeloop_Type_e outer_loop_type; // 最外层的闭环,未设置时默认为最高级的闭环
Closeloop_Type_e close_loop_type; // 使用几个闭环(串级) Closeloop_Type_e close_loop_type; // 使用几个闭环(串级)
Reverse_Flag_e reverse_flag; // 是否反转 Motor_Reverse_Flag_e motor_reverse_flag; // 是否反转
Feedback_Reverse_Flag_e feedback_reverse_flag; // 反馈是否反向
Feedback_Source_e angle_feedback_source; // 角度反馈类型 Feedback_Source_e angle_feedback_source; // 角度反馈类型
Feedback_Source_e speed_feedback_source; // 速度反馈类型 Feedback_Source_e speed_feedback_source; // 速度反馈类型
Feedfoward_Type_e feedforward_flag; // 前馈标志 Feedfoward_Type_e feedforward_flag; // 前馈标志