用arduino nano做主控,三个菜鸟四天三夜做出电赛题目。虽然差一点成功,但是制作过程也让菜鸟们学到不少东西。关于倒立摆,有兴趣的童鞋可以先百度了解一下。
由于倒立摆自动控制的数学模型是非线性、多阶、多输入的,是各大高校实验室用于测试自动控制算法的理想模型。但是由于菜鸟们算法和数学建模的知识匮乏,这次只用到了简单的pid算法,而且直接调用了arduino的pid库。用nano的2个外部中断采集编码器的数据,通过中断数量计算摆杆角度。摆杆角度与垂直的差值作为pid算法的输入,经过主控计算后通过引脚pwm控制l289驱动直流减速电机转动……
材料列表:
1.主控arduino nano一块
2.nano扩展板,自制腐蚀pcb一块
3.自制腐蚀pcb电机驱动l298一块
4.欧姆龙高精度旋转编码器(2000线)+编码器滤波放大电路板各一个
5.直流减速电机一个
6.12v直流电源一个
7.碳纤维棒,木板,电源线若干
先写到这里吧,机器还在赛区封着……今天下午开箱测试,晚上回来继续加视屏和无码大图
额,测试完了居然不让把东西拿走,,,,
,先随便上个视频吧
上代码,pid库可以在https://github.com/br3ttb/Arduino-PID-Library/这里下载
int PDAJ = 12; //模式选择 | |
long int anlge; | |
unsigned long time = 0; | |
long count = 0; //计数值 | |
long num = 0; | |
double Setpoint, Input, Output,setpoint; | |
double kp = 0.040,ki = 0.0005,kd =0.0011;//kp = 0.040,ki = 0.0005,kd =0.0011; | |
PID myPID(&Input, &Output, &Setpoint,kp,ki,kd, REVERSE); | |
//初始化 | |
void setup() | |
{ | |
Serial.begin(9600); //窗口初始化 | |
pinMode(PinA,INPUT); //D2脚为输入 | |
pinMode(PinB,INPUT); //D3脚为输入 | |
pinMode(PDAJ,INPUT_PULLUP); | |
attachInterrupt(0, blinkA, FALLING ); //注册中断0调用函数blinkA | |
attachInterrupt(1, blinkB, FALLING ); //注册中断1调用函数blinkB | |
time = micros(); //时间初值 | |
myPID.SetTunings(kp,ki,kd); | |
myPID.SetOutputLimits(-255,255); | |
myPID.SetSampleTime(5); | |
myPID.SetMode(AUTOMATIC); | |
} | |
//主体程序 | |
void loop() | |
{ | |
int bun=digitalRead(PDAJ); | |
if (bun==HIGH) | |
{ | |
num = count; | |
long int anlge=num*18; | |
//Serial.print(anlge); | |
//Serial.print(" "); | |
while(anlge>36000){ | |
anlge=anlge-36000; | |
} | |
while(anlge<0){ | |
anlge=anlge+36000; | |
//Serial.println(anlge); | |
} | |
Input = anlge; | |
myPID.Compute(); | |
int spd; | |
//Serial.print("output= "); | |
Setpoint=18000; | |
//Serial.print(" jd= "); | |
//Serial.print(JD_angle); | |
//Serial.print(" pt= "); | |
//Serial.print(PT_angle); | |
Serial.print(" anlge "); | |
Serial.print(anlge); | |
if (anlge>15000&&anlge<21000) | |
{ | |
spd=Output; | |
} | |
Serial.print(" spd="); | |
Serial.println(spd); | |
motor(spd); | |
} | |
else | |
{ | |
motor(20); | |
delay(40); | |
motor(30); | |
delay(40); | |
motor(50); | |
delay(40); | |
motor(100); | |
delay(40); | |
motor(150); | |
delay(40); | |
motor(0); | |
delay(200); | |
motor(-20); | |
delay(40); | |
motor(-30); | |
delay(40); | |
motor(-50); | |
delay(40); | |
motor(-100); | |
delay(40); | |
motor(-150); | |
delay(40); | |
motor(0); | |
delay(200); | |
} | |
} | |
///////////////////////////////////////////////////////////////////////////////////////////////////////////////// | |
//中断0调用函数 | |
void blinkA() | |
{ | |
if ((micros() - time) > 15) //防抖动处理 | |
count ++; | |
time = micros(); | |
} | |
//中断1调用函数 | |
void blinkB() | |
{ | |
if ((micros() - time) > 15) //防抖动处理 | |
count --; | |
time = micros(); | |
} | |
void motor(int sp1) | |
{ | |
if(sp1>0) { | |
digitalWrite(INA, HIGH); | |
} | |
else | |
{ | |
digitalWrite(INA, LOW); | |
} | |
analogWrite(PWMA,abs (sp1)); | |
} |
来源: 基于arduino的倒立摆(用arduino参加大学生电子设计竞赛)-Arduino中文社区 - Powered by Discuz!
文章末尾固定信息

我的微信
我的微信
一个码农、工程狮、集能量和智慧于一身的、DIY高手、小伙伴er很多的、80后奶爸。
评论