在之前,本魔拿到了這台EduCake平衡車,
本魔認為相當有趣,
因為使用的是實驗用的小馬達及小型行動電源,
所以出現許許多多不同的問題,
但也將這些問題一一排解,現在就來介紹遇到的問題及解決的方法。
首先,最大的問題是平衡,
先前做的版本其實並不是相當穩定,
之後本魔加入了PID去做調整,加入了Kp與Kd雖然穩定許多,
但還是經常出現爆衝無法平衡的問題,
最後加入了Ki,情況才穩定下來。
接著是馬達力道問題,
基本上兩顆馬達的精度就不是很高,
所以有時會出現一輪轉一輪不轉的情況(即一輪未克服摩擦力),
接著就是克服摩擦力的力道有點大,
這樣使得馬達無法相當低速的旋轉,在克服摩擦力後的轉速過快,
平衡時會無法精準的調整到我要的轉速,使得平衡又再難上一個層次。
接著的問題是施力過大時,陀螺儀會當掉,
一開始本魔也是百思不得其解,
電表、示波器都測試過,結果去詢問了電路的達人,
他幫我加了幾顆電容,就解決了,
似乎是電流被拉低,導致陀螺儀重啟。
接著是要在倒地時自己站立起來,
本魔發現力道相當不夠,所以將電源做了更換,
換成7.4V的鋰電池,在加上5V穩壓電路供給控制板。
以上是近期遇到的問題,
也確實的想辦法解決了,
而之後,本魔會再加入移動控制,
請各位敬請關注!
code:
code:
#include <EEPROM.h>
#include "FreeIMU1.h"
#include <Wire.h>
#include <stdio.h>
#include <conio.h>
#include "pitches.h"
int raw_values[9];
float ypr[3]; // yaw pitch roll
unsigned long pretime = 0;
unsigned long pretime1 = 0;
unsigned long pretime2 = 0;
int pin[4] = {10,11,31,32};
float target;
float targetoffset = 0;
float Kp,Ki,Kd;
float pid_u,pid_sum;
float pid_e[2];
char key;
boolean flag = true;
// Set the FreeIMU object
FreeIMU1 my3IMU = FreeIMU1();
void setup() {
Serial.begin(115200);
Wire.begin();
delay(5);
my3IMU.init(); // the parameter enable or disable fast mode
delay(5);
pinMode(10,OUTPUT);
pinMode(11,OUTPUT);
Kp = 70;
Ki = 1.2;
Kd = 20;
target = 0;
pid_u = 0;
pid_e[0] = 0;
pid_e[1] = 0;
pid_sum = 0;
}
void loop() {
//Get gyro value
target += targetoffset;
my3IMU.getYawPitchRoll(ypr);
//PID calculate
if(kbhit()){
key = getch();
if(key == '1')
Kp += 5;
else if(key == '2')
Kp -= 5;
else if(key == '3')
Kd += 5;
else if(key == '4')
Kd -= 5;
}
if((ypr[2] > 25 || ypr[2] < -25) && flag){
target = 0;
targetoffset = 0;
tone(PCSPEAKER, NOTE_G3,1000/4);
delay(1000/4 * 1.30);
noTone(PCSPEAKER);
flag = false;
pretime1 = millis();
analogWrite(pin[0],0);
analogWrite(pin[1],0);
analogWrite(pin[2],0);
analogWrite(pin[3],0);
}
if(ypr[2] > 25 && millis() - pretime1> 2000ul){
target = 0;
targetoffset = 0;
tone(PCSPEAKER, NOTE_G4,1000/4);
delay(1000/4 * 1.30);
noTone(PCSPEAKER);
pid_sum = 0;
analogWrite(pin[0],0);
analogWrite(pin[1],255);
analogWrite(pin[2],0);
analogWrite(pin[3],255);
delay(100);
analogWrite(pin[1],0);
analogWrite(pin[0],255);
analogWrite(pin[3],0);
analogWrite(pin[2],255);
delay(100);
analogWrite(pin[0],0);
analogWrite(pin[1],0);
analogWrite(pin[2],0);
analogWrite(pin[3],0);
delay(75);
pretime2 = millis();
while(millis() - pretime2 < 2000ul){
my3IMU.getYawPitchRoll(ypr);
if(ypr[2] < -5 && ypr[2] > -25){
flag = true;
break;
}
}
}else if(ypr[2] < -25 && millis() - pretime1> 2000ul){
target = 0;
targetoffset = 0;
tone(PCSPEAKER, NOTE_G4,1000/4);
pid_sum = 0;
analogWrite(pin[1],0);
analogWrite(pin[0],255);
analogWrite(pin[3],0);
analogWrite(pin[2],255);
delay(100);
analogWrite(pin[0],0);
analogWrite(pin[1],255);
analogWrite(pin[2],0);
analogWrite(pin[3],255);
delay(100);
analogWrite(pin[0],0);
analogWrite(pin[1],0);
analogWrite(pin[2],0);
analogWrite(pin[3],0);
delay(75);
pretime2 = millis();
while(millis() - pretime2 < 2000ul){
my3IMU.getYawPitchRoll(ypr);
if(ypr[2] < 25 && ypr[2] > 5){
flag = true;
break;
}
}
}
if(ypr[2] < 25 && ypr[2] > -25){
pid_sum += pid_e[0];
pid_e[0] = target - ypr[2];
pid_u = Kp * (pid_e[0])
+ Ki * (pid_sum)
+ Kd * (pid_e[0] - pid_e[1]);
if(pid_u > 0){
pid_u = pid_u > 255 ? 255: pid_u;
pid_u = pid_u < 90 ? 0: pid_u;
}else{
pid_u = pid_u < -255 ? -255: pid_u;
pid_u = pid_u > -90 ? 0: pid_u;
}
pid_e[1] = pid_e[0];
analogWrite(pin[1],pid_u > 0 ? pid_u : 0);
analogWrite(pin[0],pid_u < 0 ? -pid_u : 0);
analogWrite(pin[3],pid_u > 0 ? pid_u : 0);
analogWrite(pin[2],pid_u < 0 ? -pid_u : 0);
}
if(pid_u > 90 || pid_u < -90){
targetoffset = pid_u * 0.0003;
}else{
targetoffset = 0;
}
while(millis() - pretime> 1000ul){
Serial.print(" Roll: ");
Serial.print(ypr[2]);
Serial.println("");
pretime = millis();
}
}












