我是靠谱客的博主 贪玩台灯,最近开发中收集的这篇文章主要介绍STM32+Cube MX使用MPU6050 DMP时,在外部中断中调用read_dmp函数发生系统卡死问题的根本原因分析,觉得挺不错的,现在分享给大家,希望可以做个参考。

概述

系统环境

硬件:

    MCU:STM32F405RGT6

    IMU:MPU6050

软件:

    开发环境:KEIL MDK-ARM uVision5

    MPU6050使用DMP

复现步骤

程序中MPU6050 DMP的采样率设置为100Hz,使用中断引脚接到STM32单片机的GPIO引脚,此引脚通过Cube MX配置为外部中断,下降沿触发中断。

在外部中断中调用dmp中的一个函数read_dmp,在mpu6050_dmp.c中,源码如下:

/**
  * @brief  read_dmp()      读取MPU内置DMP的姿态.
  * @param  *pose_msg       传入姿态的地址
	* @note                 参考野火、原子、平衡之家等开源资料
  * @retval HAL status      0/1/2
  */
uint8_t read_dmp(pose_msg_t *pose_msg)
{
	uint8_t more;
	long quat[4]; //四元数
	int16_t gyro[3], accel[3], sensors;
	unsigned long sensor_timestamp; //传感器时间戳
	float q0=1.0f, q1=0.0f, q2=0.0f, q3=0.0f;

	//读取FIFO中的数据
	if(dmp_read_fifo(gyro, accel, quat, &sensor_timestamp, &sensors, &more))
	{
		//printf("dmp_read_fifo errorn"); //phph
		return 1;
	}
	if(sensors & INV_WXYZ_QUAT) //#define INV_WXYZ_QUAT       (0x100)
	{
		q0 = quat[0] / q30;
		q1 = quat[1] / q30;
		q2 = quat[2] / q30;
		q3 = quat[3] / q30;

		pose_msg->pitch = asin(-2 * q1 * q3 + 2 * q0* q2)* 57.3f; //四元数解算, 俯仰角(Pitch)-->绕着X轴旋转
		pose_msg->roll = atan2(2 * q2 * q3 + 2 * q0 * q1, -2 * q1 * q1 - 2 * q2* q2 + 1)* 57.3f; //四元数解算, 翻滚角(Roll)-->绕着Y轴旋转
		pose_msg->yaw = atan2(2*(q1*q2 + q0*q3), q0*q0+q1*q1-q2*q2-q3*q3) * 57.3f; //四元数解算, 偏航角(Yaw)-->绕着Z轴旋转

		return 0;
	}
	else
		return 2;
}

外部中断处理函数中源码如下:

void HAL_GPIO_EXTI_Callback(uint16_t GPIO_Pin)
{
	if(dmp_init_finished == 1)
	{
		read_dmp(&mpu_pose_msg); //读取mpu姿态
	}
}

问题现象

当按照上述步骤执行后,在main.c的主循环中加入printf语句打印调试,定时(500毫秒)打印“123n”,发现程序运行起来后,电脑的串口调试助手中并没有看到"123"这个输出。

问题分析

首先排除串口问题,因为main函数中dmp初始化代码之前的打印语句是能够输出到串口调试助手中的。

既然经过dmp初始化代码之后就出现了问题,那么一定是跟dmp代码相关。怀疑read_dmp()执行时间过长,导致中断时间耗尽,但是函数还没有执行完。

但其实很多平衡车或者智能小车方案中的例程代码都是在外部中断中调用的read_dmp函数,人家还调用了很多其它函数。为什么人家的都没有问题,而我们的即使只调用了一个read_dmp函数就已经没有输出、系统卡死了?

进一步调查,实测一下read_dmp()所需要的时间,通过在函数前后各加入HAL_GetTick()获取时间差值,发现这个函数只耗时1毫秒,应该不会有影响,至少不会有很大影响。

为了更进一步验证耗时的情况,在外部中断中延时1毫秒,看看问题会不会出现。将外部中断处理函数改造如下:

void HAL_GPIO_EXTI_Callback(uint16_t GPIO_Pin)
{
	if(dmp_init_finished == 1)
	{
		//read_dmp(&mpu_pose_msg); //读取mpu姿态
		HAL_Delay(1);
	}
}

这样就实现了在外部中断中纯延时1ms,其它什么都不做,进行测试。结果仍然出现了卡死的问题。进一步地,将HAL_Delay(1)改为HAL_Delay(0)再次测试,现象仍然是一样的。这就很奇怪了,都没有延时了,为什么还会出现卡死的问题?

为了探明这个问题,查看HAL_Delay函数的源码,在stm32f4xx_hal.c中,源码如下:

__weak void HAL_Delay(uint32_t Delay)
{
  uint32_t tickstart = HAL_GetTick();
  uint32_t wait = Delay;

  /* Add a freq to guarantee minimum wait */
  if (wait < HAL_MAX_DELAY)
  {
    wait += (uint32_t)(uwTickFreq);
  }

  while((HAL_GetTick() - tickstart) < wait)
  {
  }
}

将这个函数分批次注释掉各部分,先保留最上边两句

uint32_t tickstart = HAL_GetTick();
uint32_t wait = Delay;

发现没有问题。

进一步往下解封代码,把

if (wait < HAL_MAX_DELAY)
{
    wait += (uint32_t)(uwTickFreq);
}

也解封,发现也没有问题。

最终将最后一段代码解封,出现了问题。

为什么最后一段代码

while((HAL_GetTick() - tickstart) < wait)
{
}

一加入就出现了问题?

根据上边的代码可以知道,当上层调用Hal_Delay(0)时,传入的参数值Delay为0,也就是wait被赋值为了0,经过if语句后,wait被加入了一个uwTickFreq,这个值在stm32f4xx_hal.c中定义:

HAL_TickFreqTypeDef uwTickFreq = HAL_TICK_FREQ_DEFAULT;  /* 1KHz */

HAL_TICK_FREQ_DEFAULT是一个枚举值,在stm32f4xx_hal.h中定义:

/** @defgroup HAL_TICK_FREQ Tick Frequency
  * @{
  */
typedef enum
{
  HAL_TICK_FREQ_10HZ         = 100U,
  HAL_TICK_FREQ_100HZ        = 10U,
  HAL_TICK_FREQ_1KHZ         = 1U,
  HAL_TICK_FREQ_DEFAULT      = HAL_TICK_FREQ_1KHZ
} HAL_TickFreqTypeDef;

可以看到HAL_TICK_FREQ_DEFAULT的值实际为1。也就是说wait的值加上了1,之前是0,现在变为了1。之后就进入了while循环。

猜测是不是while循环引发的问题,将wait在循环之前直接赋值为0,进行测试。这一次没有出现问题,也就是说确实是由于while循环引发的问题。进一步思考为什么

while((HAL_GetTick() - tickstart) < wait)
{
}

会引发问题。

当wait为0的时候,实际上直接跳出了循环,并没有陷入while循环,而当wait大于0的时候,则会会陷入循环,直到间隔时间大于wait值为止。

由此猜测原因可能是这样的:外部中断的回调函数仍然处在中断上下文,当它在死循环运行的时候,HAL_GetTick()得到的SysTick的值并没有发生变化。

HAL_GetTick()是在stm32f4xx_hal.c中实现的,源码如下:

__weak void HAL_IncTick(void)
{
  uwTick += uwTickFreq;
}

__weak uint32_t HAL_GetTick(void)
{
  return uwTick;
}

HAL_GetTick()只是返回了uwTick的值,而uwTick的值是在HAL_IncTick()中改变的,每次增加uwTickFreq。

正常是会进入到SysTick相关的中断的,每次将uwTick的值增加,这样通过HAL_GetTick()得到的值就会相应改变。而如果外部中断中一直陷入在while循环中,那么SysTick这个中断进不去,导致HAL_IncTick函数没有被执行,uwTick没有变化,这样外部中断中始终在while循环中出不来(有点类似于操作系统中死锁的意思)。

为了印证这个猜测,看一下中断的级别,发现通过Cube MX设置的各个优先级都是0,0,都是一个级别。将外部中断的级别调低,调为1,0(HAL_NVIC_SetPriority(EXTI3_IRQn, 0, 0);改为HAL_NVIC_SetPriority(EXTI3_IRQn, 1, 0);),再次进行测试,这次无论调用HAL_Delay(0)还是HAL_Delay(1)都没有问题了。在此基础上,解封之前调用的read_dmp函数,也没有问题了。可以说实际上已经找到问题的根本原因了。

但是还有一个问题,之前在进行问题排查的实验时,发现将MPU6050 DMP的采样频率设置为20Hz,即50ms进入一次中断,这样即使在中断中加入了read_dmp函数,也可以正常执行,不会产生上边的问题,这又是为什么?

通过查看read_dmp函数的源码(见上边),其中调用了

dmp_read_fifo(gyro, accel, quat, &sensor_timestamp, &sensors, &more)

这个函数在inv_mpu_dmp_motion_driver.c中实现,源码如下:

int dmp_read_fifo(short *gyro, short *accel, long *quat,
	unsigned long *timestamp, short *sensors, unsigned char *more)
{
	unsigned char fifo_data[MAX_PACKET_LENGTH];
	unsigned char ii = 0;

	/* TODO: sensors[0] only changes when dmp_enable_feature is called. We can
	 * cache this value and save some cycles.
	 */
	sensors[0] = 0;

	/* Get a packet. */
	if (mpu_read_fifo_stream(dmp.packet_length, fifo_data, more))
	{
		//printf("mpu_read_fifo_stream errn"); //phph
		return -1;
	}

	/* Parse DMP packet. */
	if (dmp.feature_mask & (DMP_FEATURE_LP_QUAT | DMP_FEATURE_6X_LP_QUAT)) {
#ifdef FIFO_CORRUPTION_CHECK
		long quat_q14[4], quat_mag_sq;
#endif
		quat[0] = ((long)fifo_data[0] << 24) | ((long)fifo_data[1] << 16) |
			((long)fifo_data[2] << 8) | fifo_data[3];
		quat[1] = ((long)fifo_data[4] << 24) | ((long)fifo_data[5] << 16) |
			((long)fifo_data[6] << 8) | fifo_data[7];
		quat[2] = ((long)fifo_data[8] << 24) | ((long)fifo_data[9] << 16) |
			((long)fifo_data[10] << 8) | fifo_data[11];
		quat[3] = ((long)fifo_data[12] << 24) | ((long)fifo_data[13] << 16) |
			((long)fifo_data[14] << 8) | fifo_data[15];
		ii += 16;
#ifdef FIFO_CORRUPTION_CHECK
		/* We can detect a corrupted FIFO by monitoring the quaternion data and
		 * ensuring that the magnitude is always normalized to one. This
		 * shouldn't happen in normal operation, but if an I2C error occurs,
		 * the FIFO reads might become misaligned.
		 *
		 * Let's start by scaling down the quaternion data to avoid long long
		 * math.
		 */
		quat_q14[0] = quat[0] >> 16;
		quat_q14[1] = quat[1] >> 16;
		quat_q14[2] = quat[2] >> 16;
		quat_q14[3] = quat[3] >> 16;
		quat_mag_sq = quat_q14[0] * quat_q14[0] + quat_q14[1] * quat_q14[1] +
			quat_q14[2] * quat_q14[2] + quat_q14[3] * quat_q14[3];
		if ((quat_mag_sq < QUAT_MAG_SQ_MIN) ||
			(quat_mag_sq > QUAT_MAG_SQ_MAX)) {
			/* Quaternion is outside of the acceptable threshold. */
			mpu_reset_fifo();
			sensors[0] = 0;
			return -1;
		}
		sensors[0] |= INV_WXYZ_QUAT;
#endif
	}

	if (dmp.feature_mask & DMP_FEATURE_SEND_RAW_ACCEL) {
		accel[0] = ((short)fifo_data[ii+0] << 8) | fifo_data[ii+1];
		accel[1] = ((short)fifo_data[ii+2] << 8) | fifo_data[ii+3];
		accel[2] = ((short)fifo_data[ii+4] << 8) | fifo_data[ii+5];
		ii += 6;
		sensors[0] |= INV_XYZ_ACCEL;
	}

	if (dmp.feature_mask & DMP_FEATURE_SEND_ANY_GYRO) {
		gyro[0] = ((short)fifo_data[ii+0] << 8) | fifo_data[ii+1];
		gyro[1] = ((short)fifo_data[ii+2] << 8) | fifo_data[ii+3];
		gyro[2] = ((short)fifo_data[ii+4] << 8) | fifo_data[ii+5];
		ii += 6;
		sensors[0] |= INV_XYZ_GYRO;
	}

	/* Gesture data is at the end of the DMP packet. Parse it and call
	 * the gesture callbacks (if registered).
	 */
	if (dmp.feature_mask & (DMP_FEATURE_TAP | DMP_FEATURE_ANDROID_ORIENT)) //#define DMP_FEATURE_TAP             (0x001), #define DMP_FEATURE_ANDROID_ORIENT  (0x002)
		decode_gesture(fifo_data + ii);

	get_ms(timestamp);

	return 0;
}

这个函数进一步调用了mpu_read_fifo_stream函数,在inv_mpu.c中,源码如下:

int mpu_read_fifo_stream(unsigned short length, unsigned char *data,
	unsigned char *more)
{
	unsigned char tmp[2];
	unsigned short fifo_count;

	if (!st.chip_cfg.dmp_on)
		return -1;
	if (!st.chip_cfg.sensors)
		return -1;

	if (i2c_read(st.hw->addr, st.reg->fifo_count_h, 2, tmp)) //.fifo_count_h   = 0x72,
		return -1;

	fifo_count = (tmp[0] << 8) | tmp[1];
	if (fifo_count < length) {
		more[0] = 0;
		return -1;
	}

	if (fifo_count > (st.hw->max_fifo >> 1)) {
		/* FIFO is 50% full, better check overflow bit. */
		if (i2c_read(st.hw->addr, st.reg->int_status, 1, tmp)) //.int_status     = 0x3A,
			return -1;
		if (tmp[0] & BIT_FIFO_OVERFLOW) { //#define BIT_FIFO_OVERFLOW   (0x10)
			//printf("daozhelile5?n"); //phph
			mpu_reset_fifo();
			return -2;
		}
		//printf("daozhelile6?n"); //phph
	}

	if (i2c_read(st.hw->addr, st.reg->fifo_r_w, length, data))
		return -1;
	more[0] = fifo_count / length - 1;

	return 0;
}

dmp_read_fifo及mpu_read_fifo_stream函数中都调用了mpu_reset_fifo(),实现在inv_mpu.c中:

int mpu_reset_fifo(void)
{
	unsigned char data;

	if (!(st.chip_cfg.sensors))
		return -1;

	data = 0;
	if (i2c_write(st.hw->addr, st.reg->int_enable, 1, &data)) //.int_enable     = 0x38,
		return -1;
	if (i2c_write(st.hw->addr, st.reg->fifo_en, 1, &data)) //.fifo_en        = 0x23,
		return -1;
	if (i2c_write(st.hw->addr, st.reg->user_ctrl, 1, &data)) //.user_ctrl      = 0x6A,
		return -1;

	if (st.chip_cfg.dmp_on) {
		data = BIT_FIFO_RST | BIT_DMP_RST; //#define BIT_FIFO_RST        (0x04), #define BIT_DMP_RST         (0x08)
		if (i2c_write(st.hw->addr, st.reg->user_ctrl, 1, &data)) //.user_ctrl      = 0x6A,
			return -1;
		delay_ms(50);

		data = BIT_DMP_EN | BIT_FIFO_EN; //#define BIT_DMP_EN          (0x80), #define BIT_FIFO_EN         (0x40)
		if (st.chip_cfg.sensors & INV_XYZ_COMPASS) //#define INV_XYZ_COMPASS (0x01)
			data |= BIT_AUX_IF_EN; //#define BIT_AUX_IF_EN       (0x20)
		if (i2c_write(st.hw->addr, st.reg->user_ctrl, 1, &data)) //.user_ctrl      = 0x6A,
			return -1;

		if (st.chip_cfg.int_enable)
			data = BIT_DMP_INT_EN; //#define BIT_DMP_INT_EN      (0x02)
		else
			data = 0;
		if (i2c_write(st.hw->addr, st.reg->int_enable, 1, &data)) //.int_enable     = 0x38,
			return -1;

		data = 0;
		if (i2c_write(st.hw->addr, st.reg->fifo_en, 1, &data)) //.fifo_en        = 0x23,
			return -1;
	} else {
		data = BIT_FIFO_RST; //#define BIT_FIFO_RST        (0x04)
		if (i2c_write(st.hw->addr, st.reg->user_ctrl, 1, &data)) //.user_ctrl      = 0x6A,
			return -1;

		if (st.chip_cfg.bypass_mode || !(st.chip_cfg.sensors & INV_XYZ_COMPASS)) //#define INV_XYZ_COMPASS (0x01)
			data = BIT_FIFO_EN; //#define BIT_FIFO_EN         (0x40)
		else
			data = BIT_FIFO_EN | BIT_AUX_IF_EN; //#define BIT_FIFO_EN         (0x40), #define BIT_AUX_IF_EN       (0x20)
		if (i2c_write(st.hw->addr, st.reg->user_ctrl, 1, &data)) //.user_ctrl      = 0x6A,
			return -1;
		delay_ms(50);

		if (st.chip_cfg.int_enable)
			data = BIT_DATA_RDY_EN; //#define BIT_DATA_RDY_EN     (0x01)
		else
			data = 0;
		if (i2c_write(st.hw->addr, st.reg->int_enable, 1, &data)) //.int_enable     = 0x38,
			return -1;

		if (i2c_write(st.hw->addr, st.reg->fifo_en, 1, &st.chip_cfg.fifo_enable)) //.fifo_en        = 0x23,
			return -1;
	}

	return 0;
}

可以看到,mpu_reset_fifo函数中调用了delay_ms函数,这样就导致了如上边所分析的问题。

如果采样率设置得比较低,mpu_read_fifo_stream函数中检测MPU6050 FIFO的时候达不到溢出的情况,就不会调用mpu_reset_fifo函数,也就不会调用delay_ms函数,则不会产生问题;如果采样率设置的比较高,则有可能导致MPU6050 FIFO溢出,从而调用mpu_reset_fifo函数,进一步调用delay_ms函数,从而引发问题。

总结

Cube MX虽然通过图形界面大幅简化了开发工作,但是仍然需要对于具体实现机制掌握得比较深入,不能完全依赖Cube MX。这样在出现问题时,才能够准确定位,而不是茫然不知所措。

最后

以上就是贪玩台灯为你收集整理的STM32+Cube MX使用MPU6050 DMP时,在外部中断中调用read_dmp函数发生系统卡死问题的根本原因分析的全部内容,希望文章能够帮你解决STM32+Cube MX使用MPU6050 DMP时,在外部中断中调用read_dmp函数发生系统卡死问题的根本原因分析所遇到的程序开发问题。

如果觉得靠谱客网站的内容还不错,欢迎将靠谱客网站推荐给程序员好友。

本图文内容来源于网友提供,作为学习参考使用,或来自网络收集整理,版权属于原作者所有。
点赞(39)

评论列表共有 0 条评论

立即
投稿
返回
顶部