Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Dependencies: mbed CRotaryEncoder TB6612FNG
main.cpp
- Committer:
- yusaku0125
- Date:
- 2019-08-26
- Revision:
- 4:ac9e6772ddb3
- Parent:
- 3:e455433c8cae
- Child:
- 5:f635f1f01d2d
File content as of revision 4:ac9e6772ddb3:
////モータPID調整用プログラム
////精密な速度制御を可能とするために
////M_KP,M_KDの調整を行う。
////DEFAULT_SPEEDに近い速度へ安定して出力
////できることを確認する。
#include "mbed.h"
#include "CRotaryEncoder.h"
#include "TB6612.h"
//☆★☆★各種パラメータ調整箇所☆★☆★☆★
#define DEFAULT_SPEED 1000 //機体の直進速度1000[mm/s]
#define PULSE_TO_UM 30 //エンコーダ1パルス当たりのタイヤ移動距離[um]
//実測で値を調整する。
#define INTERRUPT_TIME 1000 //割りこみ周期[us]
//モータ速度のゲイン関連
#define M_KP 0.002f//P(比例)制御成分
#define M_KD 0.001f//D(微分)制御成分
//////////☆★☆★☆★☆★☆★//////////////
Serial PC(USBTX,USBRX);
CRotaryEncoder encoder_a(D1,D0); //モータAのエンコーダ
CRotaryEncoder encoder_b(D11,D12); //モータBのエンコーダ
Ticker timer; //タイマ割込み用
TB6612 motor_a(D2,D7,D6); //モータA制御用(pwma,ain1,ain2)
TB6612 motor_b(D10,D8,D9); //モータB制御用(pwmb,bin1,bin2)
int Enc_Count_A=0,Enc_Count_B=0; //エンコーダパルス数を格納
int Distance_A=0,Distance_B=0; //タイヤ移動距離を格納[mm]
int Speed_A=0, Speed_B=0; //現在速度
int Target_Speed_A=0,Target_Speed_B=0; //目標速度
int Motor_A_Diff[2]={0,0}; //過去の偏差と現在の偏差を格納
int Motor_B_Diff[2]={0,0};
float Motor_A_P,Motor_B_P; //モータP制御成分
float Motor_A_D,Motor_B_D; //モータD制御成分
float Motor_A_Pwm,Motor_B_Pwm; //モータへの出力
void timer_interrupt(){
////モータ現在速度の取得
Enc_Count_A=encoder_a.Get(); //エンコーダパルス数を取得
Enc_Count_B=-encoder_b.Get();
Distance_A=(Enc_Count_A*PULSE_TO_UM); //移動距離をmm単位で格納
Distance_B=(Enc_Count_B*PULSE_TO_UM);
Speed_A=(Distance_A*1000)/INTERRUPT_TIME;//走行速度演算[mm/s]
Speed_B=(Distance_B*1000)/INTERRUPT_TIME;
Distance_A=0;
Distance_B=0;
encoder_a.Set(0);
encoder_b.Set(0);
/////各モータの目標速度の設定
Target_Speed_A=DEFAULT_SPEED;
Target_Speed_B=DEFAULT_SPEED;
/////モータの速度制御
//過去の速度偏差を退避
Motor_A_Diff[1]=Motor_A_Diff[0];
Motor_A_Diff[1]=Motor_A_Diff[0];
//現在の速度偏差を取得。
Motor_A_Diff[0]=(Target_Speed_A-Speed_A);
Motor_B_Diff[0]=(Target_Speed_B-Speed_B);
//P成分演算
Motor_A_P=Motor_A_Diff[0]*M_KP;
Motor_B_P=Motor_B_Diff[0]*M_KP;
//D成分演算
Motor_A_D=(Motor_A_Diff[0]-Motor_A_Diff[1])*M_KD;
Motor_B_D=(Motor_B_Diff[0]-Motor_B_Diff[1])*M_KD;
Motor_A_Pwm=Motor_A_P+Motor_A_D;
Motor_B_Pwm=Motor_B_P+Motor_B_D;
//最終的には符号を逆転して出力
motor_a=-Motor_A_Pwm;
motor_b=-Motor_B_Pwm;
}
int main() {
timer.attach_us(&timer_interrupt,INTERRUPT_TIME);//タイマ割り込みスタート
while(1){
wait(1);
PC.printf("spd_a:%d[mm/sec] spd_b:%d[mm/sec]\r\n",Speed_A,Speed_B);//表示
}
}