接线图,如下所示:
arduino代码
/*
PID速度控制
(1) 接收命令从MATLAB(通过COM6): set_speed(设定速度值), kP, kI, kD(PID的参数)
(2)通过PWM波控制电机速度(PWM是基于PID计算的)
(3)发送当前速度并发送到MATLAB中显示出来
*/
String mySt = "";
char myChar;
boolean stringComplete = false; // 字符是否完整
boolean motor_start = false;
const byte pin_a = 2; //对于编码器脉冲A
const byte pin_b = 3; //编码器脉冲B
const byte pin_fwd = 4; //驱动器的插线
const byte pin_bwd = 5; //
const byte pin_pwm = 6; //控制驱动电机的速度
int encoder = 0;
int m_direction = 0;
int sv_speed = 100; //该值为0~255
double pv_speed = 0;
double set_speed = 0;
double e_speed = 0; //速度误差 = 设定速度- 当前速度
double e_speed_pre = 0; //最后速度误差
double e_speed_sum = 0; //总的速度误差
double pwm_pulse = 0; //值为0~255
double kp = 0;
double ki = 0;
double kd = 0;
int timer1_counter; //定时器1的设定
int i=0;
void setup() {
pinMode(pin_a,INPUT_PULLUP);
pinMode(pin_b,INPUT_PULLUP);
pinMode(pin_fwd,OUTPUT);
pinMode(pin_bwd,OUTPUT);
pinMode(pin_pwm,OUTPUT);
attachInterrupt(digitalPinToInterrupt(pin_a), detect_a, RISING);// //Enable中断管脚, 中断服务程序为detect_a(), 监视引脚变化
// 设置波特率
Serial.begin(9600);
//--------------------------定时器设置
noInterrupts(); //禁用所有中断
TCCR1A = 0;
TCCR1B = 0;
timer1_counter = 59286; // 预加载计时器65536-16MHz/256/2Hz (34286 for 0.5sec) (59286 for 0.1sec)
TCNT1 = timer1_counter; // 预加载计时器
TCCR1B |= (1 << CS12); // 256个预分选器
TIMSK1 |= (1 << TOIE1); // 启用定时器溢出中断
interrupts(); // 启用所有中断
//--------------------------建立完毕
while (!Serial) {
; // 等待串口连接,仅用于本地USB端口
}
analogWrite(pin_pwm,0); //电机停止
digitalWrite(pin_fwd,0); //
digitalWrite(pin_bwd,0); //
}
void loop() {
if (stringComplete) {
//当COM接收完成后,清除该字符串
mySt = ""; //注意:在下面的代码中,mySt不会变成空白,mySt是空白的,直到收到'\n'为止。
stringComplete = false;
}
//接收matlab指令
//获取字符串位置的信息
if (mySt.substring(0,8) == "vs_start"){
digitalWrite(pin_fwd,1); //前进
digitalWrite(pin_bwd,0);
motor_start = true;
}
if (mySt.substring(0,7) == "vs_stop"){
digitalWrite(pin_fwd,0);
digitalWrite(pin_bwd,0); //停止
motor_start = false;
}
if (mySt.substring(0,12) == "vs_set_speed"){
set_speed = mySt.substring(12,mySt.length()).toFloat(); //在set_speed之后获取字符串
}
if (mySt.substring(0,5) == "vs_kp"){
kp = mySt.substring(5,mySt.length()).toFloat(); //在vs_kp后获取字符
}
if (mySt.substring(0,5) == "vs_ki"){
ki = mySt.substring(5,mySt.length()).toFloat(); // vs_ki后获取字符
}
if (mySt.substring(0,5) == "vs_kd"){
kd = mySt.substring(5,mySt.length()).toFloat(); // vs_kd后获取字符
}
}
void detect_a() {
encoder+=1; //编码器在新脉冲时增加
m_direction = digitalRead(pin_b); //读取电机转向
}
ISR(TIMER1_OVF_vect) // 中断服务程序--每0.1秒滴答一次。
{
TCNT1 = timer1_counter; // 建立计时器
pv_speed = 600.0*(encoder/200.0)/0.1; //计算电机转速单位转(这里200个脉冲为一圈)
encoder=0;
//打印出速度(串口)
if (Serial.available() <= 0) {
Serial.print("speed");
Serial.println(pv_speed); //串口发到MATLAB中
}
//PID控制工程
if (motor_start){
e_speed = set_speed - pv_speed;//误差速度=设定速度 - 先前测得速度
pwm_pulse = e_speed*kp + e_speed_sum*ki + (e_speed - e_speed_pre)*kd;
e_speed_pre = e_speed; //保留最后(先前)误差值
e_speed_sum += e_speed; //总误差
if (e_speed_sum >4000) e_speed_sum = 4000; //极限转速
if (e_speed_sum <-4000) e_speed_sum = -4000;
}
else{
e_speed = 0;
e_speed_pre = 0;
e_speed_sum = 0;
pwm_pulse = 0;
}
//更新速度
if (pwm_pulse <255 & pwm_pulse >0){
analogWrite(pin_pwm,pwm_pulse); //设立电机速度
}
else{
if (pwm_pulse>255){
analogWrite(pin_pwm,255);
}
else{
analogWrite(pin_pwm,0);
}
}
}
void serialEvent() {
while (Serial.available()) {
// 获取新字节
char inChar = (char)Serial.read();
// 将其添加到输入字符串中:
if (inChar != '\n') {
mySt += inChar;
}
// 如果输入的字符是换行符,则设置一个标志。
// 因此主循环可以做这些:
if (inChar == '\n') {
stringComplete = true;
}
}
}
[文件名:(arduino_pid_speed)]