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
Fork of Robotics_Lab_DCMotor by
main.cpp@7:f7d503690ea5, 2016-04-13 (annotated)
- Committer:
- winstonkuo
- Date:
- Wed Apr 13 09:32:58 2016 +0000
- Revision:
- 7:f7d503690ea5
- Parent:
- 3:178ee1fe1c60
- Child:
- 8:05ac8875cb1f
ting yu;
Who changed what in which revision?
| User | Revision | Line number | New 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) |
| dg0704 | 3:178ee1fe1c60 | 7 | #define Kp 0.05f |
| dg0704 | 3:178ee1fe1c60 | 8 | #define Ki 0.001f |
| 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; |
| YCTung | 0:0971f0666990 | 46 | |
| YCTung | 0:0971f0666990 | 47 | int main() { |
| YCTung | 0:0971f0666990 | 48 | |
| dg0704 | 3:178ee1fe1c60 | 49 | bluetooth.baud(115200); |
| dg0704 | 3:178ee1fe1c60 | 50 | |
| YCTung | 0:0971f0666990 | 51 | init_TIMER(); |
| YCTung | 0:0971f0666990 | 52 | init_PWM(); |
| YCTung | 0:0971f0666990 | 53 | init_CN(); |
| YCTung | 0:0971f0666990 | 54 | |
| YCTung | 0:0971f0666990 | 55 | v1_ref = 0.0; |
| YCTung | 0:0971f0666990 | 56 | v2_ref = 0.0; |
| YCTung | 0:0971f0666990 | 57 | |
| dg0704 | 3:178ee1fe1c60 | 58 | while(1) |
| dg0704 | 3:178ee1fe1c60 | 59 | { |
| dg0704 | 3:178ee1fe1c60 | 60 | if(pc.readable()) |
| dg0704 | 3:178ee1fe1c60 | 61 | { |
| dg0704 | 3:178ee1fe1c60 | 62 | bluetooth.putc(pc.getc()); |
| dg0704 | 3:178ee1fe1c60 | 63 | } |
| dg0704 | 3:178ee1fe1c60 | 64 | if(bluetooth.readable()) |
| dg0704 | 3:178ee1fe1c60 | 65 | { |
| winstonkuo | 7:f7d503690ea5 | 66 | speedCommand = bluetooth.getc(); |
| dg0704 | 3:178ee1fe1c60 | 67 | |
| dg0704 | 3:178ee1fe1c60 | 68 | if (speedCommand == 'a') |
| dg0704 | 3:178ee1fe1c60 | 69 | { |
| dg0704 | 3:178ee1fe1c60 | 70 | v1_ref = v1_ref + 10; |
| dg0704 | 3:178ee1fe1c60 | 71 | v2_ref = v2_ref + 10; |
| dg0704 | 3:178ee1fe1c60 | 72 | } |
| dg0704 | 3:178ee1fe1c60 | 73 | else if (speedCommand == 's') |
| dg0704 | 3:178ee1fe1c60 | 74 | { |
| dg0704 | 3:178ee1fe1c60 | 75 | v1_ref = v1_ref - 10; |
| dg0704 | 3:178ee1fe1c60 | 76 | v2_ref = v2_ref - 10; |
| dg0704 | 3:178ee1fe1c60 | 77 | } |
| dg0704 | 3:178ee1fe1c60 | 78 | else if (speedCommand == 'q') |
| dg0704 | 3:178ee1fe1c60 | 79 | { |
| dg0704 | 3:178ee1fe1c60 | 80 | v1_ref = v1_ref + 20; |
| dg0704 | 3:178ee1fe1c60 | 81 | v2_ref = v2_ref + 20; |
| dg0704 | 3:178ee1fe1c60 | 82 | } |
| dg0704 | 3:178ee1fe1c60 | 83 | else if (speedCommand == 'w') |
| dg0704 | 3:178ee1fe1c60 | 84 | { |
| dg0704 | 3:178ee1fe1c60 | 85 | v1_ref = v1_ref - 20; |
| dg0704 | 3:178ee1fe1c60 | 86 | v2_ref = v2_ref - 20; |
| dg0704 | 3:178ee1fe1c60 | 87 | } |
| dg0704 | 3:178ee1fe1c60 | 88 | |
| dg0704 | 3:178ee1fe1c60 | 89 | if (v1_ref < -100) |
| dg0704 | 3:178ee1fe1c60 | 90 | v1_ref = -100; |
| dg0704 | 3:178ee1fe1c60 | 91 | else if (v1_ref > 100) |
| winstonkuo | 7:f7d503690ea5 | 92 | v1_ref = 100; |
| dg0704 | 3:178ee1fe1c60 | 93 | |
| dg0704 | 3:178ee1fe1c60 | 94 | if (v2_ref < -100) |
| dg0704 | 3:178ee1fe1c60 | 95 | v2_ref = -100; |
| dg0704 | 3:178ee1fe1c60 | 96 | else if (v2_ref > 100) |
| dg0704 | 3:178ee1fe1c60 | 97 | v2_ref = 100; |
| dg0704 | 3:178ee1fe1c60 | 98 | } |
| YCTung | 0:0971f0666990 | 99 | } |
| YCTung | 0:0971f0666990 | 100 | } |
| YCTung | 0:0971f0666990 | 101 | |
| YCTung | 0:0971f0666990 | 102 | void timer1_interrupt(void) |
| YCTung | 0:0971f0666990 | 103 | { |
| YCTung | 0:0971f0666990 | 104 | //Motor 1 |
| YCTung | 1:6747911cdd90 | 105 | v1 = (float)v1Count * 100.0f / 12.0f * 60.0f / 29.0f; //unit: rpm |
| YCTung | 0:0971f0666990 | 106 | v1Count = 0; |
| YCTung | 0:0971f0666990 | 107 | |
| YCTung | 0:0971f0666990 | 108 | ///code for PI control/// |
| dg0704 | 3:178ee1fe1c60 | 109 | v1_err = v1_ref - v1; |
| dg0704 | 3:178ee1fe1c60 | 110 | v1_ierr += v1_err; |
| dg0704 | 3:178ee1fe1c60 | 111 | PIout_1 = Kp * v1_err + Ki * Ts * (v1_ierr - v1_err); |
| YCTung | 0:0971f0666990 | 112 | |
| dg0704 | 3:178ee1fe1c60 | 113 | // saturation |
| YCTung | 0:0971f0666990 | 114 | if(PIout_1 >= 0.5f)PIout_1 = 0.5f; |
| YCTung | 0:0971f0666990 | 115 | else if(PIout_1 <= -0.5f)PIout_1 = -0.5f; |
| YCTung | 0:0971f0666990 | 116 | pwm1.write(PIout_1 + 0.5f); |
| YCTung | 0:0971f0666990 | 117 | TIM1->CCER |= 0x4; |
| YCTung | 0:0971f0666990 | 118 | |
| dg0704 | 3:178ee1fe1c60 | 119 | PIout_1_old = PIout_1; |
| YCTung | 0:0971f0666990 | 120 | |
| YCTung | 0:0971f0666990 | 121 | //Motor 2 |
| YCTung | 1:6747911cdd90 | 122 | v2 = (float)v2Count * 100.0f / 12.0f * 60.0f / 29.0f; //unit: rpm |
| YCTung | 0:0971f0666990 | 123 | v2Count = 0; |
| YCTung | 0:0971f0666990 | 124 | |
| YCTung | 0:0971f0666990 | 125 | ///code for PI control/// |
| dg0704 | 3:178ee1fe1c60 | 126 | v2_err = v2_ref - v2; |
| dg0704 | 3:178ee1fe1c60 | 127 | v2_ierr += v2_err; |
| dg0704 | 3:178ee1fe1c60 | 128 | PIout_2 = Kp * v2_err + Ki * Ts * (v2_ierr - v2_err); |
| YCTung | 0:0971f0666990 | 129 | |
| dg0704 | 3:178ee1fe1c60 | 130 | //saturation |
| YCTung | 0:0971f0666990 | 131 | if(PIout_2 >= 0.5f)PIout_2 = 0.5f; |
| YCTung | 0:0971f0666990 | 132 | else if(PIout_2 <= -0.5f)PIout_2 = -0.5f; |
| YCTung | 0:0971f0666990 | 133 | pwm2.write(PIout_2 + 0.5f); |
| YCTung | 0:0971f0666990 | 134 | TIM1->CCER |= 0x40; |
| dg0704 | 3:178ee1fe1c60 | 135 | |
| dg0704 | 3:178ee1fe1c60 | 136 | PIout_2_old = PIout_2; |
| YCTung | 0:0971f0666990 | 137 | } |
| YCTung | 0:0971f0666990 | 138 | |
| YCTung | 0:0971f0666990 | 139 | void CN_interrupt(void) |
| YCTung | 0:0971f0666990 | 140 | { |
| YCTung | 0:0971f0666990 | 141 | //Motor 1 |
| YCTung | 0:0971f0666990 | 142 | stateA_1 = HallA_1.read(); |
| YCTung | 0:0971f0666990 | 143 | stateB_1 = HallB_1.read(); |
| YCTung | 0:0971f0666990 | 144 | |
| YCTung | 0:0971f0666990 | 145 | ///code for state determination/// |
| dg0704 | 3:178ee1fe1c60 | 146 | if (stateA_1 == 0) |
| dg0704 | 3:178ee1fe1c60 | 147 | { |
| dg0704 | 3:178ee1fe1c60 | 148 | if (stateB_1 == 0) |
| dg0704 | 3:178ee1fe1c60 | 149 | state_1 = 1; |
| dg0704 | 3:178ee1fe1c60 | 150 | else |
| winstonkuo | 7:f7d503690ea5 | 151 | state_1 = 2; |
| dg0704 | 3:178ee1fe1c60 | 152 | } |
| dg0704 | 3:178ee1fe1c60 | 153 | else |
| dg0704 | 3:178ee1fe1c60 | 154 | { |
| dg0704 | 3:178ee1fe1c60 | 155 | if (stateB_1 == 1) |
| dg0704 | 3:178ee1fe1c60 | 156 | state_1 = 3; |
| dg0704 | 3:178ee1fe1c60 | 157 | else |
| winstonkuo | 7:f7d503690ea5 | 158 | state_1 = 4; |
| dg0704 | 3:178ee1fe1c60 | 159 | } |
| YCTung | 0:0971f0666990 | 160 | |
| dg0704 | 3:178ee1fe1c60 | 161 | //Forward: v1Count +1 |
| dg0704 | 3:178ee1fe1c60 | 162 | //Inverse: v1Count -1 |
| dg0704 | 3:178ee1fe1c60 | 163 | if ( (state_1 == (state_1_old + 1)) || (state_1 == (state_1_old - 3)) ) |
| dg0704 | 3:178ee1fe1c60 | 164 | v1Count++; |
| dg0704 | 3:178ee1fe1c60 | 165 | else if ( (state_1 == (state_1_old - 1)) || (state_1 == (state_1_old + 3))) |
| dg0704 | 3:178ee1fe1c60 | 166 | v1Count--; |
| dg0704 | 3:178ee1fe1c60 | 167 | |
| dg0704 | 3:178ee1fe1c60 | 168 | state_1_old = state_1; |
| YCTung | 0:0971f0666990 | 169 | |
| YCTung | 0:0971f0666990 | 170 | //Motor 2 |
| YCTung | 0:0971f0666990 | 171 | stateA_2 = HallA_2.read(); |
| YCTung | 0:0971f0666990 | 172 | stateB_2 = HallB_2.read(); |
| YCTung | 0:0971f0666990 | 173 | |
| YCTung | 0:0971f0666990 | 174 | ///code for state determination/// |
| dg0704 | 3:178ee1fe1c60 | 175 | if (stateA_2 == 0) |
| dg0704 | 3:178ee1fe1c60 | 176 | { |
| dg0704 | 3:178ee1fe1c60 | 177 | if (stateB_2 == 0) |
| dg0704 | 3:178ee1fe1c60 | 178 | state_2 = 1; |
| dg0704 | 3:178ee1fe1c60 | 179 | else |
| winstonkuo | 7:f7d503690ea5 | 180 | state_2 = 2; |
| dg0704 | 3:178ee1fe1c60 | 181 | } |
| dg0704 | 3:178ee1fe1c60 | 182 | else |
| dg0704 | 3:178ee1fe1c60 | 183 | { |
| dg0704 | 3:178ee1fe1c60 | 184 | if (stateB_2 == 1) |
| dg0704 | 3:178ee1fe1c60 | 185 | state_2 = 3; |
| dg0704 | 3:178ee1fe1c60 | 186 | else |
| winstonkuo | 7:f7d503690ea5 | 187 | state_2 = 4; |
| dg0704 | 3:178ee1fe1c60 | 188 | } |
| YCTung | 0:0971f0666990 | 189 | |
| dg0704 | 3:178ee1fe1c60 | 190 | //Forward: v2Count +1 |
| dg0704 | 3:178ee1fe1c60 | 191 | //Inverse: v2Count -1 |
| dg0704 | 3:178ee1fe1c60 | 192 | if ( (state_2 == (state_2_old + 1)) || (state_2 == (state_2_old - 3)) ) |
| dg0704 | 3:178ee1fe1c60 | 193 | v1Count++; |
| dg0704 | 3:178ee1fe1c60 | 194 | else if ( (state_2 == (state_2_old - 1)) || (state_2 == (state_2_old + 3))) |
| dg0704 | 3:178ee1fe1c60 | 195 | v1Count--; |
| YCTung | 0:0971f0666990 | 196 | } |
| YCTung | 0:0971f0666990 | 197 | |
| YCTung | 0:0971f0666990 | 198 | void init_TIMER(void) |
| YCTung | 0:0971f0666990 | 199 | { |
| YCTung | 0:0971f0666990 | 200 | timer1.attach_us(&timer1_interrupt, 10000);//10ms interrupt period (100 Hz) |
| YCTung | 0:0971f0666990 | 201 | } |
| YCTung | 0:0971f0666990 | 202 | |
| YCTung | 0:0971f0666990 | 203 | void init_PWM(void) |
| YCTung | 0:0971f0666990 | 204 | { |
| YCTung | 0:0971f0666990 | 205 | pwm1.period_us(50); |
| YCTung | 0:0971f0666990 | 206 | pwm1.write(0.5); |
| YCTung | 0:0971f0666990 | 207 | TIM1->CCER |= 0x4; |
| YCTung | 0:0971f0666990 | 208 | |
| YCTung | 0:0971f0666990 | 209 | pwm2.period_us(50); |
| YCTung | 0:0971f0666990 | 210 | pwm2.write(0.5); |
| YCTung | 0:0971f0666990 | 211 | TIM1->CCER |= 0x40; |
| YCTung | 0:0971f0666990 | 212 | } |
| YCTung | 0:0971f0666990 | 213 | |
| YCTung | 0:0971f0666990 | 214 | void init_CN(void) |
| YCTung | 0:0971f0666990 | 215 | { |
| YCTung | 0:0971f0666990 | 216 | HallA_1.rise(&CN_interrupt); |
| YCTung | 0:0971f0666990 | 217 | HallA_1.fall(&CN_interrupt); |
| YCTung | 0:0971f0666990 | 218 | HallB_1.rise(&CN_interrupt); |
| YCTung | 0:0971f0666990 | 219 | HallB_1.fall(&CN_interrupt); |
| YCTung | 0:0971f0666990 | 220 | |
| YCTung | 0:0971f0666990 | 221 | HallA_2.rise(&CN_interrupt); |
| YCTung | 0:0971f0666990 | 222 | HallA_2.fall(&CN_interrupt); |
| YCTung | 0:0971f0666990 | 223 | HallB_2.rise(&CN_interrupt); |
| YCTung | 0:0971f0666990 | 224 | HallB_2.fall(&CN_interrupt); |
| YCTung | 0:0971f0666990 | 225 | |
| YCTung | 0:0971f0666990 | 226 | stateA_1 = HallA_1.read(); |
| YCTung | 0:0971f0666990 | 227 | stateB_1 = HallB_1.read(); |
| YCTung | 0:0971f0666990 | 228 | stateA_2 = HallA_2.read(); |
| YCTung | 0:0971f0666990 | 229 | stateB_2 = HallB_2.read(); |
| YCTung | 0:0971f0666990 | 230 | } |
