arduino uno 平衡小车程序死机 求助大神-Arduino中文社区 - Powered by Discuz!

Arduino中文社区

 找回密码
 立即注册

QQ登录

只需一步,快速开始

查看: 2368|回复: 7

[未解决] arduino uno 平衡小车程序死机 求助大神

[复制链接]
发表于 2021-8-6 14:45 | 显示全部楼层 |阅读模式
硬件使用了只用了 uno HC-05 mpu6050,平衡小车是使用步进电机的。利用中断驱动步进电机。不用蓝牙控制,手怎么去推去弄都不会死机,但是一用手机蓝牙遥控控制就死机,表现就是明明速度和倾角不大直接就哉下去了。串口监视器也不输出数据了。怀疑是串口和电机中断冲突了。加了喂狗也没用。求助大神。这是主程序:

  1. #include <CtrlApp.h>
  2. #include <avr/wdt.h>
  3. #include "TimerOne.h"
  4. #include <Wire.h>
  5. CtrlApp obj((HardwareSerial&)Serial, 115200);           //实例化检测对象
  6. float Joy_x, Joy_y, Grav_x, Grav_y;
  7. int gyro_address = 0x68;                                     //MPU-6050 I2C address (0x68 or 0x69)
  8. int acc_calibration_value = 0;                            //Enter the accelerometer calibration value
  9. //Various settings
  10. float pid_p_gain = 60.0;                                       //Gain setting for the P-controller (15)
  11. float pid_d_gain = 120.0;                                       //Gain setting for the D-controller (30)
  12. //float turning_speed = 60;                                    //Turning speed (20)
  13. float maxspeed = 800;                                //Max target speed (100)
  14. float    pid_speed_Kp = 0.015;                 //utput 角度环目标pid_setpoint//0.015    0.00007
  15. float    pid_speed_Ki = 0.000075;
  16. float    pid_speed_out , pid_speed_temp, pid_last_speed_error, pid_i_mem_speed , pid_setspeed , pid_output_2;
  17. ///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
  18. //Declaring global variables
  19. ///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
  20. byte start_0, received_byte, low_bat;
  21. int yxjs_2 = 0;
  22. int left_motor, throttle_left_motor, throttle_counter_left_motor, throttle_left_motor_memory;
  23. int right_motor, throttle_right_motor, throttle_counter_right_motor, throttle_right_motor_memory;
  24. int battery_voltage;
  25. int receive_counter;
  26. int gyro_pitch_data_raw, gyro_yaw_data_raw, accelerometer_data_raw;
  27. long gyro_yaw_calibration_value, gyro_pitch_calibration_value;
  28. float angle_gyro, angle_acc, angle, self_balance_pid_setpoint;
  29. float pid_error_temp, pid_i_mem, pid_setpoint, gyro_input, pid_output, pid_last_d_error;
  30. float pid_output_left, pid_output_right;
  31. void setup() {

  32.   obj.begin();                                                               //串口启动
  33.   Wire.begin();                                                             //I2C通讯启动
  34.   TWBR = 12;
  35.   Timer1.initialize(20);                                                    //中断时间
  36.   Timer1.attachInterrupt(Flash);                                            //中断启动
  37.   pinMode(2, OUTPUT);
  38.   pinMode(3, OUTPUT);
  39.   pinMode(5, OUTPUT);
  40.   pinMode(6, OUTPUT);
  41.   pinMode(13, OUTPUT);
  42.   pinMode(8, OUTPUT);

  43.   mpu6050_Start();                                                          //mpu6050获取参数前设置
  44.   wdt_enable(WDTO_15MS);                                                    //喂狗启动设置时间15MS
  45. }

  46. void loop() {
  47.   obj.routine();                                                               //蓝牙数据程序
  48.   Joy_x = obj.getJoyX();
  49.   Joy_y = obj.getJoyY();                                                       //数据赋值
  50.   //    Grav_x = obj.getGravX();
  51.   //    Grav_y = obj.getGravY();
  52.   Joy_x = Joy_x * 60;                                                         //将蓝牙获取数据放大
  53.   Joy_y = Joy_y * 200;
  54.   if (yxjs_2 >= 50 && yxjs_2 < 100) {                                           //定时启动程序  200次计数一次20US约4MS启动一次PID计算及角度获取

  55.     Angle();                                                                    //角度加速度获取函数

  56.     if (start_0 == 0 && angle_acc > -0.5 && angle_acc < 0.5) {                  //平衡条件达成启动计算
  57.       angle_gyro = angle_acc;
  58.       start_0 = 1;
  59.       pid_output = 0;
  60.       pid_speed_out = 0;
  61.       pid_i_mem_speed = 0;
  62.       pid_setpoint = 0;
  63.       self_balance_pid_setpoint = 0;
  64.       PORTB &= 0b11111110 ;                                                  //使能步进
  65.     }
  66.     if (angle_gyro > 25 || angle_gyro < -25 || start_0 == 0 ) {               //如果各个条件达成关闭计算并复位参数
  67.       pid_output = 0;
  68.       pid_speed_out = 0;
  69.       pid_i_mem_speed = 0;
  70.       start_0 = 0;
  71.       pid_setpoint = 0;
  72.       self_balance_pid_setpoint = 0;
  73.       PORTB |= 0b00000001 ;

  74.     }
  75.   }
  76.   pid_setspeed = pid_setspeed * 0.9 + Joy_y * 0.1;                           //平滑角度
  77.   if (yxjs_2 >= 200) {
  78.     yxjs_2 = 0;
  79.     if (start_0 == 1) {
  80.       pd_huan();                                                                //pd角度环
  81.       pi_huan();                                                                //pi速度环
  82.       motor_pulse();                                                            //脉冲速度计算
  83.     }
  84.   }
  85. //    Serial.print(throttle_left_motor_memory);
  86. //    Serial.print("\t");
  87.     Serial.println(angle_gyro);
  88.   wdt_reset();                                                          //喂狗复位
  89. }
复制代码


这是打包的函数:
  1. void mpu6050_Start(){
  2. //By default the MPU-6050 sleeps. So we have to wake it up.
  3.   Wire.beginTransmission(gyro_address);                                     //Start communication with the address found during search.
  4.   Wire.write(0x6B);                                                         //We want to write to the PWR_MGMT_1 register (6B hex)
  5.   Wire.write(0x00);                                                         //Set the register bits as 00000000 to activate the gyro
  6.   Wire.endTransmission();                                                   //End the transmission with the gyro.
  7.   //Set the full scale of the gyro to +/- 250 degrees per second
  8.   Wire.beginTransmission(gyro_address);                                     //Start communication with the address found during search.
  9.   Wire.write(0x1B);                                                         //We want to write to the GYRO_CONFIG register (1B hex)
  10.   Wire.write(0x00);                                                         //Set the register bits as 00000000 (250dps full scale)
  11.   Wire.endTransmission();                                                   //End the transmission with the gyro
  12.   //Set the full scale of the accelerometer to +/- 4g.
  13.   Wire.beginTransmission(gyro_address);                                     //Start communication with the address found during search.
  14.   Wire.write(0x1C);                                                         //We want to write to the ACCEL_CONFIG register (1A hex)
  15.   Wire.write(0x08);                                                         //Set the register bits as 00001000 (+/- 4g full scale range)
  16.   Wire.endTransmission();                                                   //End the transmission with the gyro
  17.   //Set some filtering to improve the raw data.
  18.   Wire.beginTransmission(gyro_address);                                     //Start communication with the address found during search
  19.   Wire.write(0x1A);                                                         //We want to write to the CONFIG register (1A hex)
  20.   Wire.write(0x03);                                                         //Set the register bits as 00000011 (Set Digital Low Pass Filter to ~43Hz)
  21.   Wire.endTransmission();                                                   //End the transmission with the gyro

  22. }

  23. void Angle(){
  24.     //Angle calculations
  25.   ///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
  26.   Wire.beginTransmission(gyro_address);                                     //Start communication with the gyro
  27.   Wire.write(0x3D);                                                         //Start reading at register 3F
  28.   Wire.endTransmission();                                                   //End the transmission
  29.   Wire.requestFrom(gyro_address, 2);                                        //Request 2 bytes from the gyro
  30.   accelerometer_data_raw = Wire.read() << 8 | Wire.read();                  //Combine the two bytes to make one intege
  31.   if (accelerometer_data_raw > 8200)accelerometer_data_raw = 8200;          //Prevent division by zero by limiting the acc data to +/-8200;
  32.   if (accelerometer_data_raw < -8200)accelerometer_data_raw = -8200;        //Prevent division by zero by limiting the acc data to +/-8200;
  33.   angle_acc = asin((float)accelerometer_data_raw / 8200.0) * 57.296;        //Calculate the current angle according to the accelerometer

  34.   Wire.beginTransmission(gyro_address);                                      //Start communication with the gyro
  35.   Wire.write(0x43);                                                         //Start reading at register 43
  36.   Wire.endTransmission();                                                   //End the transmission
  37.   Wire.requestFrom(gyro_address, 2);                                        //Request 4 bytes from the gyro
  38.   gyro_pitch_data_raw = Wire.read() << 8 | Wire.read();                       //Combine the two bytes to make one integer
  39.   gyro_pitch_data_raw += 830;                      //Add the gyro calibration value
  40.   angle_gyro += gyro_pitch_data_raw * 0.000031;
  41.   angle_gyro = angle_gyro * 0.999 + angle_acc * 0.001;
  42. }
  43. void pd_huan(){
  44.     pid_error_temp = angle_gyro  - pid_setpoint;
  45.     //Calculate the PID output value
  46.     pid_output = pid_p_gain * pid_error_temp  + pid_d_gain * (pid_error_temp - pid_last_d_error);
  47.     if (pid_output > maxspeed)pid_output = maxspeed;                                    //Limit the PI-controller to the maximum controller output
  48.     else if (pid_output < maxspeed*-1)pid_output = maxspeed*-1;

  49.     pid_last_d_error = pid_error_temp;                                        //Store the error for the next loop

  50.     if (pid_output < 5 && pid_output > -5)pid_output = 0;                     //Create a dead-band to stop the motors when the robot is balanced
  51.     pid_output_left = pid_output+Joy_x;                                             //Copy the controller output to the pid_output_left variable for the left motor
  52.     pid_output_right = pid_output-Joy_x;                                        //Copy the controller output to the pid_output_right variable for the right motor
  53. }
  54. void pi_huan(){
  55.        pid_output_2 =  pid_output_2 * 0.9 + pid_output * 0.1;
  56.       pid_speed_temp = pid_output_2 - pid_setspeed;
  57.       pid_i_mem_speed +=  pid_speed_Ki * pid_speed_temp;
  58.        if (pid_i_mem_speed > 20)pid_i_mem_speed = 20;                                      //Limit the I-controller to the maximum controller output
  59.   else if (pid_i_mem_speed < -20)pid_i_mem_speed = -20;
  60.       pid_speed_out = pid_speed_Kp * pid_speed_temp + pid_i_mem_speed ;
  61.      if (pid_speed_out > 20)pid_speed_out =20 ;                                    //Limit the PI-controller to the maximum controller output
  62.   else if (pid_speed_out < -20)pid_speed_out = -20;
  63.          pid_setpoint = pid_speed_out*-1;
  64.    }
  65. void motor_pulse(){
  66.   //To compensate for the non-linear behaviour of the stepper motors the folowing calculations are needed to get a linear speed behaviour.
  67.   if (pid_output_left > 0)pid_output_left = maxspeed+5 - (1 / (pid_output_left + 9)) * 5000;
  68.   else if (pid_output_left < 0)pid_output_left = (maxspeed+5)*-1 - (1 / (pid_output_left - 9)) * 5000;

  69.   if (pid_output_right > 0)pid_output_right = maxspeed+5 - (1 / (pid_output_right + 9)) * 5000;
  70.   else if (pid_output_right < 0)pid_output_right = (maxspeed+5)*-1 - (1 / (pid_output_right - 9)) * 5000;

  71.   //Calculate the needed pulse time for the left and right stepper motor controllers
  72.   if (pid_output_left > 0)left_motor = maxspeed+5  - pid_output_left;
  73.   else if (pid_output_left < 0)left_motor = (maxspeed+5)*-1 - pid_output_left;
  74.   else left_motor = 0;

  75.   if (pid_output_right > 0)right_motor =maxspeed+5 - pid_output_right;
  76.   else if (pid_output_right < 0)right_motor = (maxspeed+5)*-1 - pid_output_right;
  77.   else right_motor = 0;

  78.   //Copy the pulse time to the throttle variables so the interrupt subroutine can use them
  79.   throttle_left_motor = left_motor;
  80.   throttle_right_motor = right_motor;
  81. }


  82. void Flash() {

  83.   //Left motor pulse calculations
  84.   yxjs_2++;
  85.   throttle_counter_left_motor ++; //1次加1                                          //Increase the throttle_counter_left_motor variable by 1 every time this routine is executed
  86.   if (throttle_counter_left_motor > throttle_left_motor_memory) {           //If the number of loops is larger then the throttle_left_motor_memory variable
  87.     throttle_counter_left_motor = 0;                                        //Reset the throttle_counter_left_motor variable
  88.     throttle_left_motor_memory = throttle_left_motor;                       //Load the next throttle_left_motor variable
  89.     if (throttle_left_motor_memory < 0) {                                   //If the throttle_left_motor_memory is negative
  90.       PORTD &= 0b11011111;                                                  //Set output 3 low to reverse the direction of the stepper controller
  91.       throttle_left_motor_memory *= -1;                                     //Invert the throttle_left_motor_memory variable
  92.     }
  93.     else PORTD |= 0b00100000;        //1正转                                       //Set output 3 high for a forward direction of the stepper motor//else PORTD |= 0b00001000;
  94.   }
  95.   else if (throttle_counter_left_motor == 1)PORTD |= 0b00000100;            //Set output 2 high to create a pulse for the stepper controller    //else if(throttle_counter_left_motor == 1)PORTD |= 0b00000100;
  96.   else if (throttle_counter_left_motor == 2)PORTD &= 0b11111011;            //Set output 2 low because the pulse only has to last for 20us //else if(throttle_counter_left_motor == 2)PORTD &= 0b11111011;

  97.   //right motor pulse calculations
  98.   throttle_counter_right_motor ++;                                          //Increase the throttle_counter_right_motor variable by 1 every time the routine is executed
  99.   if (throttle_counter_right_motor > throttle_right_motor_memory) {         //If the number of loops is larger then the throttle_right_motor_memory variable
  100.     throttle_counter_right_motor = 0;                                       //Reset the throttle_counter_right_motor variable
  101.     throttle_right_motor_memory = throttle_right_motor;                     //Load the next throttle_right_motor variable
  102.     if (throttle_right_motor_memory < 0) {                                  //If the throttle_right_motor_memory is negative
  103.       PORTD |= 0b01000000;                                                  //Set output 5 low to reverse the direction of the stepper controller
  104.       throttle_right_motor_memory *= -1;                                    //Invert the throttle_right_motor_memory variable
  105.     }
  106.     else PORTD &= 0b10111111;                                               //Set output 5 high for a forward direction of the stepper motor
  107.   }
  108.   else if (throttle_counter_right_motor == 1)PORTD |= 0b00001000;           //Set output 4 high to create a pulse for the stepper controller
  109.   else if (throttle_counter_right_motor == 2)PORTD &= 0b11110111;           //Set output 4 low because the pulse only has to last for 20us

  110. }
复制代码



发表于 2021-8-6 21:19 | 显示全部楼层
初步猜测,串口的中断干扰了有关步进电机的中断
可以试着改一下步进电机的中断处理函数,函数开始运行的时候把全局中断关掉,函数退出前再把全局中断使能
 楼主| 发表于 2021-8-6 23:53 来自手机 | 显示全部楼层
frankhan747 发表于 2021-8-6 21:19
初步猜测,串口的中断干扰了有关步进电机的中断
可以试着改一下步进电机的中断处理函数,函数开始运行的时 ...

行我先试着处理下,看看有没有用
 楼主| 发表于 2021-8-9 13:09 | 显示全部楼层
frankhan747 发表于 2021-8-6 21:19
初步猜测,串口的中断干扰了有关步进电机的中断
可以试着改一下步进电机的中断处理函数,函数开始运行的时 ...

我按照百度的办法把全局中断开启关闭加在电机中断里。好像并没有效果,还是会一头栽倒
发表于 2021-8-9 16:47 | 显示全部楼层
本帖最后由 frankhan747 于 2021-8-9 17:17 编辑
xmc520 发表于 2021-8-9 13:09
我按照百度的办法把全局中断开启关闭加在电机中断里。好像并没有效果,还是会一头栽倒 ...

后来我查了一下资料,发现AVR单片机中,计时器中断的优先级高于所有串口中断的优先级[1]。换句话说,不管计时器中断处理函数中有没有设置开/关全局中断的操作,串口中断都不应该干扰到计时器中断处理函数的执行。
这就有点玄学了。类似的情况我也遇到过:分配某几个功能给Arduino系统,一点问题没有;再加一个功能,Arduino就崩了
当时我用Arduino通过I2C读取传感器并进行大量运算,通过串口输出解算结果。至此一切正常;
然后加了一个SPI总线上的无线收发模块,系统直接就崩了,串口调试发现之前还正常的解算数据都变成了NAN;
换用STM32之后,啥问题没有。
不难猜出,Arduino这个体系其实插满了中断,提供方便也降低效率···加之Atmega328p自身算力贫弱,活一多就忙不过来

[1] AVR中断优先级:重置>外部中断>计时器中断>SPI中断>串口(UART)中断>ADC中断>EEPROM>two-wire(I2C?)中断
https://exploreembedded.com/wiki/Basics_of_AVR_Interrupts

发表于 2021-8-9 17:59 | 显示全部楼层
而且,我寻思这种中断控制步进电机的设计思路可能有些欠妥
如果用计时器中断控制步进电机的转速,那这个中断触发的频率可以说是非常高了。高频中断···会把系统逼得很慢(https://www.avrfreaks.net/forum/ ... -interrupt-too-much
 楼主| 发表于 2021-8-10 08:37 | 显示全部楼层
frankhan747 发表于 2021-8-9 16:47
后来我查了一下资料,发现AVR单片机中,计时器中断的优先级高于所有串口中断的优先级[1]。换句话说,不管 ...

我这个步进速度控制借鉴的别人的程序,代码只加了几个计数,别人也是使用蓝牙控制小车的运动,没有一点问题,这就太玄学了。
 楼主| 发表于 2021-8-10 08:37 | 显示全部楼层
frankhan747 发表于 2021-8-9 17:59
而且,我寻思这种中断控制步进电机的设计思路可能有些欠妥
如果用计时器中断控制步进电机的转速,那这个中 ...

不过还是感谢老哥解答,实在不行上mega2560试试
您需要登录后才可以回帖 登录 | 立即注册

本版积分规则

小黑屋|Archiver|手机版|Arduino中文社区

GMT+8, 2024-11-29 01:42 , Processed in 0.094923 second(s), 15 queries .

Powered by Discuz! X3.4

Copyright © 2001-2021, Tencent Cloud.

快速回复 返回顶部 返回列表