Merge remote-tracking branch 'origin/master'
# Conflicts: # application/cmd/robot_cmd.c # application/gimbal/gimbal.c
This commit is contained in:
commit
ea4db9d4e9
|
@ -15,7 +15,7 @@
|
|||
{
|
||||
"label": "download dap",
|
||||
"type": "shell", // 如果希望在下载前编译,可以把command换成下面的命令
|
||||
"command":"mingw32-make -j24 ; mingw32-make download_dap", // "mingw32-make -j24 && mingw32-make download_dap",
|
||||
"command":"mingw32-make download_dap", // "mingw32-make -j24 ; mingw32-make download_dap",
|
||||
"group": { // 如果没有修改代码,编译任务不会消耗时间,因此推荐使用上面的替换.
|
||||
"kind": "build",
|
||||
"isDefault": false,
|
||||
|
@ -24,7 +24,7 @@
|
|||
{
|
||||
"label": "download jlink",
|
||||
"type": "shell",
|
||||
"command":"mingw32-make -j24 ; mingw32-make download_jlink", // "mingw32-make -j24 && mingw32-make download_dap"
|
||||
"command":"mingw32-make download_jlink", // "mingw32-make -j24 ; mingw32-make download_dap"
|
||||
"group": {
|
||||
"kind": "build",
|
||||
"isDefault": false,
|
||||
|
|
|
@ -48,4 +48,22 @@
|
|||
|
||||
### 紧急程度
|
||||
|
||||
⭐⭐⭐⭐⭐
|
||||
⭐⭐⭐⭐⭐
|
||||
|
||||
## 总线挂载多个电机后,pitch和yaw的GM6020电机出现编码器反馈值跳动
|
||||
|
||||
> 已修复,详细信息见“如何定位bug.md”
|
||||
|
||||
CAN1总线挂载5个电机,4\*3508+1\*6020,控制报文发送频率为500Hz,电机的反馈频率皆为1kHz.云台在控制时会出现突然跳动.添加到Ozone graph查看发现ECD(编码器)值在静止状态下也会出现突然抖动,并且幅度超过4000.但不会出现超过编码器反馈值范围的值.
|
||||
|
||||
### 尝试解决的方案
|
||||
|
||||
若使用单个6020电机,不会出现此问题. 曾认为是指针越界导致`motor_measure->ecd`值被修改, 需要进一步观察其他反馈值是否出现问题. 且反馈值始终在编码器范围之内.
|
||||
|
||||
### 如何复现问题
|
||||
|
||||
同时启用CAN1和CAN2,并在单条CAN总线上挂载超过5个电机.
|
||||
|
||||
### 紧急程度
|
||||
|
||||
⭐⭐⭐
|
|
@ -30,7 +30,6 @@
|
|||
#include "led_task.h"
|
||||
#include "daemon.h"
|
||||
#include "robot.h"
|
||||
#include "ps_handle.h"
|
||||
|
||||
/* USER CODE END Includes */
|
||||
|
||||
|
|
2
Makefile
2
Makefile
|
@ -141,7 +141,6 @@ modules/can_comm/can_comm.c \
|
|||
modules/message_center/message_center.c \
|
||||
modules/daemon/daemon.c \
|
||||
modules/vofa/vofa.c \
|
||||
modules/ps_handle/ps_handle.c \
|
||||
application/gimbal/gimbal.c \
|
||||
application/chassis/chassis.c \
|
||||
application/shoot/shoot.c \
|
||||
|
@ -263,7 +262,6 @@ C_INCLUDES = \
|
|||
-Imodules/message_center \
|
||||
-Imodules/daemon \
|
||||
-Imodules/vofa \
|
||||
-Imodules/ps_handle \
|
||||
-Imodules
|
||||
|
||||
# compile gcc flags
|
||||
|
|
|
@ -659,7 +659,7 @@ Project.SetOSPlugin(“plugin_name”)
|
|||
|
||||
在Terminal窗口查看,还可以通过命令直接控制单片机的运行(不过不常用)。
|
||||
|
||||
未打开窗口则在view-> terminal中打开。
|
||||
未打开窗口则在view-> terminal中打开。使用bsp_log打印的日志会输出到该窗口中.
|
||||
|
||||
- **外设查看**
|
||||
|
||||
|
|
|
@ -240,14 +240,14 @@ static void MouseKeySet()
|
|||
switch (rc_data[TEMP].key[KEY_PRESS].shift) //待添加 按shift允许超功率 消耗缓冲能量
|
||||
{
|
||||
case 1:
|
||||
|
||||
|
||||
break;
|
||||
|
||||
|
||||
default:
|
||||
|
||||
break;
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -281,7 +281,7 @@ static void EmergencyHandler()
|
|||
robot_state = ROBOT_READY;
|
||||
shoot_cmd_send.shoot_mode = SHOOT_ON;
|
||||
break;
|
||||
|
||||
|
||||
default:
|
||||
robot_state = ROBOT_STOP;
|
||||
gimbal_cmd_send.gimbal_mode = GIMBAL_ZERO_FORCE;
|
||||
|
|
|
@ -20,41 +20,41 @@ BMI088Instance* imu;
|
|||
void GimbalInit()
|
||||
{
|
||||
BMI088_Init_Config_s imu_config = {
|
||||
.spi_acc_config={
|
||||
.GPIOx=CS1_ACCEL_GPIO_Port,
|
||||
.cs_pin=CS1_ACCEL_Pin,
|
||||
.spi_handle=&hspi1,
|
||||
.spi_acc_config = {
|
||||
.GPIOx = CS1_ACCEL_GPIO_Port,
|
||||
.cs_pin = CS1_ACCEL_Pin,
|
||||
.spi_handle = &hspi1,
|
||||
},
|
||||
.spi_gyro_config={
|
||||
.GPIOx=CS1_GYRO_GPIO_Port,
|
||||
.cs_pin=CS1_GYRO_Pin,
|
||||
.spi_handle=&hspi1,
|
||||
.spi_gyro_config = {
|
||||
.GPIOx = CS1_GYRO_GPIO_Port,
|
||||
.cs_pin = CS1_GYRO_Pin,
|
||||
.spi_handle = &hspi1,
|
||||
},
|
||||
.acc_int_config={
|
||||
.exti_mode=EXTI_TRIGGER_FALLING,
|
||||
.GPIO_Pin=INT_ACC_Pin,
|
||||
.GPIOx=INT_ACC_GPIO_Port,
|
||||
.acc_int_config = {
|
||||
.exti_mode = EXTI_TRIGGER_FALLING,
|
||||
.GPIO_Pin = INT_ACC_Pin,
|
||||
.GPIOx = INT_ACC_GPIO_Port,
|
||||
},
|
||||
.gyro_int_config={
|
||||
.exti_mode=EXTI_TRIGGER_FALLING,
|
||||
.GPIO_Pin=INT_GYRO_Pin,
|
||||
.GPIOx=INT_GYRO_GPIO_Port,
|
||||
.gyro_int_config = {
|
||||
.exti_mode = EXTI_TRIGGER_FALLING,
|
||||
.GPIO_Pin = INT_GYRO_Pin,
|
||||
.GPIOx = INT_GYRO_GPIO_Port,
|
||||
},
|
||||
.heat_pid_config={
|
||||
.Kp=0.0f,
|
||||
.Kd=0.0f,
|
||||
.Ki=0.0f,
|
||||
.MaxOut=0.0f,
|
||||
.DeadBand=0.0f,
|
||||
.heat_pid_config = {
|
||||
.Kp = 0.0f,
|
||||
.Kd = 0.0f,
|
||||
.Ki = 0.0f,
|
||||
.MaxOut = 0.0f,
|
||||
.DeadBand = 0.0f,
|
||||
},
|
||||
.heat_pwm_config={
|
||||
.channel=TIM_CHANNEL_1,
|
||||
.htim=&htim1,
|
||||
.heat_pwm_config = {
|
||||
.channel = TIM_CHANNEL_1,
|
||||
.htim = &htim1,
|
||||
},
|
||||
.cali_mode=BMI088_CALIBRATE_ONLINE_MODE,
|
||||
.work_mode=BMI088_BLOCK_PERIODIC_MODE,
|
||||
.cali_mode = BMI088_CALIBRATE_ONLINE_MODE,
|
||||
.work_mode = BMI088_BLOCK_PERIODIC_MODE,
|
||||
};
|
||||
// imu=BMI088Register(&imu_config);
|
||||
// imu=BMI088Register(&imu_config);
|
||||
gimba_IMU_data = INS_Init(); // IMU先初始化,获取姿态数据指针赋给yaw电机的其他数据来源
|
||||
// YAW
|
||||
Motor_Init_Config_s yaw_config = {
|
||||
|
@ -101,11 +101,11 @@ void GimbalInit()
|
|||
},
|
||||
.controller_param_init_config = {
|
||||
.angle_PID = {
|
||||
.Kp =10,//10
|
||||
.Kp = 10, // 10
|
||||
.Ki = 0,
|
||||
.Kd = 0,
|
||||
.Improve = PID_Trapezoid_Intergral | PID_Integral_Limit |PID_Derivative_On_Measurement,
|
||||
.IntegralLimit =100,
|
||||
.Improve = PID_Trapezoid_Intergral | PID_Integral_Limit | PID_Derivative_On_Measurement,
|
||||
.IntegralLimit = 100,
|
||||
.MaxOut = 500,
|
||||
},
|
||||
.speed_PID = {
|
||||
|
@ -118,7 +118,7 @@ void GimbalInit()
|
|||
},
|
||||
.other_angle_feedback_ptr = &gimba_IMU_data->Pitch,
|
||||
// 还需要增加角速度额外反馈指针,注意方向,ins_task.md中有c板的bodyframe坐标系说明
|
||||
.other_speed_feedback_ptr=(&gimba_IMU_data->Gyro[0]),
|
||||
.other_speed_feedback_ptr = (&gimba_IMU_data->Gyro[0]),
|
||||
},
|
||||
.controller_setting_init_config = {
|
||||
.angle_feedback_source = OTHER_FEED,
|
||||
|
@ -136,7 +136,7 @@ void GimbalInit()
|
|||
gimbal_pub = PubRegister("gimbal_feed", sizeof(Gimbal_Upload_Data_s));
|
||||
gimbal_sub = SubRegister("gimbal_cmd", sizeof(Gimbal_Ctrl_Cmd_s));
|
||||
}
|
||||
int aaaaaaa;
|
||||
|
||||
/* 机器人云台控制核心任务,后续考虑只保留IMU控制,不再需要电机的反馈 */
|
||||
void GimbalTask()
|
||||
{
|
||||
|
@ -178,10 +178,7 @@ void GimbalTask()
|
|||
default:
|
||||
break;
|
||||
}
|
||||
// if(yaw_motor->motor_measure.total_angle>120)
|
||||
// {
|
||||
// aaaaaaa++;
|
||||
// }
|
||||
|
||||
// 在合适的地方添加pitch重力补偿前馈力矩
|
||||
// 根据IMU姿态/pitch电机角度反馈计算出当前配重下的重力矩
|
||||
// ...
|
||||
|
|
|
@ -276,9 +276,9 @@ Mcu.UserName=STM32F407IGHx
|
|||
MxCube.Version=6.7.0
|
||||
MxDb.Version=DB.6.0.70
|
||||
NVIC.BusFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false\:false
|
||||
NVIC.CAN1_RX0_IRQn=true\:6\:0\:true\:false\:true\:true\:true\:true\:true
|
||||
NVIC.CAN1_RX0_IRQn=true\:5\:0\:true\:false\:true\:true\:true\:true\:true
|
||||
NVIC.CAN1_RX1_IRQn=true\:5\:0\:false\:false\:true\:true\:true\:true\:true
|
||||
NVIC.CAN2_RX0_IRQn=true\:6\:0\:true\:false\:true\:true\:true\:true\:true
|
||||
NVIC.CAN2_RX0_IRQn=true\:5\:0\:true\:false\:true\:true\:true\:true\:true
|
||||
NVIC.CAN2_RX1_IRQn=true\:5\:0\:false\:false\:true\:true\:true\:true\:true
|
||||
NVIC.DMA1_Stream1_IRQn=true\:5\:0\:false\:false\:true\:true\:false\:true\:true
|
||||
NVIC.DMA1_Stream2_IRQn=true\:5\:0\:false\:false\:true\:true\:false\:true\:true
|
||||
|
@ -432,7 +432,7 @@ PF0.Mode=I2C
|
|||
PF0.Signal=I2C2_SDA
|
||||
PF1.Mode=I2C
|
||||
PF1.Signal=I2C2_SCL
|
||||
PF6.GPIOParameters=GPIO_Label,GPIO_Speed,GPIO_PuPd
|
||||
PF6.GPIOParameters=GPIO_Speed,GPIO_PuPd,GPIO_Label
|
||||
PF6.GPIO_Label=IMU_TEMP
|
||||
PF6.GPIO_PuPd=GPIO_PULLUP
|
||||
PF6.GPIO_Speed=GPIO_SPEED_FREQ_HIGH
|
||||
|
|
|
@ -131,9 +131,9 @@ void CANSetDLC(CANInstance *_instance, uint8_t length)
|
|||
*/
|
||||
static void CANFIFOxCallback(CAN_HandleTypeDef *_hcan, uint32_t fifox)
|
||||
{
|
||||
static uint8_t can_rx_buff[8]; // 用于保存接收到的数据,static是为了减少栈空间占用,避免重复分配
|
||||
static CAN_RxHeaderTypeDef rxconf; // 同上
|
||||
|
||||
uint8_t can_rx_buff[8];
|
||||
|
||||
HAL_CAN_GetRxMessage(_hcan, fifox, &rxconf, can_rx_buff); // 从FIFO中获取数据
|
||||
for (size_t i = 0; i < idx; ++i)
|
||||
{ // 两者相等说明这是要找的实例
|
||||
|
|
|
@ -15,7 +15,7 @@ static GPIOInstance *gpio_instance[GPIO_MX_DEVICE_NUM] = {NULL};
|
|||
void HAL_GPIO_EXTI_Callback(uint16_t GPIO_Pin)
|
||||
{
|
||||
// 如有必要,可以根据pinstate和HAL_GPIO_ReadPin来判断是上升沿还是下降沿/rise&fall等
|
||||
static GPIOInstance *gpio;
|
||||
GPIOInstance *gpio;
|
||||
for (size_t i = 0; i < idx; i++)
|
||||
{
|
||||
gpio = gpio_instance[i];
|
||||
|
|
|
@ -65,10 +65,10 @@ typedef struct
|
|||
|
||||
// improve parameter
|
||||
PID_Improvement_e Improve;
|
||||
float IntegralLimit; // 积分限幅
|
||||
float CoefA; // 变速积分 For Changing Integral
|
||||
float CoefB; // 变速积分 ITerm = Err*((A-abs(err)+B)/A) when B<|err|<A+B
|
||||
float Output_LPF_RC; // 输出滤波器 RC = 1/omegac
|
||||
float IntegralLimit; // 积分限幅
|
||||
float CoefA; // 变速积分 For Changing Integral
|
||||
float CoefB; // 变速积分 ITerm = Err*((A-abs(err)+B)/A) when B<|err|<A+B
|
||||
float Output_LPF_RC; // 输出滤波器 RC = 1/omegac
|
||||
float Derivative_LPF_RC; // 微分滤波器系数
|
||||
|
||||
//-----------------------------------
|
||||
|
@ -113,8 +113,6 @@ typedef struct // config parameter
|
|||
float CoefB; // ITerm = Err*((A-abs(err)+B)/A) when B<|err|<A+B
|
||||
float Output_LPF_RC; // RC = 1/omegac
|
||||
float Derivative_LPF_RC;
|
||||
|
||||
|
||||
} PID_Init_Config_s;
|
||||
|
||||
/**
|
||||
|
|
|
@ -23,8 +23,7 @@ static void CANCommResetRx(CANCommInstance *ins)
|
|||
*/
|
||||
static void CANCommRxCallback(CANInstance *_instance)
|
||||
{
|
||||
static CANCommInstance *comm;
|
||||
comm = (CANCommInstance *)_instance->id; // 注意写法,将can instance的id强制转换为CANCommInstance*类型
|
||||
CANCommInstance *comm = (CANCommInstance *)_instance->id; // 注意写法,将can instance的id强制转换为CANCommInstance*类型
|
||||
|
||||
/* 接收状态判断 */
|
||||
if (_instance->rx_buff[0] == CAN_COMM_HEADER && comm->recv_state == 0) // 之前尚未开始接收且此次包里第一个位置是帧头
|
||||
|
|
|
@ -33,7 +33,7 @@ uint8_t DaemonIsOnline(DaemonInstance *instance)
|
|||
|
||||
void DaemonTask()
|
||||
{
|
||||
static DaemonInstance *dins; // 提高可读性同时降低访存开销
|
||||
DaemonInstance *dins; // 提高可读性同时降低访存开销
|
||||
for (size_t i = 0; i < idx; ++i)
|
||||
{
|
||||
dins = daemon_instances[i];
|
||||
|
|
|
@ -118,18 +118,10 @@ void INS_Task(void)
|
|||
}
|
||||
BodyFrameToEarthFrame(INS.MotionAccel_b, INS.MotionAccel_n, INS.q); // 转换回导航系n
|
||||
|
||||
//获取最终数据
|
||||
INS.Accel[X] = INS.Accel[X]*RAD_2_ANGLE;
|
||||
INS.Accel[Y] = INS.Accel[Y]*RAD_2_ANGLE;
|
||||
INS.Accel[Z] = INS.Accel[Z]*RAD_2_ANGLE;
|
||||
INS.Gyro[X] = INS.Gyro[X]*RAD_2_ANGLE;
|
||||
INS.Gyro[Y] = INS.Gyro[Y]*RAD_2_ANGLE;
|
||||
INS.Gyro[Z] = INS.Gyro[Z]*RAD_2_ANGLE;
|
||||
INS.Yaw = QEKF_INS.Yaw;
|
||||
INS.Pitch = QEKF_INS.Pitch;
|
||||
INS.Roll = QEKF_INS.Roll;
|
||||
INS.YawTotalAngle = QEKF_INS.YawTotalAngle;
|
||||
|
||||
}
|
||||
|
||||
// temperature control
|
||||
|
|
|
@ -29,9 +29,8 @@ static uint8_t ist8310_write_reg_data_error[IST8310_WRITE_REG_NUM][3] = {
|
|||
*/
|
||||
static void IST8310Decode(IICInstance *iic)
|
||||
{
|
||||
static int16_t temp[3]; // 用于存储解码后的数据
|
||||
static IST8310Instance *ist; // 用于存储IST8310实例的指针
|
||||
ist = (IST8310Instance *)(iic->id); // iic的id保存了IST8310实例的指针(父指针)
|
||||
int16_t temp[3]; // 用于存储解码后的数据
|
||||
IST8310Instance *ist= (IST8310Instance *)(iic->id); // iic的id保存了IST8310实例的指针(父指针)
|
||||
|
||||
memcpy(temp, ist->iic_buffer, 6 * sizeof(uint8_t)); // 不要强制转换,直接cpy
|
||||
for (uint8_t i = 0; i < 3; i++)
|
||||
|
|
|
@ -10,7 +10,7 @@ LEDInstance *LEDRegister(LED_Init_Config_s *led_config)
|
|||
{
|
||||
LEDInstance *led_ins = (LEDInstance *)zero_malloc(sizeof(LEDInstance));
|
||||
// 剩下的值暂时都被置零
|
||||
led_ins->led_pwm = GPIORegister(&led_config->pwm_config);
|
||||
led_ins->led_pwm = PWMRegister(&led_config->pwm_config);
|
||||
led_ins->led_switch = led_config->init_swtich;
|
||||
|
||||
bsp_led_ins[idx++] = led_ins;
|
||||
|
|
|
@ -29,12 +29,10 @@ static DaemonInstance *vision_daemon_instance;
|
|||
*/
|
||||
static void DecodeVision()
|
||||
{
|
||||
static uint16_t flag_register;
|
||||
uint16_t flag_register;
|
||||
DaemonReload(vision_daemon_instance); // 喂狗
|
||||
get_protocol_info(vision_usart_instance->recv_buff, &flag_register, (uint8_t *)&recv_data.pitch);
|
||||
// TODO: code to resolve flag_register;
|
||||
PrintLog("decode vision");
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -80,9 +78,9 @@ Vision_Recv_s *VisionInit(UART_HandleTypeDef *_handle)
|
|||
*/
|
||||
void VisionSend(Vision_Send_s *send)
|
||||
{
|
||||
static uint16_t flag_register;
|
||||
static uint8_t send_buff[VISION_SEND_SIZE];
|
||||
static uint16_t tx_len;
|
||||
uint16_t flag_register;
|
||||
uint8_t send_buff[VISION_SEND_SIZE];
|
||||
uint16_t tx_len;
|
||||
// TODO: code to set flag_register
|
||||
flag_register = 30<<8|0b00000001;
|
||||
// 将数据转化为seasky协议的数据包
|
||||
|
|
|
@ -72,7 +72,8 @@ static void MotorSenderGrouping(DJIMotorInstance *motor, CAN_Init_Config_s *conf
|
|||
if (dji_motor_instance[i]->motor_can_instance->can_handle == config->can_handle && dji_motor_instance[i]->motor_can_instance->rx_id == config->rx_id)
|
||||
{
|
||||
LOGERROR("[dji_motor] ID crash. Check in debug mode, add dji_motor_instance to watch to get more information."); // 后续可以把id和CAN打印出来
|
||||
while (1); // 6020的id 1-4和2006/3508的id 5-8会发生冲突(若有注册,即1!5,2!6,3!7,4!8) (1!5!,LTC! (((不是)
|
||||
while (1)
|
||||
; // 6020的id 1-4和2006/3508的id 5-8会发生冲突(若有注册,即1!5,2!6,3!7,4!8) (1!5!,LTC! (((不是)
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
@ -99,7 +100,8 @@ static void MotorSenderGrouping(DJIMotorInstance *motor, CAN_Init_Config_s *conf
|
|||
if (dji_motor_instance[i]->motor_can_instance->can_handle == config->can_handle && dji_motor_instance[i]->motor_can_instance->rx_id == config->rx_id)
|
||||
{
|
||||
LOGERROR("[dji_motor] ID crash. Check in debug mode, add dji_motor_instance to watch to get more information.");
|
||||
while (1); // 6020的id 1-4和2006/3508的id 5-8会发生冲突(若有注册,即1!5,2!6,3!7,4!8)
|
||||
while (1)
|
||||
; // 6020的id 1-4和2006/3508的id 5-8会发生冲突(若有注册,即1!5,2!6,3!7,4!8)
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
@ -118,13 +120,10 @@ static void MotorSenderGrouping(DJIMotorInstance *motor, CAN_Init_Config_s *conf
|
|||
*/
|
||||
static void DecodeDJIMotor(CANInstance *_instance)
|
||||
{
|
||||
// 由于需要多次变址访存,直接将buff和measure地址保存在寄存器里避免多次存取
|
||||
static uint8_t *rxbuff;
|
||||
static DJI_Motor_Measure_s *measure;
|
||||
rxbuff = _instance->rx_buff;
|
||||
// 这里对can instance的id进行了强制转换,从而获得电机的instance实例地址
|
||||
// _instance指针指向的id是对应电机instance的地址,通过强制转换为电机instance的指针,再通过->运算符访问电机的成员motor_measure,最后取地址获得指针
|
||||
measure = &(((DJIMotorInstance *)_instance->id)->motor_measure); // measure要多次使用,保存指针减小访存开销
|
||||
uint8_t *rxbuff = _instance->rx_buff;
|
||||
DJI_Motor_Measure_s *measure = &(((DJIMotorInstance *)_instance->id)->motor_measure); // measure要多次使用,保存指针减小访存开销
|
||||
|
||||
// 解析数据并对电流和速度进行滤波,电机的反馈报文具体格式见电机说明手册
|
||||
measure->last_ecd = measure->ecd;
|
||||
|
@ -188,7 +187,7 @@ void DJIMotorChangeFeed(DJIMotorInstance *motor, Closeloop_Type_e loop, Feedback
|
|||
}
|
||||
else
|
||||
{
|
||||
LOGERROR("[dji_motor] loop type error, check memory access and func param");// 检查是否传入了正确的LOOP类型,或发生了指针越界
|
||||
LOGERROR("[dji_motor] loop type error, check memory access and func param"); // 检查是否传入了正确的LOOP类型,或发生了指针越界
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -217,15 +216,14 @@ void DJIMotorSetRef(DJIMotorInstance *motor, float ref)
|
|||
// 为所有电机实例计算三环PID,发送控制报文
|
||||
void DJIMotorControl()
|
||||
{
|
||||
// 预先通过静态变量定义避免反复释放分配栈空间,直接保存一次指针引用从而减小访存的开销
|
||||
// 同样可以提高可读性
|
||||
static uint8_t group, num; // 电机组号和组内编号
|
||||
static int16_t set; // 电机控制CAN发送设定值
|
||||
static DJIMotorInstance *motor;
|
||||
static Motor_Control_Setting_s *motor_setting; // 电机控制参数
|
||||
static Motor_Controller_s *motor_controller; // 电机控制器
|
||||
static DJI_Motor_Measure_s *motor_measure; // 电机测量值
|
||||
static float pid_measure, pid_ref; // 电机PID测量值和设定值
|
||||
// 直接保存一次指针引用从而减小访存的开销,同样可以提高可读性
|
||||
uint8_t group, num; // 电机组号和组内编号
|
||||
int16_t set; // 电机控制CAN发送设定值
|
||||
DJIMotorInstance *motor;
|
||||
Motor_Control_Setting_s *motor_setting; // 电机控制参数
|
||||
Motor_Controller_s *motor_controller; // 电机控制器
|
||||
DJI_Motor_Measure_s *motor_measure; // 电机测量值
|
||||
float pid_measure, pid_ref; // 电机PID测量值和设定值
|
||||
|
||||
// 遍历所有电机实例,进行串级PID的计算并设置发送报文的值
|
||||
for (size_t i = 0; i < idx; ++i)
|
||||
|
|
|
@ -40,12 +40,9 @@ static float uint_to_float(int x_int, float x_min, float x_max, int bits)
|
|||
*/
|
||||
static void HTMotorDecode(CANInstance *motor_can)
|
||||
{
|
||||
static uint16_t tmp; // 用于暂存解析值,稍后转换成float数据,避免多次创建临时变量
|
||||
static HTMotor_Measure_t *measure;
|
||||
static uint8_t *rxbuff;
|
||||
|
||||
rxbuff = motor_can->rx_buff;
|
||||
measure = &((HTMotorInstance *)motor_can->id)->motor_measure; // 将can实例中保存的id转换成电机实例的指针
|
||||
uint16_t tmp; // 用于暂存解析值,稍后转换成float数据,避免多次创建临时变量
|
||||
uint8_t *rxbuff = motor_can->rx_buff;
|
||||
HTMotor_Measure_t *measure = &((HTMotorInstance *)motor_can->id)->motor_measure; // 将can实例中保存的id转换成电机实例的指针
|
||||
|
||||
measure->last_angle = measure->total_angle;
|
||||
|
||||
|
@ -89,12 +86,12 @@ void HTMotorSetRef(HTMotorInstance *motor, float ref)
|
|||
|
||||
void HTMotorControl()
|
||||
{
|
||||
static float set, pid_measure, pid_ref;
|
||||
static uint16_t tmp;
|
||||
static HTMotorInstance *motor;
|
||||
static HTMotor_Measure_t *measure;
|
||||
static Motor_Control_Setting_s *setting;
|
||||
static CANInstance *motor_can;
|
||||
float set, pid_measure, pid_ref;
|
||||
uint16_t tmp;
|
||||
HTMotorInstance *motor;
|
||||
HTMotor_Measure_t *measure;
|
||||
Motor_Control_Setting_s *setting;
|
||||
CANInstance *motor_can;
|
||||
|
||||
// 遍历所有电机实例,计算PID
|
||||
for (size_t i = 0; i < idx; i++)
|
||||
|
|
|
@ -13,8 +13,8 @@ static CANInstance *sender_instance; // 多电机发送时使用的caninstance(
|
|||
*/
|
||||
static void LKMotorDecode(CANInstance *_instance)
|
||||
{
|
||||
static LKMotor_Measure_t *measure;
|
||||
static uint8_t *rx_buff;
|
||||
LKMotor_Measure_t *measure;
|
||||
uint8_t *rx_buff;
|
||||
rx_buff = _instance->rx_buff;
|
||||
measure = &(((LKMotorInstance *)_instance->id)->measure); // 通过caninstance保存的id获取对应的motorinstance
|
||||
|
||||
|
@ -72,11 +72,11 @@ LKMotorInstance *LKMotorInit(Motor_Init_Config_s *config)
|
|||
/* 第一个电机的can instance用于发送数据,向其tx_buff填充数据 */
|
||||
void LKMotorControl()
|
||||
{
|
||||
static float pid_measure, pid_ref;
|
||||
static int16_t set;
|
||||
static LKMotorInstance *motor;
|
||||
static LKMotor_Measure_t *measure;
|
||||
static Motor_Control_Setting_s *setting;
|
||||
float pid_measure, pid_ref;
|
||||
int16_t set;
|
||||
LKMotorInstance *motor;
|
||||
LKMotor_Measure_t *measure;
|
||||
Motor_Control_Setting_s *setting;
|
||||
|
||||
for (size_t i = 0; i < idx; ++i)
|
||||
{
|
||||
|
|
|
@ -55,6 +55,7 @@ typedef enum
|
|||
MOTOR_DIRECTION_NORMAL = 0,
|
||||
MOTOR_DIRECTION_REVERSE = 1
|
||||
} Motor_Reverse_Flag_e;
|
||||
|
||||
/* 反馈量正反标志 */
|
||||
typedef enum
|
||||
{
|
||||
|
|
|
@ -82,7 +82,7 @@ void Servo_Motor_Type_Select(ServoInstance *Servo_Motor, int16_t mode)
|
|||
*/
|
||||
void ServeoMotorControl()
|
||||
{
|
||||
static ServoInstance *Servo_Motor;
|
||||
ServoInstance *Servo_Motor;
|
||||
|
||||
for (size_t i = 0; i < servo_idx; i++)
|
||||
{
|
||||
|
|
|
@ -112,12 +112,13 @@ static void RemoteControlRxCallback()
|
|||
}
|
||||
|
||||
/**
|
||||
* @brief
|
||||
* @brief 遥控器离线的回调函数,注册到守护进程中,串口掉线时调用
|
||||
*
|
||||
*/
|
||||
static void RCLostCallback()
|
||||
static void RCLostCallback(void *id)
|
||||
{
|
||||
// @todo 遥控器丢失的处理
|
||||
USARTServiceInit(rc_usart_instance); // 尝试重新启动接收
|
||||
}
|
||||
|
||||
RC_ctrl_t *RemoteControlInit(UART_HandleTypeDef *rc_usart_handle)
|
||||
|
@ -131,9 +132,9 @@ RC_ctrl_t *RemoteControlInit(UART_HandleTypeDef *rc_usart_handle)
|
|||
// 进行守护进程的注册,用于定时检查遥控器是否正常工作
|
||||
// @todo 当前守护进程直接在这里注册,后续考虑将其封装到遥控器的初始化函数中,即可以让用户决定reload_count的值(是否有必要?)
|
||||
Daemon_Init_Config_s daemon_conf = {
|
||||
.reload_count = 100, // 100ms,遥控器的接收频率实际上是1000/14Hz(大约70)
|
||||
.callback = NULL, // 后续考虑重新启动遥控器对应串口的传输
|
||||
.owner_id = NULL, // 只有1个遥控器,不需要owner_id
|
||||
.reload_count = 10, // 100ms未收到数据视为离线,遥控器的接收频率实际上是1000/14Hz(大约70Hz)
|
||||
.callback = RCLostCallback,
|
||||
.owner_id = NULL, // 只有1个遥控器,不需要owner_id
|
||||
};
|
||||
rc_daemon_instance = DaemonRegister(&daemon_conf);
|
||||
|
||||
|
|
|
@ -13,8 +13,8 @@ static SuperCapInstance *super_cap_instance = NULL; // 可以由app保存此指
|
|||
|
||||
static void SuperCapRxCallback(CANInstance *_instance)
|
||||
{
|
||||
static uint8_t *rxbuff;
|
||||
static SuperCap_Msg_s *Msg;
|
||||
uint8_t *rxbuff;
|
||||
SuperCap_Msg_s *Msg;
|
||||
rxbuff = _instance->rx_buff;
|
||||
Msg = &super_cap_instance->cap_msg;
|
||||
Msg->vol = (uint16_t)(rxbuff[0] << 8 | rxbuff[1]);
|
||||
|
|
14
如何定位bug.md
14
如何定位bug.md
|
@ -87,7 +87,7 @@ long long的范围比float小。无符号和有符号数直接转换可能变成
|
|||
|
||||
|
||||
|
||||
## 典型debug案例
|
||||
## 典型debug案例一
|
||||
|
||||
这是一个结合了软件和硬件且有多模块耦合的异常。该bug发生在调试平衡步兵的底盘过程当中。
|
||||
|
||||
|
@ -159,3 +159,15 @@ void MotorControlTask()
|
|||
|
||||
均衡总线负载,调节任务运行时间。
|
||||
|
||||
|
||||
|
||||
# 典型debug案例二
|
||||
|
||||
这仍然是一个CAN总线引发的bug。使用的电机均为DJI电机。当多个电机接入时,会产生反馈值跳变的情况。起初认为**总线负载过高**,(控制频率为500Hz,反馈频率均为1kHz,计算之后得出CAN的负载率接近90%),但将电机减少为一半甚至更少时仍然出现此问题。**单独使用CAN1且仅挂载一个电机则问题消失**,同时使用CAN1和CAN2(不论单个总线挂载几个电机)则问题再次出现。
|
||||
|
||||
**单步调试发现反馈值并未因指针越界而被纂改**。仔细检查代码的计算发现并未出错,打开Ozone查看反馈值曲线,发现确实偶发跳变,但跳变值并未超出反馈值范围,即即使发生跳变值仍然在**正常范围内**,因此不像是总线负载过大导致数据帧错误或指针越界修改的随机值。加入多个电机同时查看反馈值,**发现反馈跳变之后会和另一电机的反馈值相同**,呈现“你跳到我我跳到你”的图景。怀疑CAN中断被**重入**,即一个中断未完成时另一个CAN报文到来,打断了当前的中断并执行了**相同的反馈解码函数**。但CAN1和CAN2的中断优先级均为5,因此不可能打断彼此。打开CubeMX查看初始化配置,发现两个CAN的FIFO0和FIFO1中断优先级不同,分别是5和6。则FIFO1的溢出中断会被FIFO0打断,且我们在电机的解码函数中使用了一些**静态变量**用于存储触发接收中断的电机报文的相关信息,故而新进入的中断覆写了之前中断的静态变量值,使得之前中断在恢复之后存储了前者的值,导致自身反馈错误。
|
||||
|
||||
将优先级统一设为5,编译之后重新运行,反馈值正常。
|
||||
|
||||
> “同时使用CAN1和CAN2(不论几个电机)则问题再次出现。” 导致此问题的原因是初始化CAN时按照rxid分配FIFO,因此注册的电机会被交替分配到不同的FIFO,故不论注册了几个电机(只要多于2)、注册到哪条总线都会出现FIFO1中断被FIFO0打断的情况。
|
||||
|
||||
|
|
Loading…
Reference in New Issue