此篇博客用于记录使用arduino驱动直流减速电机的过程,仅实现简单的功能:PID调速、蓝牙控制
-
- 1、直流减速电机简介
- 2、DRV8833电机驱动模块简介
- 3、HC-05蓝牙模块简介
- 电机转动测试
- 4、PID控制
- 5、蓝牙控制电机
1、直流减速电机简介
我在淘宝购买的电机,减速比是21.3,旋转一圈产生的脉冲数是11,这样实际通过编码区采集到的一圈脉冲数(使用一倍频计数)是11×21.3,如果采用N倍频的话就是:11×21.3×N。这里关于编码器的相关知识直接看此文档有详细介绍:http://www.autolabor.com.cn/book/ROSTutorials/di-8-zhang-gou-jian-lun-shi-cha-fen-ji-qi-ren/83-di-pan-kong-zhi-ji-chu-arduino-yu-dian-ji-qu-dong/833-dian-ji-ce-su.html
上面给出了接线方式,要注意的是直接使用arduino的io口是无法驱动电机的,所以还需要一块电机驱动板或者驱动芯片,这里使用的是DRV8833电机驱动模块,红色接DRV8833的AO1、白色接DRV8833的AO2、黑色接arduino的GND、蓝色接3V3、因为使用一倍频,只需要一个中断口就可以,这里换黄色接引脚2(外部中断),绿色接引脚9(可以使用其他的io口)。
2、DRV8833电机驱动模块简介
下面是芯片引脚图
由于这里VM需要较高的电压才能驱动电机转起来,所以还单独购买了一个电池,用于VM引脚供电,电池名称:18650锂电池,最好选可以充电的那种。
AIN1接arduino的引脚10(需要可以输出pwm波的引脚),AIN2接引脚11(可以任意指定引脚,这只是用于控制方向),STBY引脚直接接5V。
3、HC-05蓝牙模块简介
一共六个引脚,EN和STATE一般用不到,其余的有两个电源引脚、两个串口引脚。建议在使用单片机调试之前先用usb转ttl模块连接电脑进行测试:①将RX连接至usb转ttl模块的TX,TX连接RX,电源线对着连。②插进电脑之前先按住HC-05上的按键,然后将usb转ttl模块插入电脑,此时HC-05就会进入AT指令状态下,可以使用电脑的串口助手进行测试,蓝牙模块的波特率默认是38400,0个停止位,0个校验位。③进行测试,发送指令的顺序可以参考这个:1、AT,返回OK;2、AT+ROLE=0,默认就是零,保险起见再设置一下,设置完这个之后,下一次上电周围的设备就可以搜索到此蓝牙;3、AT+NAME=xxx,这里按自己喜好设置名字;4、AT+PSWD=“xxx”,设定密码;5、AT+UART=38400,0,0。设置波特率和停止位、校验位。
这样就设置完成了,下一次可以直接上电,然后手机搜索蓝牙使用密码连接。如果不想用串口助手测试,也可以再arduino中用以下代码测试(蓝牙模块的RX连接arduino引脚9,TX连引脚8):
#include <SoftwareSerial.h> //库文件 SoftwareSerial BT(8, 9); //设置蓝牙与板子的连接端口。 pin 8 接蓝牙的 TXD pin 9 接蓝牙的 RXD char X; //定义一个变量存数据。 void setup() { Serial.begin(38400); //串口监视器通信速率,38400 Serial.println("蓝牙连接正常"); //串口监视器显示蓝牙正常状态 BT.begin(38400); //蓝牙通信速率,默认一般为 38400 } void loop() //大循环,执行。 { if (Serial.available()) { X = Serial.read(); //把写入的数据给到自定义变量 X BT.print(X); //由arduino向手机发数据 } if (BT.available()) { X = BT.read(); //把检测到的数据给到自定义变量 X Serial.print(X); //由手机向arduino发数据 } }
编译运行之后打开自带的串口监视器,设置模式BOTH NL &CR,波特率选择38400,就可以输入前面的指令进行设置了,后面与手机进行通信的时候发现数据都是乱码,将 BT.begin(38400); 改为 BT.begin(9600);即可。
电机转动测试
按照上面的方式连接好线路之后可以先测试看是否能正常驱动电机转起来:
/* * 电机转动控制 * 1.定义接线中电机对应的引脚 * 2.setup 中设置引脚为输出模式 * 3.loop中控制电机转动 * */ int DIRA = 11; int PWMA = 10; void setup() { //两个引脚都设置为 OUTPUT pinMode(DIRA,OUTPUT); pinMode(PWMA,OUTPUT); } void loop() { //先正向转动3秒 digitalWrite(DIRA,LOW); analogWrite(PWMA,100); delay(3000); //停止3秒 digitalWrite(DIRA,LOW); analogWrite(PWMA,0); delay(3000); //再反向转动3秒 digitalWrite(DIRA,HIGH); analogWrite(PWMA,100); delay(3000); //停止3秒 digitalWrite(DIRA,LOW); analogWrite(PWMA,0); delay(3000); /* * 注意: * 1.可以通过将DIRA设置为HIGH或LOW来控制电机转向,但是哪个标志位正转或反转需要根据需求判断,转向是相对的。 * 2.PWM的取值为 [0,255],该值可自己设置。 * */ }
如果电机转动起来说明前面的步骤就没问题。
转速测试也直接参考前面的那个链接里做就行。
4、PID控制
理论部分参考链接文档,下面给出具体实现流程:
也就是直接调用PID库里的函数就可以实现,具体代码如下:
#include <PID_v1.h> int motor_A = 2;//中端口是2 int motor_B = 9;//中断口是3 int DIRA = 11; int PWMA = 10; volatile int count = 0;//如果是正转,那么每计数一次自增1,如果是反转,那么每计数一次自减1 float reducation = 21;//减速比,根据电机参数设置,比如 15 | 30 | 60 int pulse = 11; //编码器旋转一圈产生的脉冲数该值需要参考商家电机参数 int per_round = pulse * reducation;//车轮旋转一圈产生的脉冲数 long start_time = millis();//一个计算周期的开始时刻,初始值为 millis(); long interval_time = 50;//一个计算周期 50ms double current_vel; void count_A(){ //单频计数实现 //手动旋转电机一圈,输出结果为 一圈脉冲数 * 减速比 if(digitalRead(motor_A) == HIGH){ if(digitalRead(motor_B) == HIGH){//A 高 B 高 count++; } else {//A 高 B 低 count--; } } } //获取当前转速的函数 void get_current_vel(){ long right_now = millis(); long past_time = right_now - start_time;//计算逝去的时间 if(past_time >= interval_time){//如果逝去时间大于等于一个计算周期 //1.禁止中断 noInterrupts(); //2.计算转速 转速单位可以是秒,也可以是分钟... 自定义即可 current_vel = (double)(count) / per_round / past_time * 1000 * 60; //3.重置计数器 count = 0; //4.重置开始时间 start_time = right_now; //5.重启中断 interrupts(); Serial.println(current_vel); } } //-------------------------------------PID------------------------------------------- //创建 PID 对象 //1.当前转速 2.计算输出的pwm 3.目标转速 4.kp 5.ki 6.kd 7.当输入与目标值出现偏差时,向哪个方向控制 double pwm;//电机驱动的PWM值 double target = 20; double kp=1.5, ki=3.0, kd=0.1; PID pid(¤t_vel,&pwm,&target,kp,ki,kd,DIRECT); //速度更新函数 void update_vel(){ //获取当前速度 get_current_vel(); pid.Compute();//计算需要输出的PWM digitalWrite(DIRA,HIGH); analogWrite(PWMA,pwm); } void setup() { Serial.begin(57600);//设置波特率 pinMode(9,INPUT); pinMode(2,INPUT); pinMode(10,OUTPUT); pinMode(11,OUTPUT); attachInterrupt(0,count_A,CHANGE);//当电平发生改变时触发中断函数 pid.SetMode(AUTOMATIC); } void loop() { delay(10); update_vel(); }
PID控制的最终预期结果,是要快速、精准、稳定的达成预期结果,P主要用于控制响应速度,I主要用于控制精度,D主要用于减小震荡增强系统稳定性,三者的取值是需要反复调试的,调试过程中需要查看系统的响应曲线,根据响应曲线以确定合适的PID值。
在 Arduino 中响应曲线的查看可以借助于 Serial.println() 将结果输出,然后再选择菜单栏的工具下串口绘图器以图形化的方式显示响应结果
5、蓝牙控制电机
这里只提供简单实现,可以用安卓手机市场里的蓝牙调试器进行调试,如果找不到也可以私信我。实现控制电机正反转。
#include <SoftwareSerial.h> #include <PID_v1.h> SoftwareSerial BT(8, 9); //设置蓝牙与板子的连接端口。 pin 8 接蓝牙的 TXD pin 9 接蓝牙的 RXD char X; //定义一个变量存数据。 String temp = ""; int motor_A = 2;//中端口是2 int motor_B = 9;//中断口是3 int DIRA = 11; int PWMA = 10; volatile int count = 0;//如果是正转,那么每计数一次自增1,如果是反转,那么每计数一次自减1 float reducation = 21.3;//减速比,根据电机参数设置,比如 15 | 30 | 60 int pulse = 11; //编码器旋转一圈产生的脉冲数该值需要参考商家电机参数 int per_round = pulse * reducation;//车轮旋转一圈产生的脉冲数 long start_time = millis();//一个计算周期的开始时刻,初始值为 millis(); long interval_time = 50;//一个计算周期 50ms double current_vel; void count_A(){ //单频计数实现 //手动旋转电机一圈,输出结果为 一圈脉冲数 * 减速比 if(digitalRead(motor_A) == HIGH){ if(digitalRead(motor_B) == HIGH){//A 高 B 高 count++; } else {//A 高 B 低 count--; } } } //获取当前转速的函数 void get_current_vel(){ long right_now = millis(); long past_time = right_now - start_time;//计算逝去的时间 if(past_time >= interval_time){//如果逝去时间大于等于一个计算周期 //1.禁止中断 noInterrupts(); //2.计算转速 转速单位可以是秒,也可以是分钟... 自定义即可 current_vel = (double)(count) / per_round / past_time * 1000 * 60; //3.重置计数器 count = 0; //4.重置开始时间 start_time = right_now; //5.重启中断 interrupts(); Serial.println(current_vel); } } //-------------------------------------PID------------------------------------------- //创建 PID 对象 //1.当前转速 2.计算输出的pwm 3.目标转速 4.kp 5.ki 6.kd 7.当输入与目标值出现偏差时,向哪个方向控制 double pwm;//电机驱动的PWM值 double target = 0; double kp=1.5, ki=3.0, kd=0.1; PID pid(¤t_vel,&pwm,&target,kp,ki,kd,DIRECT); //速度更新函数 void update_vel(){ //获取当前速度 get_current_vel(); pid.Compute();//计算需要输出的PWM if(target > 0) { digitalWrite(DIRA,LOW); //正转 } else if(target < 0) { digitalWrite(DIRA,HIGH);//反转 } else { } analogWrite(PWMA,pwm); } void setup() { Serial.begin(38400);//设置波特率 pinMode(9,INPUT); pinMode(2,INPUT); pinMode(10,OUTPUT); pinMode(11,OUTPUT); attachInterrupt(0,count_A,CHANGE);//当电平发生改变时触发中断函数 pid.SetMode(AUTOMATIC); BT.begin(9600); } void loop() { if (BT.available()) //检测:【蓝牙】如果数据写入,则执行。 { X = BT.read(); //把检测到的数据给到自定义变量 X Serial.println(X); //把从蓝牙得到的数据显示到串口监视器 temp = X; } if(temp == "2") { target = 80; Serial.println(temp); } else if(temp == "3") { target = -80; Serial.println(temp); } else if(temp == "0") { target = 0; Serial.println(temp); } delay(10); update_vel(); }
蓝牙调试器发送2控制电机正转,发送3反转,发送0停止。