No.9 Robotics / Mbed 2 deprecated Robotics_DCMotor

Dependencies:   mbed

Fork of Robotics_Lab_DCMotor by LDSC_Robotics

Committer:
winstonkuo
Date:
Wed Apr 13 10:26:17 2016 +0000
Revision:
8:05ac8875cb1f
Parent:
7:f7d503690ea5
wenyu;

Who changed what in which revision?

UserRevisionLine numberNew contents of line
dg0704 3:178ee1fe1c60 1 /*DCMotor*/
YCTung 0:0971f0666990 2 #include "mbed.h"
YCTung 0:0971f0666990 3
YCTung 0:0971f0666990 4 //The number will be compiled as type "double" in default
YCTung 0:0971f0666990 5 //Add a "f" after the number can make it compiled as type "float"
YCTung 0:0971f0666990 6 #define Ts 0.01f //period of timer1 (s)
winstonkuo 8:05ac8875cb1f 7 #define Kp 0.005f
winstonkuo 8:05ac8875cb1f 8 #define Ki 0.0001f
dg0704 3:178ee1fe1c60 9
dg0704 3:178ee1fe1c60 10 Serial bluetooth(D10,D2); //宣告藍牙腳位
dg0704 3:178ee1fe1c60 11 Serial pc(D1, D0);
YCTung 0:0971f0666990 12
YCTung 0:0971f0666990 13 PwmOut pwm1(D7);
YCTung 0:0971f0666990 14 PwmOut pwm1n(D11);
YCTung 0:0971f0666990 15 PwmOut pwm2(D8);
YCTung 0:0971f0666990 16 PwmOut pwm2n(A3);
YCTung 0:0971f0666990 17
YCTung 0:0971f0666990 18 DigitalOut led1(A4);
YCTung 0:0971f0666990 19 DigitalOut led2(A5);
YCTung 0:0971f0666990 20
YCTung 0:0971f0666990 21 //Motor1 sensor
YCTung 0:0971f0666990 22 InterruptIn HallA_1(A1);
YCTung 0:0971f0666990 23 InterruptIn HallB_1(A2);
YCTung 0:0971f0666990 24 //Motor2 sensor
YCTung 0:0971f0666990 25 InterruptIn HallA_2(D13);
YCTung 0:0971f0666990 26 InterruptIn HallB_2(D12);
YCTung 0:0971f0666990 27
YCTung 0:0971f0666990 28 Ticker timer1;
YCTung 0:0971f0666990 29 void timer1_interrupt(void);
YCTung 0:0971f0666990 30 void CN_interrupt(void);
YCTung 0:0971f0666990 31
YCTung 0:0971f0666990 32 void init_TIMER(void);
YCTung 0:0971f0666990 33 void init_PWM(void);
YCTung 0:0971f0666990 34 void init_CN(void);
YCTung 0:0971f0666990 35
YCTung 0:0971f0666990 36 int8_t stateA_1=0, stateB_1=0, stateA_2=0, stateB_2=0;
YCTung 0:0971f0666990 37 int8_t state_1 = 0, state_1_old = 0, state_2 = 0, state_2_old = 0;
YCTung 0:0971f0666990 38
YCTung 0:0971f0666990 39 int v1Count = 0;
YCTung 0:0971f0666990 40 int v2Count = 0;
YCTung 0:0971f0666990 41
YCTung 0:0971f0666990 42 float v1 = 0.0, v1_ref = 0.0;
YCTung 0:0971f0666990 43 float v1_err = 0.0, v1_ierr = 0.0, PIout_1 = 0.0, PIout_1_old = 0.0;
YCTung 0:0971f0666990 44 float v2 = 0.0, v2_ref = 0.0;
YCTung 0:0971f0666990 45 float v2_err = 0.0, v2_ierr = 0.0, PIout_2 = 0.0, PIout_2_old = 0.0;
winstonkuo 8:05ac8875cb1f 46 char speedCommand;
winstonkuo 8:05ac8875cb1f 47 int timer_count = 0;
winstonkuo 8:05ac8875cb1f 48 char str[100];
YCTung 0:0971f0666990 49
YCTung 0:0971f0666990 50 int main() {
YCTung 0:0971f0666990 51
dg0704 3:178ee1fe1c60 52 bluetooth.baud(115200);
dg0704 3:178ee1fe1c60 53
YCTung 0:0971f0666990 54 init_TIMER();
YCTung 0:0971f0666990 55 init_PWM();
YCTung 0:0971f0666990 56 init_CN();
YCTung 0:0971f0666990 57
YCTung 0:0971f0666990 58 v1_ref = 0.0;
YCTung 0:0971f0666990 59 v2_ref = 0.0;
YCTung 0:0971f0666990 60
dg0704 3:178ee1fe1c60 61 while(1)
dg0704 3:178ee1fe1c60 62 {
dg0704 3:178ee1fe1c60 63 if(pc.readable())
dg0704 3:178ee1fe1c60 64 {
dg0704 3:178ee1fe1c60 65 bluetooth.putc(pc.getc());
dg0704 3:178ee1fe1c60 66 }
dg0704 3:178ee1fe1c60 67 if(bluetooth.readable())
dg0704 3:178ee1fe1c60 68 {
winstonkuo 7:f7d503690ea5 69 speedCommand = bluetooth.getc();
dg0704 3:178ee1fe1c60 70
dg0704 3:178ee1fe1c60 71 if (speedCommand == 'a')
dg0704 3:178ee1fe1c60 72 {
dg0704 3:178ee1fe1c60 73 v1_ref = v1_ref + 10;
winstonkuo 8:05ac8875cb1f 74 v2_ref = v2_ref - 10;
dg0704 3:178ee1fe1c60 75 }
dg0704 3:178ee1fe1c60 76 else if (speedCommand == 's')
dg0704 3:178ee1fe1c60 77 {
dg0704 3:178ee1fe1c60 78 v1_ref = v1_ref - 10;
winstonkuo 8:05ac8875cb1f 79 v2_ref = v2_ref + 10;
dg0704 3:178ee1fe1c60 80 }
dg0704 3:178ee1fe1c60 81 else if (speedCommand == 'q')
dg0704 3:178ee1fe1c60 82 {
winstonkuo 8:05ac8875cb1f 83 v1_ref = v1_ref + 30;
winstonkuo 8:05ac8875cb1f 84 v2_ref = v2_ref - 30;
dg0704 3:178ee1fe1c60 85 }
dg0704 3:178ee1fe1c60 86 else if (speedCommand == 'w')
dg0704 3:178ee1fe1c60 87 {
winstonkuo 8:05ac8875cb1f 88 v1_ref = v1_ref - 30;
winstonkuo 8:05ac8875cb1f 89 v2_ref = v2_ref + 30;
dg0704 3:178ee1fe1c60 90 }
dg0704 3:178ee1fe1c60 91
winstonkuo 8:05ac8875cb1f 92 if (v1_ref < -300)
winstonkuo 8:05ac8875cb1f 93 v1_ref = -300;
winstonkuo 8:05ac8875cb1f 94 else if (v1_ref > 300)
winstonkuo 8:05ac8875cb1f 95 v1_ref = 300;
dg0704 3:178ee1fe1c60 96
winstonkuo 8:05ac8875cb1f 97 if (v2_ref < -300)
winstonkuo 8:05ac8875cb1f 98 v2_ref = -300;
winstonkuo 8:05ac8875cb1f 99 else if (v2_ref > 300)
winstonkuo 8:05ac8875cb1f 100 v2_ref = 300;
dg0704 3:178ee1fe1c60 101 }
YCTung 0:0971f0666990 102 }
YCTung 0:0971f0666990 103 }
YCTung 0:0971f0666990 104
YCTung 0:0971f0666990 105 void timer1_interrupt(void)
YCTung 0:0971f0666990 106 {
YCTung 0:0971f0666990 107 //Motor 1
YCTung 1:6747911cdd90 108 v1 = (float)v1Count * 100.0f / 12.0f * 60.0f / 29.0f; //unit: rpm
YCTung 0:0971f0666990 109 v1Count = 0;
YCTung 0:0971f0666990 110
YCTung 0:0971f0666990 111 ///code for PI control///
dg0704 3:178ee1fe1c60 112 v1_err = v1_ref - v1;
dg0704 3:178ee1fe1c60 113 v1_ierr += v1_err;
dg0704 3:178ee1fe1c60 114 PIout_1 = Kp * v1_err + Ki * Ts * (v1_ierr - v1_err);
YCTung 0:0971f0666990 115
dg0704 3:178ee1fe1c60 116 // saturation
YCTung 0:0971f0666990 117 if(PIout_1 >= 0.5f)PIout_1 = 0.5f;
YCTung 0:0971f0666990 118 else if(PIout_1 <= -0.5f)PIout_1 = -0.5f;
YCTung 0:0971f0666990 119 pwm1.write(PIout_1 + 0.5f);
YCTung 0:0971f0666990 120 TIM1->CCER |= 0x4;
YCTung 0:0971f0666990 121
dg0704 3:178ee1fe1c60 122 PIout_1_old = PIout_1;
YCTung 0:0971f0666990 123
YCTung 0:0971f0666990 124 //Motor 2
YCTung 1:6747911cdd90 125 v2 = (float)v2Count * 100.0f / 12.0f * 60.0f / 29.0f; //unit: rpm
YCTung 0:0971f0666990 126 v2Count = 0;
YCTung 0:0971f0666990 127
YCTung 0:0971f0666990 128 ///code for PI control///
dg0704 3:178ee1fe1c60 129 v2_err = v2_ref - v2;
dg0704 3:178ee1fe1c60 130 v2_ierr += v2_err;
dg0704 3:178ee1fe1c60 131 PIout_2 = Kp * v2_err + Ki * Ts * (v2_ierr - v2_err);
YCTung 0:0971f0666990 132
dg0704 3:178ee1fe1c60 133 //saturation
YCTung 0:0971f0666990 134 if(PIout_2 >= 0.5f)PIout_2 = 0.5f;
YCTung 0:0971f0666990 135 else if(PIout_2 <= -0.5f)PIout_2 = -0.5f;
YCTung 0:0971f0666990 136 pwm2.write(PIout_2 + 0.5f);
YCTung 0:0971f0666990 137 TIM1->CCER |= 0x40;
dg0704 3:178ee1fe1c60 138
dg0704 3:178ee1fe1c60 139 PIout_2_old = PIout_2;
winstonkuo 8:05ac8875cb1f 140
winstonkuo 8:05ac8875cb1f 141 /*timer_count++;
winstonkuo 8:05ac8875cb1f 142 //send speed
winstonkuo 8:05ac8875cb1f 143 if(timer_count == 50)
winstonkuo 8:05ac8875cb1f 144 {
winstonkuo 8:05ac8875cb1f 145 bluetooth.printf(str, "motor1: %f, motor2: %f\n", v1, v2);
winstonkuo 8:05ac8875cb1f 146 timer_count = 0;
winstonkuo 8:05ac8875cb1f 147 }*/
YCTung 0:0971f0666990 148 }
YCTung 0:0971f0666990 149
YCTung 0:0971f0666990 150 void CN_interrupt(void)
YCTung 0:0971f0666990 151 {
YCTung 0:0971f0666990 152 //Motor 1
YCTung 0:0971f0666990 153 stateA_1 = HallA_1.read();
YCTung 0:0971f0666990 154 stateB_1 = HallB_1.read();
YCTung 0:0971f0666990 155
YCTung 0:0971f0666990 156 ///code for state determination///
dg0704 3:178ee1fe1c60 157 if (stateA_1 == 0)
dg0704 3:178ee1fe1c60 158 {
dg0704 3:178ee1fe1c60 159 if (stateB_1 == 0)
dg0704 3:178ee1fe1c60 160 state_1 = 1;
dg0704 3:178ee1fe1c60 161 else
winstonkuo 7:f7d503690ea5 162 state_1 = 2;
dg0704 3:178ee1fe1c60 163 }
dg0704 3:178ee1fe1c60 164 else
dg0704 3:178ee1fe1c60 165 {
dg0704 3:178ee1fe1c60 166 if (stateB_1 == 1)
dg0704 3:178ee1fe1c60 167 state_1 = 3;
dg0704 3:178ee1fe1c60 168 else
winstonkuo 7:f7d503690ea5 169 state_1 = 4;
dg0704 3:178ee1fe1c60 170 }
YCTung 0:0971f0666990 171
dg0704 3:178ee1fe1c60 172 //Forward: v1Count +1
dg0704 3:178ee1fe1c60 173 //Inverse: v1Count -1
dg0704 3:178ee1fe1c60 174 if ( (state_1 == (state_1_old + 1)) || (state_1 == (state_1_old - 3)) )
dg0704 3:178ee1fe1c60 175 v1Count++;
dg0704 3:178ee1fe1c60 176 else if ( (state_1 == (state_1_old - 1)) || (state_1 == (state_1_old + 3)))
dg0704 3:178ee1fe1c60 177 v1Count--;
dg0704 3:178ee1fe1c60 178
dg0704 3:178ee1fe1c60 179 state_1_old = state_1;
YCTung 0:0971f0666990 180
YCTung 0:0971f0666990 181 //Motor 2
YCTung 0:0971f0666990 182 stateA_2 = HallA_2.read();
YCTung 0:0971f0666990 183 stateB_2 = HallB_2.read();
YCTung 0:0971f0666990 184
YCTung 0:0971f0666990 185 ///code for state determination///
dg0704 3:178ee1fe1c60 186 if (stateA_2 == 0)
dg0704 3:178ee1fe1c60 187 {
dg0704 3:178ee1fe1c60 188 if (stateB_2 == 0)
dg0704 3:178ee1fe1c60 189 state_2 = 1;
dg0704 3:178ee1fe1c60 190 else
winstonkuo 7:f7d503690ea5 191 state_2 = 2;
dg0704 3:178ee1fe1c60 192 }
dg0704 3:178ee1fe1c60 193 else
dg0704 3:178ee1fe1c60 194 {
dg0704 3:178ee1fe1c60 195 if (stateB_2 == 1)
dg0704 3:178ee1fe1c60 196 state_2 = 3;
dg0704 3:178ee1fe1c60 197 else
winstonkuo 7:f7d503690ea5 198 state_2 = 4;
dg0704 3:178ee1fe1c60 199 }
YCTung 0:0971f0666990 200
dg0704 3:178ee1fe1c60 201 //Forward: v2Count +1
dg0704 3:178ee1fe1c60 202 //Inverse: v2Count -1
dg0704 3:178ee1fe1c60 203 if ( (state_2 == (state_2_old + 1)) || (state_2 == (state_2_old - 3)) )
winstonkuo 8:05ac8875cb1f 204 v2Count++;
dg0704 3:178ee1fe1c60 205 else if ( (state_2 == (state_2_old - 1)) || (state_2 == (state_2_old + 3)))
winstonkuo 8:05ac8875cb1f 206 v2Count--;
YCTung 0:0971f0666990 207 }
YCTung 0:0971f0666990 208
YCTung 0:0971f0666990 209 void init_TIMER(void)
YCTung 0:0971f0666990 210 {
YCTung 0:0971f0666990 211 timer1.attach_us(&timer1_interrupt, 10000);//10ms interrupt period (100 Hz)
YCTung 0:0971f0666990 212 }
YCTung 0:0971f0666990 213
YCTung 0:0971f0666990 214 void init_PWM(void)
YCTung 0:0971f0666990 215 {
YCTung 0:0971f0666990 216 pwm1.period_us(50);
YCTung 0:0971f0666990 217 pwm1.write(0.5);
YCTung 0:0971f0666990 218 TIM1->CCER |= 0x4;
YCTung 0:0971f0666990 219
YCTung 0:0971f0666990 220 pwm2.period_us(50);
YCTung 0:0971f0666990 221 pwm2.write(0.5);
YCTung 0:0971f0666990 222 TIM1->CCER |= 0x40;
YCTung 0:0971f0666990 223 }
YCTung 0:0971f0666990 224
YCTung 0:0971f0666990 225 void init_CN(void)
YCTung 0:0971f0666990 226 {
YCTung 0:0971f0666990 227 HallA_1.rise(&CN_interrupt);
YCTung 0:0971f0666990 228 HallA_1.fall(&CN_interrupt);
YCTung 0:0971f0666990 229 HallB_1.rise(&CN_interrupt);
YCTung 0:0971f0666990 230 HallB_1.fall(&CN_interrupt);
YCTung 0:0971f0666990 231
YCTung 0:0971f0666990 232 HallA_2.rise(&CN_interrupt);
YCTung 0:0971f0666990 233 HallA_2.fall(&CN_interrupt);
YCTung 0:0971f0666990 234 HallB_2.rise(&CN_interrupt);
YCTung 0:0971f0666990 235 HallB_2.fall(&CN_interrupt);
YCTung 0:0971f0666990 236
YCTung 0:0971f0666990 237 stateA_1 = HallA_1.read();
YCTung 0:0971f0666990 238 stateB_1 = HallB_1.read();
YCTung 0:0971f0666990 239 stateA_2 = HallA_2.read();
YCTung 0:0971f0666990 240 stateB_2 = HallB_2.read();
YCTung 0:0971f0666990 241 }