AECL 601
/
3Wtest_1_Chap3fmt_squ_0813
Chap 3
main.cpp@1:6b405e5f18ef, 2017-07-12 (annotated)
- Committer:
- xx123456987
- Date:
- Wed Jul 12 10:48:13 2017 +0000
- Revision:
- 1:6b405e5f18ef
- Parent:
- 0:f0f040a29912
Chapter3
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
xx123456987 | 0:f0f040a29912 | 1 | /* 版本說明: 正方形軌跡追蹤(從邊緣出發)邊長3m |
xx123456987 | 0:f0f040a29912 | 2 | 實驗說明: |
xx123456987 | 1:6b405e5f18ef | 3 | 增加sgn項,且dt修正為0.11秒 |
xx123456987 | 0:f0f040a29912 | 4 | |
xx123456987 | 1:6b405e5f18ef | 5 | 08/13測試紀錄: |
xx123456987 | 1:6b405e5f18ef | 6 | 可順利運轉,且有記錄結果,但應該不是正確的(非動態模型結果)。 |
xx123456987 | 0:f0f040a29912 | 7 | |
xx123456987 | 0:f0f040a29912 | 8 | */ |
xx123456987 | 0:f0f040a29912 | 9 | #include "mbed.h" |
xx123456987 | 0:f0f040a29912 | 10 | #include "math.h" |
xx123456987 | 0:f0f040a29912 | 11 | #include "QEI.h" |
xx123456987 | 0:f0f040a29912 | 12 | // pre-define |
xx123456987 | 0:f0f040a29912 | 13 | #define pi 3.1416 |
xx123456987 | 0:f0f040a29912 | 14 | #define pwm_period_us 500 |
xx123456987 | 0:f0f040a29912 | 15 | #define r 0.05 // wheel radius [m] |
xx123456987 | 0:f0f040a29912 | 16 | #define L 0.125 // distance between wheel center & geometric center [m] |
xx123456987 | 0:f0f040a29912 | 17 | #define pulsesPerRev 1024 |
xx123456987 | 0:f0f040a29912 | 18 | #define kp 0.7// p gain |
xx123456987 | 0:f0f040a29912 | 19 | #define kd 0.03// d gain |
xx123456987 | 1:6b405e5f18ef | 20 | #define ksgn 0.001// sgn term gain |
xx123456987 | 0:f0f040a29912 | 21 | // leader initial pose |
xx123456987 | 0:f0f040a29912 | 22 | #define x0 0 //[m] |
xx123456987 | 0:f0f040a29912 | 23 | #define y0 0 //[m] |
xx123456987 | 0:f0f040a29912 | 24 | #define theta0 0//[deg.] |
xx123456987 | 0:f0f040a29912 | 25 | // desied pose |
xx123456987 | 0:f0f040a29912 | 26 | #define xd 0 //[cm] |
xx123456987 | 0:f0f040a29912 | 27 | #define yd 0 //[cm] |
xx123456987 | 0:f0f040a29912 | 28 | #define thetad 0//[deg.] |
xx123456987 | 0:f0f040a29912 | 29 | // error threshold |
xx123456987 | 0:f0f040a29912 | 30 | #define ex 0.02 //[m] |
xx123456987 | 0:f0f040a29912 | 31 | #define ey 0.02 //[m] |
xx123456987 | 0:f0f040a29912 | 32 | #define etheta 3//[deg.] |
xx123456987 | 0:f0f040a29912 | 33 | |
xx123456987 | 0:f0f040a29912 | 34 | PwmOut pwm_1(D9); |
xx123456987 | 0:f0f040a29912 | 35 | PwmOut pwm_2(D10); |
xx123456987 | 0:f0f040a29912 | 36 | PwmOut pwm_3(D11); |
xx123456987 | 0:f0f040a29912 | 37 | |
xx123456987 | 0:f0f040a29912 | 38 | Timer clk; |
xx123456987 | 0:f0f040a29912 | 39 | |
xx123456987 | 0:f0f040a29912 | 40 | // define |
xx123456987 | 0:f0f040a29912 | 41 | QEI w1 (D2, D3, NC, pulsesPerRev, QEI::X4_ENCODING); |
xx123456987 | 0:f0f040a29912 | 42 | QEI w2 (D4, D5, NC, pulsesPerRev, QEI::X4_ENCODING); |
xx123456987 | 0:f0f040a29912 | 43 | QEI w3 (D14, D15, NC, pulsesPerRev, QEI::X4_ENCODING); |
xx123456987 | 0:f0f040a29912 | 44 | // formation para. |
xx123456987 | 0:f0f040a29912 | 45 | //float x=14.43; |
xx123456987 | 0:f0f040a29912 | 46 | float f1[3] = {0,1.5,0}; // formation vector |
xx123456987 | 0:f0f040a29912 | 47 | // odomerty para. |
xx123456987 | 0:f0f040a29912 | 48 | float c1 = r/(3*L), c2 = 2*r/3; |
xx123456987 | 0:f0f040a29912 | 49 | float Current_X[3] = {x0+f1[0],y0+f1[1],((theta0+f1[2])*pi/180)+pi/3}; // X[0] = x; X[1] = y; X[2] = theta; shift pi/3 : origin to new |
xx123456987 | 0:f0f040a29912 | 50 | float Next_X[3] = {0,0,0}; |
xx123456987 | 0:f0f040a29912 | 51 | double d_theta1,d_theta2,d_theta3,d_theta; |
xx123456987 | 0:f0f040a29912 | 52 | int qei1_new, qei2_new, qei3_new, qei1_old, qei2_old, qei3_old; |
xx123456987 | 0:f0f040a29912 | 53 | // control law para. |
xx123456987 | 0:f0f040a29912 | 54 | |
xx123456987 | 0:f0f040a29912 | 55 | float X1[3],V1[3],Vc[3],X1_b[3];// X1_b(X_BAR) is defined as X1-f1 |
xx123456987 | 0:f0f040a29912 | 56 | float XL[3];// = {xd,yd,(thetad*pi/180)+pi/3};// pose of virtual leader [m m rad.] |
xx123456987 | 0:f0f040a29912 | 57 | float u[3] = {0};// control law |
xx123456987 | 0:f0f040a29912 | 58 | float omg1,omg2,omg3;// velocity of wheels |
xx123456987 | 0:f0f040a29912 | 59 | // PWM |
xx123456987 | 0:f0f040a29912 | 60 | float pwm_w1,pwm_w2,pwm_w3; |
xx123456987 | 0:f0f040a29912 | 61 | // Differential |
xx123456987 | 0:f0f040a29912 | 62 | float dy,dx,dtheta; |
xx123456987 | 1:6b405e5f18ef | 63 | float dt = 0.11; |
xx123456987 | 0:f0f040a29912 | 64 | // V command |
xx123456987 | 0:f0f040a29912 | 65 | float t1 = 7.5;//2*3.75 |
xx123456987 | 0:f0f040a29912 | 66 | float T = 22.5;//6*3.75 |
xx123456987 | 0:f0f040a29912 | 67 | float S = 3.0;//0.8*3.75 |
xx123456987 | 0:f0f040a29912 | 68 | // Others |
xx123456987 | 0:f0f040a29912 | 69 | DigitalIn mybutton(USER_BUTTON); |
xx123456987 | 0:f0f040a29912 | 70 | DigitalOut myled(LED1); |
xx123456987 | 0:f0f040a29912 | 71 | int c = 3; |
xx123456987 | 0:f0f040a29912 | 72 | int xdir,ydir; // x y direction |
xx123456987 | 0:f0f040a29912 | 73 | float err[3]= {0}; |
xx123456987 | 0:f0f040a29912 | 74 | //bool s0 = false; |
xx123456987 | 0:f0f040a29912 | 75 | bool s0 = true; |
xx123456987 | 0:f0f040a29912 | 76 | bool stop = false; |
xx123456987 | 0:f0f040a29912 | 77 | char gosw = true; |
xx123456987 | 0:f0f040a29912 | 78 | int sw = 13; |
xx123456987 | 0:f0f040a29912 | 79 | float xL0,yL0;// initial position of leader |
xx123456987 | 0:f0f040a29912 | 80 | char kb='p'; |
xx123456987 | 0:f0f040a29912 | 81 | |
xx123456987 | 1:6b405e5f18ef | 82 | int sgn(float); |
xx123456987 | 1:6b405e5f18ef | 83 | |
xx123456987 | 0:f0f040a29912 | 84 | int main() |
xx123456987 | 0:f0f040a29912 | 85 | { |
xx123456987 | 0:f0f040a29912 | 86 | pwm_1.period_us(pwm_period_us); |
xx123456987 | 0:f0f040a29912 | 87 | pwm_2.period_us(pwm_period_us); |
xx123456987 | 0:f0f040a29912 | 88 | pwm_3.period_us(pwm_period_us); |
xx123456987 | 0:f0f040a29912 | 89 | |
xx123456987 | 0:f0f040a29912 | 90 | pwm_1.write(0.50); |
xx123456987 | 0:f0f040a29912 | 91 | pwm_2.write(0.50); |
xx123456987 | 0:f0f040a29912 | 92 | pwm_3.write(0.50); |
xx123456987 | 0:f0f040a29912 | 93 | |
xx123456987 | 0:f0f040a29912 | 94 | qei1_old = 0; |
xx123456987 | 0:f0f040a29912 | 95 | qei2_old = 0; |
xx123456987 | 0:f0f040a29912 | 96 | qei3_old = 0; |
xx123456987 | 0:f0f040a29912 | 97 | printf("3W_1_fmt_squ_0717\n"); |
xx123456987 | 0:f0f040a29912 | 98 | printf("Press any key to START\n"); |
xx123456987 | 0:f0f040a29912 | 99 | |
xx123456987 | 0:f0f040a29912 | 100 | while (kb=='p') { |
xx123456987 | 0:f0f040a29912 | 101 | scanf("%c",&kb); |
xx123456987 | 0:f0f040a29912 | 102 | } |
xx123456987 | 0:f0f040a29912 | 103 | |
xx123456987 | 0:f0f040a29912 | 104 | //if (s0 == ture) |
xx123456987 | 0:f0f040a29912 | 105 | s0 = true; |
xx123456987 | 0:f0f040a29912 | 106 | /* |
xx123456987 | 0:f0f040a29912 | 107 | while(c>0) { |
xx123456987 | 0:f0f040a29912 | 108 | wait(1); |
xx123456987 | 0:f0f040a29912 | 109 | c--; |
xx123456987 | 0:f0f040a29912 | 110 | myled = !myled; |
xx123456987 | 0:f0f040a29912 | 111 | } |
xx123456987 | 0:f0f040a29912 | 112 | */ |
xx123456987 | 0:f0f040a29912 | 113 | xL0=0.0;// dire. 9 |
xx123456987 | 0:f0f040a29912 | 114 | yL0=0.0; |
xx123456987 | 0:f0f040a29912 | 115 | //clk.reset(); |
xx123456987 | 0:f0f040a29912 | 116 | clk.start(); |
xx123456987 | 0:f0f040a29912 | 117 | while(1) { |
xx123456987 | 0:f0f040a29912 | 118 | // |
xx123456987 | 0:f0f040a29912 | 119 | myled = 0; |
xx123456987 | 0:f0f040a29912 | 120 | X1[0] = Current_X[0]; |
xx123456987 | 0:f0f040a29912 | 121 | X1[1] = Current_X[1]; |
xx123456987 | 0:f0f040a29912 | 122 | X1[2] = Current_X[2]; |
xx123456987 | 0:f0f040a29912 | 123 | |
xx123456987 | 0:f0f040a29912 | 124 | // P&V command 1→3→9→7→1 |
xx123456987 | 0:f0f040a29912 | 125 | if(s0==true) { |
xx123456987 | 0:f0f040a29912 | 126 | if(gosw==true) { |
xx123456987 | 0:f0f040a29912 | 127 | switch (sw) { |
xx123456987 | 0:f0f040a29912 | 128 | case 97: |
xx123456987 | 0:f0f040a29912 | 129 | xdir=-1; |
xx123456987 | 0:f0f040a29912 | 130 | ydir=0; |
xx123456987 | 0:f0f040a29912 | 131 | sw=71; |
xx123456987 | 0:f0f040a29912 | 132 | break; |
xx123456987 | 0:f0f040a29912 | 133 | case 71: |
xx123456987 | 0:f0f040a29912 | 134 | xdir=0; |
xx123456987 | 0:f0f040a29912 | 135 | ydir=-1; |
xx123456987 | 0:f0f040a29912 | 136 | sw=13; |
xx123456987 | 0:f0f040a29912 | 137 | break; |
xx123456987 | 0:f0f040a29912 | 138 | case 13: |
xx123456987 | 0:f0f040a29912 | 139 | xdir=1; |
xx123456987 | 0:f0f040a29912 | 140 | ydir=0; |
xx123456987 | 0:f0f040a29912 | 141 | sw=39; |
xx123456987 | 0:f0f040a29912 | 142 | break; |
xx123456987 | 0:f0f040a29912 | 143 | case 39: |
xx123456987 | 0:f0f040a29912 | 144 | xdir=0; |
xx123456987 | 0:f0f040a29912 | 145 | ydir=1; |
xx123456987 | 0:f0f040a29912 | 146 | sw=97; |
xx123456987 | 0:f0f040a29912 | 147 | stop=true; |
xx123456987 | 0:f0f040a29912 | 148 | break; |
xx123456987 | 0:f0f040a29912 | 149 | default: |
xx123456987 | 0:f0f040a29912 | 150 | printf("err."); |
xx123456987 | 0:f0f040a29912 | 151 | } |
xx123456987 | 0:f0f040a29912 | 152 | } |
xx123456987 | 0:f0f040a29912 | 153 | gosw=false; |
xx123456987 | 0:f0f040a29912 | 154 | clk.start(); |
xx123456987 | 0:f0f040a29912 | 155 | if(clk.read()<t1) {//1 |
xx123456987 | 0:f0f040a29912 | 156 | Vc[0]=(2*clk.read()/75)*xdir; |
xx123456987 | 0:f0f040a29912 | 157 | Vc[1]=(2*clk.read()/75)*ydir; |
xx123456987 | 0:f0f040a29912 | 158 | Vc[2]=0; |
xx123456987 | 0:f0f040a29912 | 159 | // |
xx123456987 | 0:f0f040a29912 | 160 | XL[0]=xL0 + (clk.read()*clk.read()/75)*xdir;// go to target |
xx123456987 | 0:f0f040a29912 | 161 | XL[1]=yL0 + (clk.read()*clk.read()/75)*ydir; |
xx123456987 | 0:f0f040a29912 | 162 | XL[2]=0+pi/3; |
xx123456987 | 0:f0f040a29912 | 163 | } else if(clk.read()>t1 && clk.read()<(T-t1) ) {//2 |
xx123456987 | 0:f0f040a29912 | 164 | Vc[0]=0.2*xdir; |
xx123456987 | 0:f0f040a29912 | 165 | Vc[1]=0.2*ydir; |
xx123456987 | 0:f0f040a29912 | 166 | Vc[2]=0; |
xx123456987 | 0:f0f040a29912 | 167 | // |
xx123456987 | 0:f0f040a29912 | 168 | XL[0]=xL0 + (clk.read()/5 - 0.75)*xdir; |
xx123456987 | 0:f0f040a29912 | 169 | XL[1]=yL0 + (clk.read()/5 - 0.75)*ydir; |
xx123456987 | 0:f0f040a29912 | 170 | XL[2]=0+pi/3; |
xx123456987 | 0:f0f040a29912 | 171 | } else if (clk.read()>T) {//4 |
xx123456987 | 0:f0f040a29912 | 172 | Vc[0]=0; |
xx123456987 | 0:f0f040a29912 | 173 | Vc[1]=0; |
xx123456987 | 0:f0f040a29912 | 174 | Vc[2]=0; |
xx123456987 | 0:f0f040a29912 | 175 | // |
xx123456987 | 0:f0f040a29912 | 176 | XL[0]=xL0+S*xdir; |
xx123456987 | 0:f0f040a29912 | 177 | XL[1]=yL0+S*ydir; |
xx123456987 | 0:f0f040a29912 | 178 | XL[2]=0+pi/3; |
xx123456987 | 0:f0f040a29912 | 179 | clk.reset(); |
xx123456987 | 0:f0f040a29912 | 180 | xL0=XL[0]; |
xx123456987 | 0:f0f040a29912 | 181 | yL0=XL[1]; |
xx123456987 | 0:f0f040a29912 | 182 | gosw=true; |
xx123456987 | 0:f0f040a29912 | 183 | } else {//3 |
xx123456987 | 0:f0f040a29912 | 184 | Vc[0]=(0.6-2*clk.read()/75)*xdir; |
xx123456987 | 0:f0f040a29912 | 185 | Vc[1]=(0.6-2*clk.read()/75)*ydir; |
xx123456987 | 0:f0f040a29912 | 186 | Vc[2]=0; |
xx123456987 | 0:f0f040a29912 | 187 | // |
xx123456987 | 0:f0f040a29912 | 188 | XL[0]=xL0 + (-((2*clk.read()/75 - 0.8)*(clk.read() - 15))/2 + 2.25)*xdir; |
xx123456987 | 0:f0f040a29912 | 189 | XL[1]=yL0 + (-((2*clk.read()/75 - 0.8)*(clk.read() - 15))/2 + 2.25)*ydir; |
xx123456987 | 0:f0f040a29912 | 190 | XL[2]=0+pi/3; |
xx123456987 | 0:f0f040a29912 | 191 | } |
xx123456987 | 0:f0f040a29912 | 192 | } |
xx123456987 | 0:f0f040a29912 | 193 | //printf("% .2f|% .2f|%f|X V cmd(xdire)\n", XL[0]*100, Vc[0]*100, clk.read()); |
xx123456987 | 0:f0f040a29912 | 194 | |
xx123456987 | 0:f0f040a29912 | 195 | // odometry beginning // |
xx123456987 | 0:f0f040a29912 | 196 | qei1_new = w1.getPulses(); |
xx123456987 | 0:f0f040a29912 | 197 | qei2_new = w2.getPulses(); |
xx123456987 | 0:f0f040a29912 | 198 | qei3_new = w3.getPulses(); |
xx123456987 | 0:f0f040a29912 | 199 | |
xx123456987 | 0:f0f040a29912 | 200 | double qei1 = qei1_new - qei1_old; |
xx123456987 | 0:f0f040a29912 | 201 | double qei2 = qei2_new - qei2_old; |
xx123456987 | 0:f0f040a29912 | 202 | double qei3 = qei3_new - qei3_old; |
xx123456987 | 0:f0f040a29912 | 203 | |
xx123456987 | 0:f0f040a29912 | 204 | //wait_ms(50); |
xx123456987 | 0:f0f040a29912 | 205 | |
xx123456987 | 0:f0f040a29912 | 206 | d_theta1 = qei1*360*pi/(4096*6*180); //DEG to RAD |
xx123456987 | 0:f0f040a29912 | 207 | d_theta2 = qei2*360*pi/(4096*6*180); |
xx123456987 | 0:f0f040a29912 | 208 | d_theta3 = qei3*360*pi/(4096*6*180); |
xx123456987 | 0:f0f040a29912 | 209 | d_theta = c1*( d_theta1 + d_theta2 + d_theta3 ); |
xx123456987 | 0:f0f040a29912 | 210 | |
xx123456987 | 0:f0f040a29912 | 211 | // compute theta |
xx123456987 | 0:f0f040a29912 | 212 | Next_X[2] = Current_X[2] + d_theta; |
xx123456987 | 0:f0f040a29912 | 213 | double theta = Current_X[2]; |
xx123456987 | 0:f0f040a29912 | 214 | float c3 = Current_X[2] + d_theta/2; |
xx123456987 | 0:f0f040a29912 | 215 | // compute y |
xx123456987 | 0:f0f040a29912 | 216 | Next_X[1] = Current_X[1] + c2*(+d_theta1*cos(c3)-d_theta2*cos(pi/3-c3)-d_theta3*cos(pi/3+c3)); |
xx123456987 | 0:f0f040a29912 | 217 | // compute x |
xx123456987 | 0:f0f040a29912 | 218 | Next_X[0] = Current_X[0] + c2*(-d_theta1*sin(c3)-d_theta2*sin(pi/3-c3)+d_theta3*sin(pi/3+c3)); |
xx123456987 | 0:f0f040a29912 | 219 | |
xx123456987 | 0:f0f040a29912 | 220 | // compute velocity |
xx123456987 | 0:f0f040a29912 | 221 | dx =Next_X[0]-Current_X[0]; |
xx123456987 | 0:f0f040a29912 | 222 | dy =Next_X[1]-Current_X[1]; |
xx123456987 | 0:f0f040a29912 | 223 | dtheta =Next_X[2]-Current_X[2]; |
xx123456987 | 0:f0f040a29912 | 224 | V1[0]=dx/dt; |
xx123456987 | 0:f0f040a29912 | 225 | V1[1]=dy/dt; |
xx123456987 | 0:f0f040a29912 | 226 | V1[2]=dtheta/dt; |
xx123456987 | 0:f0f040a29912 | 227 | // transition |
xx123456987 | 0:f0f040a29912 | 228 | Current_X[2] = Next_X[2]; |
xx123456987 | 0:f0f040a29912 | 229 | Current_X[1] = Next_X[1]; |
xx123456987 | 0:f0f040a29912 | 230 | Current_X[0] = Next_X[0]; |
xx123456987 | 0:f0f040a29912 | 231 | |
xx123456987 | 0:f0f040a29912 | 232 | |
xx123456987 | 0:f0f040a29912 | 233 | qei1_old = qei1_new; |
xx123456987 | 0:f0f040a29912 | 234 | qei2_old = qei2_new; |
xx123456987 | 0:f0f040a29912 | 235 | qei3_old = qei3_new; |
xx123456987 | 0:f0f040a29912 | 236 | // odometry end // |
xx123456987 | 0:f0f040a29912 | 237 | |
xx123456987 | 0:f0f040a29912 | 238 | |
xx123456987 | 0:f0f040a29912 | 239 | //printf ("% .1f|% .1f|% .1f|%f|Vc\n", Vc[0]*100, Vc[1]*100, Vc[2]*180/pi,clk.read()); |
xx123456987 | 0:f0f040a29912 | 240 | // control law beginning // |
xx123456987 | 0:f0f040a29912 | 241 | //#define r 0.05 |
xx123456987 | 0:f0f040a29912 | 242 | //#define L 0.125 |
xx123456987 | 0:f0f040a29912 | 243 | X1_b[0] = X1[0]-f1[0]; |
xx123456987 | 0:f0f040a29912 | 244 | X1_b[1] = X1[1]-f1[1]; |
xx123456987 | 0:f0f040a29912 | 245 | X1_b[2] = X1[2]-f1[2]; |
xx123456987 | 0:f0f040a29912 | 246 | |
xx123456987 | 1:6b405e5f18ef | 247 | u[0] = -kp*(X1_b[0]-XL[0])-kd*(V1[0]-Vc[0])-ksgn*sgn(V1[0]-Vc[0]); |
xx123456987 | 1:6b405e5f18ef | 248 | u[1] = -kp*(X1_b[1]-XL[1])-kd*(V1[1]-Vc[1])-ksgn*sgn(V1[1]-Vc[1]); |
xx123456987 | 1:6b405e5f18ef | 249 | u[2] = -kp*(X1_b[2]-XL[2])-kd*(V1[2]-Vc[2])-ksgn*sgn(V1[2]-Vc[2]); |
xx123456987 | 1:6b405e5f18ef | 250 | |
xx123456987 | 0:f0f040a29912 | 251 | omg1 = (5*u[2])/2 + 20*u[1]*cos(theta) - 20*u[0]*sin(theta); |
xx123456987 | 0:f0f040a29912 | 252 | omg2 = (5*u[2])/2 - 20*u[1]*cos(pi/3 - theta) - 20*u[0]*sin(pi/3 - theta); |
xx123456987 | 0:f0f040a29912 | 253 | omg3 = (5*u[2])/2 - 20*u[1]*cos(pi/3 + theta) + 20*u[0]*sin(pi/3 + theta); |
xx123456987 | 0:f0f040a29912 | 254 | // control law end // |
xx123456987 | 0:f0f040a29912 | 255 | |
xx123456987 | 0:f0f040a29912 | 256 | // omega to PWM // |
xx123456987 | 0:f0f040a29912 | 257 | pwm_w1 = 0.5 + omg1/2; |
xx123456987 | 0:f0f040a29912 | 258 | pwm_w2 = 0.5 + omg2/2; |
xx123456987 | 0:f0f040a29912 | 259 | pwm_w3 = 0.5 + omg3/2; |
xx123456987 | 0:f0f040a29912 | 260 | |
xx123456987 | 0:f0f040a29912 | 261 | pwm_1.write(pwm_w1); |
xx123456987 | 0:f0f040a29912 | 262 | pwm_2.write(pwm_w2); |
xx123456987 | 0:f0f040a29912 | 263 | pwm_3.write(pwm_w3); |
xx123456987 | 0:f0f040a29912 | 264 | // END // |
xx123456987 | 0:f0f040a29912 | 265 | |
xx123456987 | 0:f0f040a29912 | 266 | // define error // not abs() yet |
xx123456987 | 0:f0f040a29912 | 267 | err[0] = (Current_X[0]-f1[0])-(0.0); |
xx123456987 | 0:f0f040a29912 | 268 | err[1] = (Current_X[1]-f1[1])-(0.0); |
xx123456987 | 0:f0f040a29912 | 269 | err[2] = (Current_X[2]-f1[2])-XL[2]; |
xx123456987 | 0:f0f040a29912 | 270 | |
xx123456987 | 0:f0f040a29912 | 271 | if ( abs(err[0])<ex && abs(err[1])<ey && abs(err[2])<(etheta*pi/180) && stop==true ) { |
xx123456987 | 0:f0f040a29912 | 272 | printf("Arrived!\n"); |
xx123456987 | 0:f0f040a29912 | 273 | pwm_1.write(0.50); |
xx123456987 | 0:f0f040a29912 | 274 | pwm_2.write(0.50); |
xx123456987 | 0:f0f040a29912 | 275 | pwm_3.write(0.50); |
xx123456987 | 0:f0f040a29912 | 276 | while (mybutton == 1) {} |
xx123456987 | 0:f0f040a29912 | 277 | } |
xx123456987 | 0:f0f040a29912 | 278 | |
xx123456987 | 0:f0f040a29912 | 279 | |
xx123456987 | 0:f0f040a29912 | 280 | //printf ("\n"); |
xx123456987 | 0:f0f040a29912 | 281 | //printf("% .2f|% .2f|% .1f|Xnow|%f\n", Current_X[0]*100, Current_X[1]*100,Current_X[2]*180/pi-60,clk.read()); |
xx123456987 | 1:6b405e5f18ef | 282 | printf("% .2f|% .2f|% .1f|Xnow|% .2f|% .2f|% .1f|XL|% .2f|% .2f|% .1f|Vnow|%f\n", |
xx123456987 | 0:f0f040a29912 | 283 | Current_X[0]*100, Current_X[1]*100,Current_X[2]*180/pi-60, |
xx123456987 | 1:6b405e5f18ef | 284 | XL[0]*100, XL[1]*100, XL[2]*180/pi-60, |
xx123456987 | 1:6b405e5f18ef | 285 | V1[0]*100, V1[1]*100, V1[2]*180/pi, |
xx123456987 | 1:6b405e5f18ef | 286 | clk.read()); |
xx123456987 | 0:f0f040a29912 | 287 | //printf("% .1f|% .1f|% .1f|Xc|%f\n", XL[0]*100, XL[1]*100 ,XL[2]*180/pi-60,clk.read()); |
xx123456987 | 0:f0f040a29912 | 288 | ///printf ("% .2f|% .2f|% .1f|Vnow\n", V1[0]*100, V1[1]*100, V1[2]*180/pi); |
xx123456987 | 0:f0f040a29912 | 289 | //printf("%f\n",clk.read()); |
xx123456987 | 0:f0f040a29912 | 290 | //printf("% .1f|% .1f|% .1f|Xc \n", XL[0]*100, XL[1]*100 ,XL[2]*180/pi-60); |
xx123456987 | 0:f0f040a29912 | 291 | //printf("% .2f|% .2f|% .1f|Vc \n", Vc[0]*100, Vc[1]*100, Vc[2]*180/pi); |
xx123456987 | 0:f0f040a29912 | 292 | //printf ("% .2f|% .2f|%f|now\n", Current_X[0]*100, V1[0]*100,clk.read()); |
xx123456987 | 0:f0f040a29912 | 293 | //printf("% .2f|% .2f|%f|X V cmd(xdire)\n", XL[0]*100, Vc[0]*100, clk.read());//測命令用 |
xx123456987 | 0:f0f040a29912 | 294 | //printf("% .2f|% .2f|%f|X V cmd(ydire)\n", XL[1]*100, Vc[1]*100, clk.read()); |
xx123456987 | 0:f0f040a29912 | 295 | //printf ("Error : [% .1f(cm) % .1f(cm) % .1f(deg)]\n", (err[0])*100, (err[1])*100, (err[2])*180/pi); |
xx123456987 | 0:f0f040a29912 | 296 | /* |
xx123456987 | 0:f0f040a29912 | 297 | printf ("\nWheel[1] counts: %d | revolutions: % .2f", qei1_new, (float)qei1_new/(4096*6)); |
xx123456987 | 0:f0f040a29912 | 298 | printf ("\nWheel[2] counts: %d | revolutions: % .2f", qei2_new, (float)qei2_new/(4096*6)); |
xx123456987 | 0:f0f040a29912 | 299 | printf ("\nWheel[3] counts: %d | revolutions: % .2f", qei3_new, (float)qei3_new/(4096*6)); |
xx123456987 | 0:f0f040a29912 | 300 | */ |
xx123456987 | 0:f0f040a29912 | 301 | //printf("Wheel Vel. [%3.2f %3.2f %3.2f]\n",pwm_w1,pwm_w2,pwm_w3); |
xx123456987 | 0:f0f040a29912 | 302 | //printf("OMEGA: [%.2f %.2f %.2f]\n",omg1,omg2,omg3); |
xx123456987 | 0:f0f040a29912 | 303 | //printf("PWM: [%.2f(%%) %.2f(%%) %.2f(%%)]\n",pwm_1.read()*100,pwm_2.read()*100,pwm_3.read()*100); |
xx123456987 | 0:f0f040a29912 | 304 | //printf("%f\n",clk.read()); |
xx123456987 | 0:f0f040a29912 | 305 | |
xx123456987 | 0:f0f040a29912 | 306 | //} |
xx123456987 | 0:f0f040a29912 | 307 | |
xx123456987 | 0:f0f040a29912 | 308 | // arrive? |
xx123456987 | 0:f0f040a29912 | 309 | wait_ms(50);// |
xx123456987 | 0:f0f040a29912 | 310 | } |
xx123456987 | 0:f0f040a29912 | 311 | } |
xx123456987 | 0:f0f040a29912 | 312 | |
xx123456987 | 1:6b405e5f18ef | 313 | int sgn(float e){ |
xx123456987 | 1:6b405e5f18ef | 314 | if (e>0) return 1; |
xx123456987 | 1:6b405e5f18ef | 315 | else if (e<0) return -1; |
xx123456987 | 1:6b405e5f18ef | 316 | else return 0; |
xx123456987 | 1:6b405e5f18ef | 317 | } |