自平衡机器人-【蛋黄物语】

pz_cloud 于 2016-1-3 00:39 编辑



项目简介:





后续:这是蛋黄的加强版,通过ccd摄像头有了巡线功能


蛋黄的创意来自于垃圾桶界萌神瓦力,那个吧唧吧唧到处跑的小机器人是不是给你带来很多感动呢



自平衡小车大家可能见过,但是能在手掌上跑的小小车大家玩过吗~







--------------------------------------------------------------------------------------------------

来看看制作蛋黄需要的材料:

1.两个减速电机X2,最好带码盘这个去网上搜就能找到,码盘测速电机,很便宜的几元钱一个。用这个电机方便的地方在于,它自带码盘脉冲输出,我们可以通过读取它转动时输出的脉冲数来获取当前轮子的转速,进而控制蛋黄的前进方向和速度。



2.L298N电机驱动模块Arduino通过它来驱动电机,买这种带光耦隔离的模块很方便,体积也很小巧,正好充当蛋黄的底座。





3.Arduino mini pro 主控板一块选mini pro是因为它体积小巧,io齐全,价格还便宜,很适合做小车,你值得拥有。缺点是不像UNO那样可以直接下载程序,需要自备一根串口线,嫌麻烦的同学可以换用Arduino nano。





4.MPU6050六轴陀螺仪加速度计模块这是让小车站立起来的核心元件,我们通过它来测量小车的自身倾角,通过I2C总线与Arduino连接。一般的陀螺仪和加速度计需要进行滤波角度合成,使用起来会麻烦一些,而6050则内部集成了DMP模块帮助直接输出合成角度,Arduino开源的优势使得我们可以利用现成的DMP库方便地驱动这块芯片。







5.蓝牙串口模块一个手机通过蓝牙连接模块之后,就能直接对机器人进行串口通信了,配合手机上的上位机,就可以随心控制机器人的行动啦。蓝牙模块分为从机模块和主机模块或者主从一体机模块,区别在于从机模块只能被搜索配对,而主机则可以主动搜索,在本项目中我们用手机连接,买从模块就行,价格大概20元。



6.废旧手机电池一块3.7v的锂电池就行,各种废旧手机相机MP4的电池都麻利地翻出来吧,容量自然是越大越好,我用的是PS3手柄的内置电池。值得注意的是,如果你的Arduino事选的5V供电版,那么就需要把电池接一个5V稳压模块再给Arduino供电哦,否则电压是不够的如果是3.3V版本则可以直接把电池接Arduino的RAW脚进行供电。


  1. 升压模块一个因为锂电池3.7V的电压驱动电机会有点力不从心,所以我们加上一个升压模块保证动力。网上搜升压模块就能买到的,几元一个不贵。



8.安卓手机一部你兜里的电话~



9.一张废旧电话卡或银行卡,502胶水一瓶,洞洞板一小块,杜邦线和排针若干用来制作车身,以及连接各个模块,塑料卡比较好加工,洞洞板也可以不用,直接用杜邦线连接各个模块再用胶水固定就行。





--------------------------------------------------------------------------------------------------



好啦,万事俱备,来介绍一下原理~就是应用负反馈控制,由测量到的角度和自身平衡时的自然角度的差作为误差,通过一个叫做PID的控制算法来控制电机转速和转向,偏离目标角度时,往前倒就向前跑一点,往后倒就向后跑一点,只要这个过程做的足够快,参数合适,小车就能稳稳地站起来啦。也就是说我们通过MPU6050检测小车的角度作为PID函数的输入,设定一个平衡角度作为PID函数的目标值,然后把PID函数的输出作为PWM值驱动电机。



--------------------------------------------------------------------------------------------------接下来是制作过程,各模块的连接:首先是连接好arduino和陀螺仪,MPU6050的vcc和gnd接5v电源和地,SDA接arduino的A4脚,SCL接arduino的A5脚,INT接arduino数字2口。

然后用洞洞板做了一个Arduino的插座,6050藏在下面



当然也可以直接把arduino焊上去,下面那个6050芯片是用杜邦线焊上去的,直接拔插组合模块会比较方便一些。



板子背面的样子



L298n模块和两个电机的连接,用502把两个电机和L298N粘在一张电话卡上。L298N模块的四个输入口分别接arduino的数字6,7,8,9口,用来控制两个电机的正反转,L298N的两个PWM口分别接arduino的10,11口,用于调节两个电机的转速。



固定好之后的样子



接下来把刚刚粘好的电机模组跟上面的主控板拼接起来,就像这样。



再把电池塞进中间的缝隙,我用的这个PS3手柄的电池很薄。



把电源线接上各个模块,机器人的主体就完成啦~

再接下来,让我们用乐高积木装饰一下小车,我还在机器人胸口装了一个蓝色的LED灯,可以有呼吸灯的效果哦,连接在arduino的5口,通过analogWrite()控制亮度。





这里空出来的线是用来连接PS2手柄的接收器的,但是因为我们这次是用蓝牙控制,所以就用不上啦。直接把蓝牙模块的TX,RX接到Arduino的RX,TX。




到这里为止你的小机器人应该就能动啦,但是我们还没有加上控制器和控制算法。首先把文章后面的代码下载到arduino中,需要说一下arduino pro mini的下载程序方法,没用过的同学可能会有点疑惑。其实很简单,用USB转TTL线连接arduino的串口,TTL板上的TX,RX连接pro mini的RX,TX,之后就是跟UNO一样的下载方法,选择IDE的板卡pro mini,选择串口号,点IDE的下载按钮,大概三秒之后等IDE的提示框出现橙色字样的时候按一下arduino pro mini的复位,稍等片刻就下载完成了。

然后拿出你的蓝牙模块,先用AT指令把它的通信波特率设成115200,AT指令的用法买模块时会给你资料的,这里也介绍一下,就是在蓝牙未配对的情况下,连接USB转TTL线到电脑,打开串口助手,输入以下字符(不带引号)“AT回车”如果收到OK字样就说明连接成功,然后使用各种AT命令设置蓝牙,比如“AT+BAUD7”就是把蓝牙的波特率设为115200。设好之后,连接蓝牙模块和arduino的TX,RX,注意是TX接RX,RX接TX。

然后,就是打开手机的上位机了,大家可能担心,我不会安卓编程啊,要怎么自定义发送的指令呢?这里教大家一个简便的方法~去下载一个app叫做“蓝牙串口”,安装在手机上,就可以很方便地调试蓝牙模块支持自定义按键哦。





进去app之后可以自己定义按下什么按钮发送什么数据,比如我们把下图几个按键这样设置,按下前进的时候发送a,然后arduino程序里面设置,接收到a就前进,b就后退,等等。



手机连接模块的步骤是,先打开机器人,等蓝牙模块开始闪烁之后,电机手机软件里右上角的连接,一会儿就连上了,蓝牙模块常亮。注意第一次连接的时候,要先进手机蓝牙设置里,搜索蓝牙设备,然后配对好之后,以后在蓝牙串口软件里才能选择这个设备,模块密码一般默认是1234。

接下来就用手机调整一下PID参数吧~等你的小车可以稳定地运行,之后就是你自由发挥添加你喜欢的模块的时候啦,我做过一个大号的蛋黄加上了摄像头非常炫酷~至此你就拥有了属于你的自平衡机器人了,向小伙伴炫耀去吧~




源代码:[C] 纯文本查看 复制代码

#include <PID_v1.h>
#include "Wire.h"
#include "I2Cdev.h"
#include "MPU6050_6Axis_MotionApps20.h"
MPU6050 mpu(0x68);

#define center 0x7F

char flag=0;
char num=0;
double time;
signed int speeds = 0;
signed int oldspeed =0;
byte inByte ;
// MPU control/status vars
bool dmpReady = false;
uint8_t mpuIntStatus;
uint8_t devStatus;
uint16_t packetSize;
uint16_t fifoCount;
uint8_t fifoBuffer[64];

signed int speedcount=0;

// orientation/motion vars
Quaternion q; // [w, x, y, z] quaternion container
VectorFloat gravity; // [x, y, z] gravity vector
float ypr[3]; // [yaw, pitch, roll] yaw/pitch/roll container and gravity vector
float angle;
double Setpoint, Input, Output;
double kp = 18.8,ki = 185.0,kd = 0.29;//需要你修改的参数

double Setpoints, Inputs, Outputs;
double sp = 0.8,si = 0,sd = 0.22;//需要你修改的参数

unsigned char dl=17,count;

union{
signed int all;
unsigned char s[2];
}data;

volatile bool mpuInterrupt = false; // indicates whether MPU interrupt pin has gone high
void dmpDataReady() {
mpuInterrupt = true;
}
PID myPID(&Input, &Output, &Setpoint,kp,ki,kd, DIRECT);

PID sPID(&Inputs, &Outputs, &Setpoints,sp,si,sd, DIRECT);

void motor(int v)
{
if(v>0)
{
v+=dl;
digitalWrite(6,0);
digitalWrite(7,1);
digitalWrite(8,1);
digitalWrite(9,0);
analogWrite(10,v);
analogWrite(11,v);
}
else if(v<0)
{
v=-v;
v+=dl;
digitalWrite(6,1);
digitalWrite(7,0);
digitalWrite(8,0);
digitalWrite(9,1);
analogWrite(10,v);
analogWrite(11,v);
}
else
{
analogWrite(10,0);
analogWrite(11,0);
}
}

void motort(int v)
{
if(v>0)
{
v+=dl;
digitalWrite(8,1);
digitalWrite(9,0);
analogWrite(10,v);
}
else if(v<0)
{
v=-v;
v+=dl;
digitalWrite(8,0);
digitalWrite(9,1);
analogWrite(10,v);
}
else
{
analogWrite(10,0);
}
}

void setup()
{
pinMode(6,OUTPUT);
pinMode(7,OUTPUT);
pinMode(8,OUTPUT);
pinMode(9,OUTPUT);
pinMode(10,OUTPUT);
pinMode(11,OUTPUT);
digitalWrite(6,0);
digitalWrite(7,1);
digitalWrite(8,1);
digitalWrite(9,0);
analogWrite(10,0);
analogWrite(11,0);
Serial.begin(115200);
Wire.begin();

delay(100);

Serial.println("Initializing I2C devices...");
mpu.initialize();
Serial.println("Testing device connections...");
Serial.println(mpu.testConnection() ? "MPU6050 connection successful" : "MPU6050 connection failed");
delay(2);
Serial.println("Initializing DMP...");
devStatus = mpu.dmpInitialize();
if (devStatus == 0)
{
Serial.println("Enabling DMP...");
mpu.setDMPEnabled(true);
Serial.println("Enabling interrupt detection (Arduino external interrupt 0)...");
attachInterrupt(0, dmpDataReady, RISING);
mpuIntStatus = mpu.getIntStatus();
Serial.println("DMP ready! Waiting for first interrupt...");
dmpReady = true;
packetSize = mpu.dmpGetFIFOPacketSize();
}
else
{
Serial.print("DMP Initialization failed (code ");
Serial.print(devStatus);
Serial.println(")");
}

Setpoint = 22.0;
myPID.SetTunings(kp,ki,kd);
myPID.SetOutputLimits(-255+dl,255-dl);
myPID.SetSampleTime(5);
myPID.SetMode(AUTOMATIC);

sPID.SetTunings(sp,si,sd);
sPID.SetOutputLimits(-10,70);
sPID.SetSampleTime(200);
sPID.SetMode(AUTOMATIC);

attachInterrupt(1,speed,RISING);
}

void loop()
{
if (!dmpReady)
return;
// wait for MPU interrupt or extra packet(s) available
if (!mpuInterrupt && fifoCount < packetSize)
return;
mpuInterrupt = false;
mpuIntStatus = mpu.getIntStatus();
fifoCount = mpu.getFIFOCount();
if ((mpuIntStatus & 0x10) || fifoCount == 1024)
{
mpu.resetFIFO();
}
else if (mpuIntStatus & 0x02)
{
while (fifoCount < packetSize) fifoCount = mpu.getFIFOCount();
mpu.getFIFOBytes(fifoBuffer, packetSize);
fifoCount -= packetSize;
mpu.dmpGetQuaternion(&q, fifoBuffer);
mpu.dmpGetGravity(&gravity, &q);
mpu.dmpGetYawPitchRoll(ypr, &q, &gravity); //从DMP中取出Yaw、Pitch、Roll三个轴的角度,放入数组ypr。单位:弧度
angle=-ypr[1] * 180/M_PI;
}

Inputs = speedcount;
sPID.Compute();

Setpoint = 22.0+Outputs;

Input = angle;
myPID.Compute();

if(angle>60||angle<0)
Output=0;
if(flag)
{
motort(Output);
flag=0;
}
else {
motor(Output);

}

if (Serial.available() > 0) {
inByte = Serial.read();
}
if(inByte == 'w'){
kp+=0.5;}
else if(inByte == 'q'){
kp-=0.5;}
else if(inByte == 'r'){
ki+=10;}
else if(inByte == 'e'){
ki-=10;}
else if(inByte == 'y'){
kd+=0.01;}
else if(inByte == 't'){
kd-=0.01;}
else if(inByte == 'i'){
dl+=1;}
else if(inByte == 'u'){
dl-=1;}
else if(inByte == 's'){
sp+=0.1;}
else if(inByte == 'a'){
sp-=0.1;}
else if(inByte == 'f'){
si+=1;}
else if(inByte == 'd'){
si-=1;}
else if(inByte == 'h'){
sd+=0.01;}
else if(inByte == 'g'){
sd-=0.01;}
else if(inByte == 'v'){
Setpoints+=2;}
else if(inByte == 'b'){
Setpoints-=2;}
else if(inByte == 'n'){
Setpoints+=2;
flag=1;}
else if(inByte == 'm'){
Setpoints-=2;
flag=1;}

inByte='x';

sPID.SetTunings(sp,si,sd);
myPID.SetTunings(kp,ki,kd);

num++;
if(num==20)
{num=0;
Serial.print(kp);
Serial.print(',');
Serial.print(ki);
Serial.print(',');
Serial.print(kd);
Serial.print(',');
Serial.print(dl);
Serial.print(" ");
Serial.print(sp);
Serial.print(',');
Serial.print(si);
Serial.print(',');
Serial.print(sd);
Serial.print(',');
Serial.println(angle);
}

}

void speed()
{
if(digitalRead(6)){
speedcount+=1;
}
else
speedcount-=1;
}







PID库文件:
网盘下载 PID_v1.zip http://pan.baidu.com/s/1dExdYV3



---------------------------------------------------------------------------------预计完成时间:已完成



联系方式:593245898@qq.com



www.pengzhihui.xyz

---------------------------------------------------------------------------------


via - arduino中文社区

标签: Arduino教程