> 技术文档 > 【STM32-HAL库】MPU6050姿态传感器

【STM32-HAL库】MPU6050姿态传感器


新建工程,并设置基本配置,可以参考以下文章:http://t.csdnimg.cn/p1oLj

MPU6050介绍

MPU6050是一款六轴运动传感器模块,广泛应用于各种领域,如机器人、无人机、智能家居等,用于测量物体的加速度和角速度。以下是对MPU6050姿态传感器的由浅入深的讲解:

  1. 基本原理

    • MPU6050由三轴加速度计和三轴陀螺仪组成,可以测量物体在X、Y、Z三个方向上的加速度和角速度。
  2. 工作方式

    • MPU6050通过I2C总线与微控制器连接,测量加速度和角速度数据,并将处理后的数据发送给外部设备进行进一步处理。
  3. 应用领域

    • 在机器人领域,可以用于测量机器人的姿态和运动状态。

    • 在无人机领域,可以测量无人机的姿态和角速度,实现稳定飞行。

    • 在智能家居领域,可用于测量家居设备的姿态和运动状态,实现智能化控制。

  4. 技术细节

    • 六轴传感器:包含三轴加速度计和三轴陀螺仪,可以通过内置的DMP实现姿态解算。

    • 数据处理:通过InvenSense提供的运动处理资料库,可以简化姿态解算过程。

    • 传感器精度:具有高精度的传感器测量,可以实现微小加速度和角速度变化的检测。

  5. 优缺点

    • 优点:高精度、低功耗、成本低廉,适用于嵌入式系统和移动设备。

    • 缺点:无法直接测量物体的位置,测量结果受环境因素影响大,需要校准和数据处理来获得可靠结果。

一、新建工程

1、新建工程

 可以参考我的新建工程系列教程

stm32-HAL库+cubeMX新建工程教程系列https://blog.csdn.net/qq_39150957/article/details/143087351?fromshare=blogdetail&sharetype=blogdetail&sharerId=143087351&sharerefer=PC&sharesource=qq_39150957&sharefrom=from_link

2、开启IIC

开启IIC,并如图所示配置。

二、移植代码

2、新建mpu6050.c文件

新建一个文件,并按下键盘“ctrl+s”组合键保存该文件,保存路径为工程路径下的“Core/Src”。文件命名为“mpu6050.h”

之后粘贴该代码:

/* * mpu6050.c * * Created on: Nov 13, 2019 * Author: Bulanov Konstantin * * Contact information * ------------------- * * e-mail : leech001@gmail.com *//* * |--------------------------------------------------------------------------------- * | Copyright (C) Bulanov Konstantin,2021 * | * | This program is free software: you can redistribute it and/or modify * | it under the terms of the GNU General Public License as published by * | the Free Software Foundation, either version 3 of the License, or * | any later version. * | * | This program is distributed in the hope that it will be useful, * | but WITHOUT ANY WARRANTY; without even the implied warranty of * | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * | GNU General Public License for more details. * | * | You should have received a copy of the GNU General Public License * | along with this program. If not, see . * | * | Kalman filter algorithm used from https://github.com/TKJElectronics/KalmanFilter * |--------------------------------------------------------------------------------- */#include #include \"mpu6050.h\"#define RAD_TO_DEG 57.295779513082320876798154814105#define WHO_AM_I_REG 0x75#define PWR_MGMT_1_REG 0x6B#define SMPLRT_DIV_REG 0x19#define ACCEL_CONFIG_REG 0x1C#define ACCEL_XOUT_H_REG 0x3B#define TEMP_OUT_H_REG 0x41#define GYRO_CONFIG_REG 0x1B#define GYRO_XOUT_H_REG 0x43// Setup MPU6050#define MPU6050_ADDR 0xD0const uint16_t i2c_timeout = 100;const double Accel_Z_corrector = 14418.0;uint32_t timer;Kalman_t KalmanX = { .Q_angle = 0.001f, .Q_bias = 0.003f, .R_measure = 0.03f};Kalman_t KalmanY = { .Q_angle = 0.001f, .Q_bias = 0.003f, .R_measure = 0.03f,};uint8_t MPU6050_Init(I2C_HandleTypeDef *I2Cx){ uint8_t check; uint8_t Data; // check device ID WHO_AM_I HAL_I2C_Mem_Read(I2Cx, MPU6050_ADDR, WHO_AM_I_REG, 1, &check, 1, i2c_timeout); if (check == 104) // 0x68 will be returned by the sensor if everything goes well { // power management register 0X6B we should write all 0\'s to wake the sensor up Data = 0; HAL_I2C_Mem_Write(I2Cx, MPU6050_ADDR, PWR_MGMT_1_REG, 1, &Data, 1, i2c_timeout); // Set DATA RATE of 1KHz by writing SMPLRT_DIV register Data = 0x07; HAL_I2C_Mem_Write(I2Cx, MPU6050_ADDR, SMPLRT_DIV_REG, 1, &Data, 1, i2c_timeout); // Set accelerometer configuration in ACCEL_CONFIG Register // XA_ST=0,YA_ST=0,ZA_ST=0, FS_SEL=0 -> � 2g Data = 0x00; HAL_I2C_Mem_Write(I2Cx, MPU6050_ADDR, ACCEL_CONFIG_REG, 1, &Data, 1, i2c_timeout); // Set Gyroscopic configuration in GYRO_CONFIG Register // XG_ST=0,YG_ST=0,ZG_ST=0, FS_SEL=0 -> � 250 �/s Data = 0x00; HAL_I2C_Mem_Write(I2Cx, MPU6050_ADDR, GYRO_CONFIG_REG, 1, &Data, 1, i2c_timeout); return 0; } return 1;}void MPU6050_Read_Accel(I2C_HandleTypeDef *I2Cx, MPU6050_t *DataStruct){ uint8_t Rec_Data[6]; // Read 6 BYTES of data starting from ACCEL_XOUT_H register HAL_I2C_Mem_Read(I2Cx, MPU6050_ADDR, ACCEL_XOUT_H_REG, 1, Rec_Data, 6, i2c_timeout); DataStruct->Accel_X_RAW = (int16_t)(Rec_Data[0] <Accel_Y_RAW = (int16_t)(Rec_Data[2] <Accel_Z_RAW = (int16_t)(Rec_Data[4] <Ax = DataStruct->Accel_X_RAW / 16384.0; DataStruct->Ay = DataStruct->Accel_Y_RAW / 16384.0; DataStruct->Az = DataStruct->Accel_Z_RAW / Accel_Z_corrector;}void MPU6050_Read_Gyro(I2C_HandleTypeDef *I2Cx, MPU6050_t *DataStruct){ uint8_t Rec_Data[6]; // Read 6 BYTES of data starting from GYRO_XOUT_H register HAL_I2C_Mem_Read(I2Cx, MPU6050_ADDR, GYRO_XOUT_H_REG, 1, Rec_Data, 6, i2c_timeout); DataStruct->Gyro_X_RAW = (int16_t)(Rec_Data[0] <Gyro_Y_RAW = (int16_t)(Rec_Data[2] <Gyro_Z_RAW = (int16_t)(Rec_Data[4] <Gx = DataStruct->Gyro_X_RAW / 131.0; DataStruct->Gy = DataStruct->Gyro_Y_RAW / 131.0; DataStruct->Gz = DataStruct->Gyro_Z_RAW / 131.0;}void MPU6050_Read_Temp(I2C_HandleTypeDef *I2Cx, MPU6050_t *DataStruct){ uint8_t Rec_Data[2]; int16_t temp; // Read 2 BYTES of data starting from TEMP_OUT_H_REG register HAL_I2C_Mem_Read(I2Cx, MPU6050_ADDR, TEMP_OUT_H_REG, 1, Rec_Data, 2, i2c_timeout); temp = (int16_t)(Rec_Data[0] <Temperature = (float)((int16_t)temp / (float)340.0 + (float)36.53);}void MPU6050_Read_All(I2C_HandleTypeDef *I2Cx, MPU6050_t *DataStruct){ uint8_t Rec_Data[14]; int16_t temp; // Read 14 BYTES of data starting from ACCEL_XOUT_H register HAL_I2C_Mem_Read(I2Cx, MPU6050_ADDR, ACCEL_XOUT_H_REG, 1, Rec_Data, 14, i2c_timeout); DataStruct->Accel_X_RAW = (int16_t)(Rec_Data[0] <Accel_Y_RAW = (int16_t)(Rec_Data[2] <Accel_Z_RAW = (int16_t)(Rec_Data[4] << 8 | Rec_Data[5]); temp = (int16_t)(Rec_Data[6] <Gyro_X_RAW = (int16_t)(Rec_Data[8] <Gyro_Y_RAW = (int16_t)(Rec_Data[10] <Gyro_Z_RAW = (int16_t)(Rec_Data[12] <Ax = DataStruct->Accel_X_RAW / 16384.0; DataStruct->Ay = DataStruct->Accel_Y_RAW / 16384.0; DataStruct->Az = DataStruct->Accel_Z_RAW / Accel_Z_corrector; DataStruct->Temperature = (float)((int16_t)temp / (float)340.0 + (float)36.53); DataStruct->Gx = DataStruct->Gyro_X_RAW / 131.0; DataStruct->Gy = DataStruct->Gyro_Y_RAW / 131.0; DataStruct->Gz = DataStruct->Gyro_Z_RAW / 131.0; // Kalman angle solve double dt = (double)(HAL_GetTick() - timer) / 1000; timer = HAL_GetTick(); double roll; double roll_sqrt = sqrt( DataStruct->Accel_X_RAW * DataStruct->Accel_X_RAW + DataStruct->Accel_Z_RAW * DataStruct->Accel_Z_RAW); if (roll_sqrt != 0.0) { roll = atan(DataStruct->Accel_Y_RAW / roll_sqrt) * RAD_TO_DEG; } else { roll = 0.0; } double pitch = atan2(-DataStruct->Accel_X_RAW, DataStruct->Accel_Z_RAW) * RAD_TO_DEG; if ((pitch KalmanAngleY > 90) || (pitch > 90 && DataStruct->KalmanAngleY KalmanAngleY = pitch; } else { DataStruct->KalmanAngleY = Kalman_getAngle(&KalmanY, pitch, DataStruct->Gy, dt); } if (fabs(DataStruct->KalmanAngleY) > 90) DataStruct->Gx = -DataStruct->Gx; DataStruct->KalmanAngleX = Kalman_getAngle(&KalmanX, roll, DataStruct->Gx, dt);}double Kalman_getAngle(Kalman_t *Kalman, double newAngle, double newRate, double dt){ double rate = newRate - Kalman->bias; Kalman->angle += dt * rate; Kalman->P[0][0] += dt * (dt * Kalman->P[1][1] - Kalman->P[0][1] - Kalman->P[1][0] + Kalman->Q_angle); Kalman->P[0][1] -= dt * Kalman->P[1][1]; Kalman->P[1][0] -= dt * Kalman->P[1][1]; Kalman->P[1][1] += Kalman->Q_bias * dt; double S = Kalman->P[0][0] + Kalman->R_measure; double K[2]; K[0] = Kalman->P[0][0] / S; K[1] = Kalman->P[1][0] / S; double y = newAngle - Kalman->angle; Kalman->angle += K[0] * y; Kalman->bias += K[1] * y; double P00_temp = Kalman->P[0][0]; double P01_temp = Kalman->P[0][1]; Kalman->P[0][0] -= K[0] * P00_temp; Kalman->P[0][1] -= K[0] * P01_temp; Kalman->P[1][0] -= K[1] * P00_temp; Kalman->P[1][1] -= K[1] * P01_temp; return Kalman->angle;};

3、新建mpu6050.h文件

同样方法新建mpu6050.h文件,h文件保存路径在“Core/Inc”路径下。

在h文件中粘贴以下代码:

/* * mpu6050.h * * Created on: Nov 13, 2019 * Author: Bulanov Konstantin */#ifndef INC_GY521_H_#define INC_GY521_H_#endif /* INC_GY521_H_ */#include #include \"i2c.h\"// MPU6050 structuretypedef struct{ int16_t Accel_X_RAW; int16_t Accel_Y_RAW; int16_t Accel_Z_RAW; double Ax; double Ay; double Az; int16_t Gyro_X_RAW; int16_t Gyro_Y_RAW; int16_t Gyro_Z_RAW; double Gx; double Gy; double Gz; float Temperature; double KalmanAngleX; double KalmanAngleY;} MPU6050_t;// Kalman structuretypedef struct{ double Q_angle; double Q_bias; double R_measure; double angle; double bias; double P[2][2];} Kalman_t;uint8_t MPU6050_Init(I2C_HandleTypeDef *I2Cx);void MPU6050_Read_Accel(I2C_HandleTypeDef *I2Cx, MPU6050_t *DataStruct);void MPU6050_Read_Gyro(I2C_HandleTypeDef *I2Cx, MPU6050_t *DataStruct);void MPU6050_Read_Temp(I2C_HandleTypeDef *I2Cx, MPU6050_t *DataStruct);void MPU6050_Read_All(I2C_HandleTypeDef *I2Cx, MPU6050_t *DataStruct);double Kalman_getAngle(Kalman_t *Kalman, double newAngle, double newRate, double dt);

4、导入mpu6050.c文件

刚才只是创建了c文件,但是工程中没有该文件,所以需要导入该文件。

鼠标右键工程路径,点击“Manage Project ltems…”

来到此界面后点击新建,在下面输入“mpu6050”

点击“Add Files”后,点击返回上级目录,进入Core/Src路径,选择mpu6050.c文件后点击“Add”

之后关闭窗口并点击“ok”

5、调用相关代码

在“main.c”文件中进行编辑

①添加6050头文件

/ * USER CODE BEGIN Includes * /#include \"mpu6050.h\"/ * USER CODE END Includes * /

②定义6050结构体

/ * USER CODE BEGIN PV * /MPU6050_t MPU6050;/ * USER CODE END PV * /

③在main函数中初始化6050

/ * USER CODE BEGIN 2 * /while (MPU6050_Init(&hi2c1) == 1);/ * USER CODE END 2 * /

④读取参数,在主循环中写入以下代码:

MPU6050_Read_All(&hi2c1, &MPU6050);printf(\"加速度 x:%.2f \\t y:%.2f \\t z:%.2f\\n\",MPU6050.Ax,MPU6050.Ay,MPU6050.Az);printf(\"陀螺仪 x:%.2f \\t y:%.2f \\t z:%.2f\\n\",MPU6050.Gx,MPU6050.Gy,MPU6050.Gz);printf(\"温度 %.2f\\n\",MPU6050.Temperature);

⑤读取角度

 MPU6050_Read_All(&hi2c1, &MPU6050);printf(\"X: %f, Y: %f\\n\", MPU6050.KalmanAngleX, MPU6050.KalmanAngleY);

6、硬件链接

单片机引脚 mpu6050引脚 引脚介绍 3.3V VCC 3.3v供电 GND GND 接地 B6 SCL IIC时钟线 B7 SDA IIC数据线 GND AD0 AD0为6050地址控制引脚,接地就可以

此引脚接法以STM32F103C8T6为例

其他芯片接法,可以去cubemx中的IIC配置查看,如图所示:

五、工程下载

工程下载连接,提取码:6666https://pan.baidu.com/s/10QMImbnyVk_Sfga2LLiZow?pwd=6666

毛巾批发