硬件使用了只用了 uno HC-05 mpu6050,平衡小车是使用步进电机的。利用中断驱动步进电机。不用蓝牙控制,手怎么去推去弄都不会死机,但是一用手机蓝牙遥控控制就死机,表现就是明明速度和倾角不大直接就哉下去了。串口监视器也不输出数据了。怀疑是串口和电机中断冲突了。加了喂狗也没用。求助大神。这是主程序:
- #include <CtrlApp.h>
- #include <avr/wdt.h>
- #include "TimerOne.h"
- #include <Wire.h>
- CtrlApp obj((HardwareSerial&)Serial, 115200); //实例化检测对象
- float Joy_x, Joy_y, Grav_x, Grav_y;
- int gyro_address = 0x68; //MPU-6050 I2C address (0x68 or 0x69)
- int acc_calibration_value = 0; //Enter the accelerometer calibration value
- //Various settings
- float pid_p_gain = 60.0; //Gain setting for the P-controller (15)
- float pid_d_gain = 120.0; //Gain setting for the D-controller (30)
- //float turning_speed = 60; //Turning speed (20)
- float maxspeed = 800; //Max target speed (100)
- float pid_speed_Kp = 0.015; //utput 角度环目标pid_setpoint//0.015 0.00007
- float pid_speed_Ki = 0.000075;
- float pid_speed_out , pid_speed_temp, pid_last_speed_error, pid_i_mem_speed , pid_setspeed , pid_output_2;
- ///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
- //Declaring global variables
- ///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
- byte start_0, received_byte, low_bat;
- int yxjs_2 = 0;
- int left_motor, throttle_left_motor, throttle_counter_left_motor, throttle_left_motor_memory;
- int right_motor, throttle_right_motor, throttle_counter_right_motor, throttle_right_motor_memory;
- int battery_voltage;
- int receive_counter;
- int gyro_pitch_data_raw, gyro_yaw_data_raw, accelerometer_data_raw;
- long gyro_yaw_calibration_value, gyro_pitch_calibration_value;
- float angle_gyro, angle_acc, angle, self_balance_pid_setpoint;
- float pid_error_temp, pid_i_mem, pid_setpoint, gyro_input, pid_output, pid_last_d_error;
- float pid_output_left, pid_output_right;
- void setup() {
- obj.begin(); //串口启动
- Wire.begin(); //I2C通讯启动
- TWBR = 12;
- Timer1.initialize(20); //中断时间
- Timer1.attachInterrupt(Flash); //中断启动
- pinMode(2, OUTPUT);
- pinMode(3, OUTPUT);
- pinMode(5, OUTPUT);
- pinMode(6, OUTPUT);
- pinMode(13, OUTPUT);
- pinMode(8, OUTPUT);
- mpu6050_Start(); //mpu6050获取参数前设置
- wdt_enable(WDTO_15MS); //喂狗启动设置时间15MS
- }
- void loop() {
- obj.routine(); //蓝牙数据程序
- Joy_x = obj.getJoyX();
- Joy_y = obj.getJoyY(); //数据赋值
- // Grav_x = obj.getGravX();
- // Grav_y = obj.getGravY();
- Joy_x = Joy_x * 60; //将蓝牙获取数据放大
- Joy_y = Joy_y * 200;
- if (yxjs_2 >= 50 && yxjs_2 < 100) { //定时启动程序 200次计数一次20US约4MS启动一次PID计算及角度获取
- Angle(); //角度加速度获取函数
- if (start_0 == 0 && angle_acc > -0.5 && angle_acc < 0.5) { //平衡条件达成启动计算
- angle_gyro = angle_acc;
- start_0 = 1;
- pid_output = 0;
- pid_speed_out = 0;
- pid_i_mem_speed = 0;
- pid_setpoint = 0;
- self_balance_pid_setpoint = 0;
- PORTB &= 0b11111110 ; //使能步进
- }
- if (angle_gyro > 25 || angle_gyro < -25 || start_0 == 0 ) { //如果各个条件达成关闭计算并复位参数
- pid_output = 0;
- pid_speed_out = 0;
- pid_i_mem_speed = 0;
- start_0 = 0;
- pid_setpoint = 0;
- self_balance_pid_setpoint = 0;
- PORTB |= 0b00000001 ;
- }
- }
- pid_setspeed = pid_setspeed * 0.9 + Joy_y * 0.1; //平滑角度
- if (yxjs_2 >= 200) {
- yxjs_2 = 0;
- if (start_0 == 1) {
- pd_huan(); //pd角度环
- pi_huan(); //pi速度环
- motor_pulse(); //脉冲速度计算
- }
- }
- // Serial.print(throttle_left_motor_memory);
- // Serial.print("\t");
- Serial.println(angle_gyro);
- wdt_reset(); //喂狗复位
- }
复制代码
这是打包的函数:
|