mpu6050控制舵机云台
准备材料:2个舵机mg90,云台支架,1个arduino-uno,mpu6050
编程工具:VScode-platformio or ArduinoIDE 我使用的是VScode在编辑代码上会更方便
首先导入驱动库Servo,mpu6050_tockn
#include#include #include MPU6050 mpu6050(Wire); Servo servo_y; Servo servo_z; /** * @pin_y: 对应纵向旋转舵机 * @pin_x: 对应横向旋转舵机 */ uint8_t pin_y = 9; uint8_t pin_z = 11; float angleY,angleZ,gyroz; double P[2][2] = {{ 1, 0 },{ 0, 1 }}; double Pdot[4] ={ 0,0,0,0}; static const double Q_angle=0.001, Q_gyro=0.003, R_angle=0.5,dtt=0.005,C_0 = 1; double q_bias, angle_err, PCt_0, PCt_1, E, K_0, K_1, t_0, t_1; /** * Kalman_Filter 卡尔曼滤波 * @angle_m: 角度 * @gyro_m: 角速度 **/ void Kalman_Filter(double angle_m,double gyro_m) { angleZ+=(gyro_m-q_bias) * dtt; Pdot[0]=Q_angle - P[0][1] - P[1][0]; Pdot[1]=- P[1][1]; Pdot[2]=- P[1][1]; Pdot[3]=Q_gyro; P[0][0] += Pdot[0] * dtt; P[0][1] += Pdot[1] * dtt; P[1][0] += Pdot[2] * dtt; P[1][1] += Pdot[3] * dtt; angle_err = angle_m - angleZ; PCt_0 = C_0 * P[0][0]; PCt_1 = C_0 * P[1][0]; E = R_angle + C_0 * PCt_0; K_0 = PCt_0 / E; K_1 = PCt_1 / E; t_0 = PCt_0; t_1 = C_0 * P[0][1]; P[0][0] -= K_0 * t_0; P[0][1] -= K_0 * t_1; P[1][0] -= K_1 * t_0; P[1][1] -= K_1 * t_1; angleZ+= K_0 * angle_err; q_bias += K_1 * angle_err; } void setup() { servo_y.attach(pin_y, 0, 180); servo_z.attach(pin_z , 0, 180); Serial.begin(9600); Wire.begin(); mpu6050.begin(); //mpu6050 自校验 mpu6050.calcGyroOffsets(true); } void loop() { mpu6050.update(); angleY = mpu6050.getAngleY(); angleZ = mpu6050.getAngleZ(); gyroz = mpu6050.getGyroZ(); Kalman_Filter(angleZ,gyroz); int pos_y = int(angleY) + 90; int pos_z = int(angleZ) ; Serial.print("angleY:"); Serial.print(angleY); Serial.print("\tangleZ:"); Serial.print(angleZ); Serial.print("\tpos_x:"); Serial.print(pos_y); Serial.print("\tpos_z:"); Serial.println(pos_z); servo_y.write(pos_y); servo_z.write(pos_z); // delay(10); }
通过获取到的yaw(航向角),pitch(俯仰角)简单转换为舵机当前角度,由于yaw角静态飘移,所以长时间会出现控制偏差过大