No.9 Robotics / Mbed 2 deprecated Robotics_DCMotor

Dependencies:   mbed

Fork of Robotics_Lab_DCMotor by LDSC_Robotics

Committer:
dg0704
Date:
Wed Apr 13 09:07:29 2016 +0000
Revision:
3:178ee1fe1c60
Parent:
2:4d048af437fe
Child:
4:04702de80697
Child:
7:f7d503690ea5
ting yu

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)
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 Serial pc(D1, D0);
YCTung 0:0971f0666990 29
YCTung 0:0971f0666990 30 Ticker timer1;
YCTung 0:0971f0666990 31 void timer1_interrupt(void);
YCTung 0:0971f0666990 32 void CN_interrupt(void);
YCTung 0:0971f0666990 33
YCTung 0:0971f0666990 34 void init_TIMER(void);
YCTung 0:0971f0666990 35 void init_PWM(void);
YCTung 0:0971f0666990 36 void init_CN(void);
YCTung 0:0971f0666990 37
YCTung 0:0971f0666990 38 int8_t stateA_1=0, stateB_1=0, stateA_2=0, stateB_2=0;
YCTung 0:0971f0666990 39 int8_t state_1 = 0, state_1_old = 0, state_2 = 0, state_2_old = 0;
YCTung 0:0971f0666990 40
YCTung 0:0971f0666990 41 int v1Count = 0;
YCTung 0:0971f0666990 42 int v2Count = 0;
YCTung 0:0971f0666990 43
YCTung 0:0971f0666990 44 float v1 = 0.0, v1_ref = 0.0;
YCTung 0:0971f0666990 45 float v1_err = 0.0, v1_ierr = 0.0, PIout_1 = 0.0, PIout_1_old = 0.0;
YCTung 0:0971f0666990 46 float v2 = 0.0, v2_ref = 0.0;
YCTung 0:0971f0666990 47 float v2_err = 0.0, v2_ierr = 0.0, PIout_2 = 0.0, PIout_2_old = 0.0;
YCTung 0:0971f0666990 48
YCTung 0:0971f0666990 49 int main() {
YCTung 0:0971f0666990 50
dg0704 3:178ee1fe1c60 51 bluetooth.baud(115200);
dg0704 3:178ee1fe1c60 52 pc.baud(57600);
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 {
dg0704 3:178ee1fe1c60 69 angle = bluetooth.getc();
dg0704 3:178ee1fe1c60 70 pc.putc(speedCommand);
dg0704 3:178ee1fe1c60 71
dg0704 3:178ee1fe1c60 72 if (speedCommand == 'a')
dg0704 3:178ee1fe1c60 73 {
dg0704 3:178ee1fe1c60 74 v1_ref = v1_ref + 10;
dg0704 3:178ee1fe1c60 75 v2_ref = v2_ref + 10;
dg0704 3:178ee1fe1c60 76 }
dg0704 3:178ee1fe1c60 77 else if (speedCommand == 's')
dg0704 3:178ee1fe1c60 78 {
dg0704 3:178ee1fe1c60 79 v1_ref = v1_ref - 10;
dg0704 3:178ee1fe1c60 80 v2_ref = v2_ref - 10;
dg0704 3:178ee1fe1c60 81 }
dg0704 3:178ee1fe1c60 82 else if (speedCommand == 'q')
dg0704 3:178ee1fe1c60 83 {
dg0704 3:178ee1fe1c60 84 v1_ref = v1_ref + 20;
dg0704 3:178ee1fe1c60 85 v2_ref = v2_ref + 20;
dg0704 3:178ee1fe1c60 86 }
dg0704 3:178ee1fe1c60 87 else if (speedCommand == 'w')
dg0704 3:178ee1fe1c60 88 {
dg0704 3:178ee1fe1c60 89 v1_ref = v1_ref - 20;
dg0704 3:178ee1fe1c60 90 v2_ref = v2_ref - 20;
dg0704 3:178ee1fe1c60 91 }
dg0704 3:178ee1fe1c60 92
dg0704 3:178ee1fe1c60 93 if (v1_ref < -100)
dg0704 3:178ee1fe1c60 94 v1_ref = -100;
dg0704 3:178ee1fe1c60 95 else if (v1_ref > 100)
dg0704 3:178ee1fe1c60 96 v1_ref = 100
dg0704 3:178ee1fe1c60 97
dg0704 3:178ee1fe1c60 98 if (v2_ref < -100)
dg0704 3:178ee1fe1c60 99 v2_ref = -100;
dg0704 3:178ee1fe1c60 100 else if (v2_ref > 100)
dg0704 3:178ee1fe1c60 101 v2_ref = 100;
dg0704 3:178ee1fe1c60 102 }
YCTung 0:0971f0666990 103 }
YCTung 0:0971f0666990 104 }
YCTung 0:0971f0666990 105
YCTung 0:0971f0666990 106 void timer1_interrupt(void)
YCTung 0:0971f0666990 107 {
YCTung 0:0971f0666990 108 //Motor 1
YCTung 1:6747911cdd90 109 v1 = (float)v1Count * 100.0f / 12.0f * 60.0f / 29.0f; //unit: rpm
YCTung 0:0971f0666990 110 v1Count = 0;
YCTung 0:0971f0666990 111
YCTung 0:0971f0666990 112 ///code for PI control///
dg0704 3:178ee1fe1c60 113 v1_err = v1_ref - v1;
dg0704 3:178ee1fe1c60 114 v1_ierr += v1_err;
dg0704 3:178ee1fe1c60 115 PIout_1 = Kp * v1_err + Ki * Ts * (v1_ierr - v1_err);
YCTung 0:0971f0666990 116
dg0704 3:178ee1fe1c60 117 // saturation
YCTung 0:0971f0666990 118 if(PIout_1 >= 0.5f)PIout_1 = 0.5f;
YCTung 0:0971f0666990 119 else if(PIout_1 <= -0.5f)PIout_1 = -0.5f;
YCTung 0:0971f0666990 120 pwm1.write(PIout_1 + 0.5f);
YCTung 0:0971f0666990 121 TIM1->CCER |= 0x4;
YCTung 0:0971f0666990 122
dg0704 3:178ee1fe1c60 123 PIout_1_old = PIout_1;
YCTung 0:0971f0666990 124
YCTung 0:0971f0666990 125 //Motor 2
YCTung 1:6747911cdd90 126 v2 = (float)v2Count * 100.0f / 12.0f * 60.0f / 29.0f; //unit: rpm
YCTung 0:0971f0666990 127 v2Count = 0;
YCTung 0:0971f0666990 128
YCTung 0:0971f0666990 129 ///code for PI control///
dg0704 3:178ee1fe1c60 130 v2_err = v2_ref - v2;
dg0704 3:178ee1fe1c60 131 v2_ierr += v2_err;
dg0704 3:178ee1fe1c60 132 PIout_2 = Kp * v2_err + Ki * Ts * (v2_ierr - v2_err);
YCTung 0:0971f0666990 133
dg0704 3:178ee1fe1c60 134 //saturation
YCTung 0:0971f0666990 135 if(PIout_2 >= 0.5f)PIout_2 = 0.5f;
YCTung 0:0971f0666990 136 else if(PIout_2 <= -0.5f)PIout_2 = -0.5f;
YCTung 0:0971f0666990 137 pwm2.write(PIout_2 + 0.5f);
YCTung 0:0971f0666990 138 TIM1->CCER |= 0x40;
dg0704 3:178ee1fe1c60 139
dg0704 3:178ee1fe1c60 140 PIout_2_old = PIout_2;
YCTung 0:0971f0666990 141 }
YCTung 0:0971f0666990 142
YCTung 0:0971f0666990 143 void CN_interrupt(void)
YCTung 0:0971f0666990 144 {
YCTung 0:0971f0666990 145 //Motor 1
YCTung 0:0971f0666990 146 stateA_1 = HallA_1.read();
YCTung 0:0971f0666990 147 stateB_1 = HallB_1.read();
YCTung 0:0971f0666990 148
YCTung 0:0971f0666990 149 ///code for state determination///
dg0704 3:178ee1fe1c60 150 if (stateA_1 == 0)
dg0704 3:178ee1fe1c60 151 {
dg0704 3:178ee1fe1c60 152 if (stateB_1 == 0)
dg0704 3:178ee1fe1c60 153 state_1 = 1;
dg0704 3:178ee1fe1c60 154 else
dg0704 3:178ee1fe1c60 155 stete_1 = 2;
dg0704 3:178ee1fe1c60 156 }
dg0704 3:178ee1fe1c60 157 else
dg0704 3:178ee1fe1c60 158 {
dg0704 3:178ee1fe1c60 159 if (stateB_1 == 1)
dg0704 3:178ee1fe1c60 160 state_1 = 3;
dg0704 3:178ee1fe1c60 161 else
dg0704 3:178ee1fe1c60 162 stete_1 = 4;
dg0704 3:178ee1fe1c60 163 }
YCTung 0:0971f0666990 164
dg0704 3:178ee1fe1c60 165 //Forward: v1Count +1
dg0704 3:178ee1fe1c60 166 //Inverse: v1Count -1
dg0704 3:178ee1fe1c60 167 if ( (state_1 == (state_1_old + 1)) || (state_1 == (state_1_old - 3)) )
dg0704 3:178ee1fe1c60 168 v1Count++;
dg0704 3:178ee1fe1c60 169 else if ( (state_1 == (state_1_old - 1)) || (state_1 == (state_1_old + 3)))
dg0704 3:178ee1fe1c60 170 v1Count--;
dg0704 3:178ee1fe1c60 171
dg0704 3:178ee1fe1c60 172 state_1_old = state_1;
YCTung 0:0971f0666990 173
YCTung 0:0971f0666990 174 //Motor 2
YCTung 0:0971f0666990 175 stateA_2 = HallA_2.read();
YCTung 0:0971f0666990 176 stateB_2 = HallB_2.read();
YCTung 0:0971f0666990 177
YCTung 0:0971f0666990 178 ///code for state determination///
dg0704 3:178ee1fe1c60 179 if (stateA_2 == 0)
dg0704 3:178ee1fe1c60 180 {
dg0704 3:178ee1fe1c60 181 if (stateB_2 == 0)
dg0704 3:178ee1fe1c60 182 state_2 = 1;
dg0704 3:178ee1fe1c60 183 else
dg0704 3:178ee1fe1c60 184 stete_2 = 2;
dg0704 3:178ee1fe1c60 185 }
dg0704 3:178ee1fe1c60 186 else
dg0704 3:178ee1fe1c60 187 {
dg0704 3:178ee1fe1c60 188 if (stateB_2 == 1)
dg0704 3:178ee1fe1c60 189 state_2 = 3;
dg0704 3:178ee1fe1c60 190 else
dg0704 3:178ee1fe1c60 191 stete_2 = 4;
dg0704 3:178ee1fe1c60 192 }
YCTung 0:0971f0666990 193
dg0704 3:178ee1fe1c60 194 //Forward: v2Count +1
dg0704 3:178ee1fe1c60 195 //Inverse: v2Count -1
dg0704 3:178ee1fe1c60 196 if ( (state_2 == (state_2_old + 1)) || (state_2 == (state_2_old - 3)) )
dg0704 3:178ee1fe1c60 197 v1Count++;
dg0704 3:178ee1fe1c60 198 else if ( (state_2 == (state_2_old - 1)) || (state_2 == (state_2_old + 3)))
dg0704 3:178ee1fe1c60 199 v1Count--;
YCTung 0:0971f0666990 200 }
YCTung 0:0971f0666990 201
YCTung 0:0971f0666990 202 void init_TIMER(void)
YCTung 0:0971f0666990 203 {
YCTung 0:0971f0666990 204 timer1.attach_us(&timer1_interrupt, 10000);//10ms interrupt period (100 Hz)
YCTung 0:0971f0666990 205 }
YCTung 0:0971f0666990 206
YCTung 0:0971f0666990 207 void init_PWM(void)
YCTung 0:0971f0666990 208 {
YCTung 0:0971f0666990 209 pwm1.period_us(50);
YCTung 0:0971f0666990 210 pwm1.write(0.5);
YCTung 0:0971f0666990 211 TIM1->CCER |= 0x4;
YCTung 0:0971f0666990 212
YCTung 0:0971f0666990 213 pwm2.period_us(50);
YCTung 0:0971f0666990 214 pwm2.write(0.5);
YCTung 0:0971f0666990 215 TIM1->CCER |= 0x40;
YCTung 0:0971f0666990 216 }
YCTung 0:0971f0666990 217
YCTung 0:0971f0666990 218 void init_CN(void)
YCTung 0:0971f0666990 219 {
YCTung 0:0971f0666990 220 HallA_1.rise(&CN_interrupt);
YCTung 0:0971f0666990 221 HallA_1.fall(&CN_interrupt);
YCTung 0:0971f0666990 222 HallB_1.rise(&CN_interrupt);
YCTung 0:0971f0666990 223 HallB_1.fall(&CN_interrupt);
YCTung 0:0971f0666990 224
YCTung 0:0971f0666990 225 HallA_2.rise(&CN_interrupt);
YCTung 0:0971f0666990 226 HallA_2.fall(&CN_interrupt);
YCTung 0:0971f0666990 227 HallB_2.rise(&CN_interrupt);
YCTung 0:0971f0666990 228 HallB_2.fall(&CN_interrupt);
YCTung 0:0971f0666990 229
YCTung 0:0971f0666990 230 stateA_1 = HallA_1.read();
YCTung 0:0971f0666990 231 stateB_1 = HallB_1.read();
YCTung 0:0971f0666990 232 stateA_2 = HallA_2.read();
YCTung 0:0971f0666990 233 stateB_2 = HallB_2.read();
YCTung 0:0971f0666990 234 }