Developers_of_anti_slip_compensator / Mbed 2 deprecated WIPV

Dependencies:   CURRENT_CONTROL IIR LSM9DS0 MEDIAN_FILTER PID QEI RF24 SENSOR_FUSION mbed

Committer:
adam_z
Date:
Sat Jun 18 09:49:17 2016 +0000
Revision:
8:9f4c10787775
Parent:
7:f33a935eb77a
Child:
9:a91135551be1
photon to stm has some problem; s

Who changed what in which revision?

UserRevisionLine numberNew contents of line
adam_z 0:150bb4605023 1 #include "mbed.h"
adam_z 0:150bb4605023 2 #include "PID.h"
adam_z 0:150bb4605023 3 #include "LSM9DS0.h"
adam_z 0:150bb4605023 4 #include "QEI.h"
adam_z 4:a2d38818c4e7 5 #include "CURRENT_CONTROL.h"
adam_z 4:a2d38818c4e7 6 #include "SENSOR_FUSION.h"
adam_z 8:9f4c10787775 7 #include "MEDIAN_FILTER.h"
adam_z 8:9f4c10787775 8 #include <algorithm>
adam_z 0:150bb4605023 9
adam_z 0:150bb4605023 10 #define Ts 0.001
adam_z 2:53a942d1b1e5 11 #define pi 3.14159
adam_z 0:150bb4605023 12
adam_z 0:150bb4605023 13 LSM9DS0 sensor(SPI_MODE, D9, D6);
adam_z 0:150bb4605023 14 Serial pc(SERIAL_TX, SERIAL_RX);
adam_z 6:5bd08053e95c 15 Serial blueTooth(D10, D2);
adam_z 7:f33a935eb77a 16 Serial LeftSerial(PC_12, PD_2);
adam_z 7:f33a935eb77a 17 Serial RightSerial(PC_10, PC_11);
adam_z 7:f33a935eb77a 18
adam_z 7:f33a935eb77a 19 DigitalOut debugLed_l(A4);
adam_z 7:f33a935eb77a 20 DigitalOut debugLed_r(A5);
adam_z 0:150bb4605023 21
adam_z 8:9f4c10787775 22 InterruptIn SCEnable(USER_BUTTON);
adam_z 8:9f4c10787775 23
adam_z 8:9f4c10787775 24
adam_z 0:150bb4605023 25 Ticker WIPVTimer;
adam_z 0:150bb4605023 26 void WIPVTimerInterrupt();
adam_z 4:a2d38818c4e7 27 float saturation(float input, float limit_H, float limit_L);
adam_z 8:9f4c10787775 28 //void SensorAcquisition(float * data, float samplingTime);
adam_z 7:f33a935eb77a 29
adam_z 7:f33a935eb77a 30 void bluetoothRx();
adam_z 7:f33a935eb77a 31 void RXIrqLeft();
adam_z 7:f33a935eb77a 32 void RXIrqRight();
adam_z 0:150bb4605023 33
adam_z 8:9f4c10787775 34 void SCEnableFunc();
adam_z 8:9f4c10787775 35 bool SCEnalbeIndicator;
adam_z 8:9f4c10787775 36
adam_z 5:842372be775c 37 //MOTOR L == MOTOR 1; MOTOR R = MOTOR 2
adam_z 5:842372be775c 38 CURRENT_CONTROL motorCur_L(PC_3, D8, A3,CURRENT_CONTROL::PWM2,400, 900.0,0.0,Ts);
adam_z 5:842372be775c 39 CURRENT_CONTROL motorCur_R(PC_2, D7, D11,CURRENT_CONTROL::PWM1,400, 900.0,0.0,Ts);
adam_z 1:ddc39900f9b8 40
adam_z 6:5bd08053e95c 41 QEI wheel_L(D13, D12, NC, 280, 200, Ts, QEI::X4_ENCODING);
adam_z 6:5bd08053e95c 42 QEI wheel_R(A1, A2, NC, 280, 200, Ts, QEI::X4_ENCODING);
adam_z 5:842372be775c 43
adam_z 2:53a942d1b1e5 44
adam_z 4:a2d38818c4e7 45 PID balancingPD(20,0.00,0.0,Ts);
adam_z 6:5bd08053e95c 46 LPF sensorFilter1(Ts);
adam_z 6:5bd08053e95c 47 LPF sensorFilter2(Ts);
adam_z 6:5bd08053e95c 48 LPF sensorFilter3(Ts);
adam_z 6:5bd08053e95c 49 LPF sensorFilter4(Ts);
adam_z 2:53a942d1b1e5 50
adam_z 8:9f4c10787775 51 MedianFilter slipA_L_MF(9);
adam_z 8:9f4c10787775 52 MedianFilter slipA_R_MF(9);
adam_z 8:9f4c10787775 53
adam_z 4:a2d38818c4e7 54
adam_z 4:a2d38818c4e7 55
adam_z 5:842372be775c 56
adam_z 4:a2d38818c4e7 57
adam_z 4:a2d38818c4e7 58 int tim_counter = 0;
adam_z 2:53a942d1b1e5 59 float tim = 0.0;
adam_z 4:a2d38818c4e7 60 float amp = 0.3;
adam_z 4:a2d38818c4e7 61 float omega = 6.0;
adam_z 4:a2d38818c4e7 62 float curCmd_L =0.0, curCmd_R =0.0;
adam_z 2:53a942d1b1e5 63
adam_z 0:150bb4605023 64
adam_z 8:9f4c10787775 65 //*************real plant states and matrices*****************************
adam_z 6:5bd08053e95c 66 float state[4] = {0.0, 0.0, 0.0, 0.0};
adam_z 6:5bd08053e95c 67 float ref[4] = {0.0, 0.0, 0.0, 0.0};
adam_z 6:5bd08053e95c 68
adam_z 6:5bd08053e95c 69 float torque_L = 0.0, torque_R = 0.0;
adam_z 8:9f4c10787775 70 float KL[4] = {-0.9159 , -0.1093 , -0.0146 , -0.0369};//{-0.7057 , -0.0733 , -0.0085 , -0.0300};
adam_z 8:9f4c10787775 71 float KR[4] = {-0.9159 , -0.1093 , -0.0369 , -0.0146};//{-0.7057 , -0.0733 , -0.0300 , -0.0085};
adam_z 8:9f4c10787775 72
adam_z 8:9f4c10787775 73 //********simulated states and multiplying matrices***********************
adam_z 8:9f4c10787775 74 float z1_prime[4] = {0.0, 0.0, 0.0, 0.0};
adam_z 8:9f4c10787775 75 float z1_prime_dot[4] = {0.0, 0.0, 0.0, 0.0};
adam_z 8:9f4c10787775 76 float v1[2] = {0.0,0.0};
adam_z 8:9f4c10787775 77 float A1_prime0[4] = {0,1,0,0},A1_prime1[4] = {176.4899,0,0,0},A1_prime2[4] = {-83.1468,0, 0, 0},A1_prime3[4] = {-83.1468, 0, 0,0};
adam_z 8:9f4c10787775 78 float B11_prime0[2] = {0,0}, B11_prime1[2] = {-537.6123, -537.6123}, B11_prime2[2] = { 679.2587, 104.3936}, B11_prime3[2] = { 104.3936, 679.2587};
adam_z 8:9f4c10787775 79 float B31_0[2] = {0,0},B31_1[2] = {0.7840,0.7840},B31_2[2] = {12.1836, 0.3086},B31_3[2] = {0.3086, 12.1836};
adam_z 8:9f4c10787775 80
adam_z 8:9f4c10787775 81 float Ks0[4] = {-1.4973, -0.1057 , 0.0042 , -0.0096}, Ks1[4] = {-1.4973 , -0.1057 , -0.0096 , 0.0042};
adam_z 8:9f4c10787775 82 float yc[2] = {0.0,0.0};
adam_z 8:9f4c10787775 83
adam_z 8:9f4c10787775 84
adam_z 6:5bd08053e95c 85
adam_z 6:5bd08053e95c 86 float Km_L = 1.050*0.163;
adam_z 6:5bd08053e95c 87 float Km_R = 1.187*0.137;
adam_z 6:5bd08053e95c 88
adam_z 6:5bd08053e95c 89 float yawRate = 0.0;
adam_z 6:5bd08053e95c 90
adam_z 6:5bd08053e95c 91 float velocityCmd[2] = {0.0, 0.0};
adam_z 6:5bd08053e95c 92 unsigned int accelerateFlag = 0;
adam_z 6:5bd08053e95c 93
adam_z 7:f33a935eb77a 94
adam_z 7:f33a935eb77a 95 uint8_t cLast_l = 0x00, cLast_r = 0x00;
adam_z 7:f33a935eb77a 96 bool headerCaptured_l = 0, headerCaptured_r = 0;
adam_z 7:f33a935eb77a 97 uint8_t fromPhoton_l[2] = {0,0}, fromPhoton_r[2] = {0,0};
adam_z 8:9f4c10787775 98 float slipAcceleration_L = 0.0, slipAcceleration_R = 0.0, slipAcceleration_L_f, slipAcceleration_R_f, slipAcceleration_L_m, slipAcceleration_R_m;
adam_z 7:f33a935eb77a 99 int i_l, i_r;
adam_z 7:f33a935eb77a 100
adam_z 8:9f4c10787775 101
adam_z 8:9f4c10787775 102 float a_vehicle;
adam_z 8:9f4c10787775 103 float slipA_L_p, slipA_R_p;
adam_z 8:9f4c10787775 104
adam_z 8:9f4c10787775 105 int send_i = 0, send_counter = 0;
adam_z 8:9f4c10787775 106 bool sent_flag = 1;
adam_z 8:9f4c10787775 107 uint8_t data_sent[18];
adam_z 8:9f4c10787775 108
adam_z 8:9f4c10787775 109
adam_z 0:150bb4605023 110 int main()
adam_z 0:150bb4605023 111 {
adam_z 2:53a942d1b1e5 112
adam_z 7:f33a935eb77a 113 pc.baud(230400);
adam_z 6:5bd08053e95c 114 blueTooth.baud(230400);
adam_z 8:9f4c10787775 115 LeftSerial.baud(115200); //uart commu with photon left
adam_z 7:f33a935eb77a 116 RightSerial.baud(230400); //uart commu with photon right
adam_z 7:f33a935eb77a 117
adam_z 0:150bb4605023 118 if( sensor.begin() != 0 ) {
adam_z 0:150bb4605023 119 pc.printf("Problem starting the sensor with CS @ Pin D6.\r\n");
adam_z 0:150bb4605023 120 } else {
adam_z 0:150bb4605023 121 pc.printf("Sensor with CS @ Pin D9&D6 started.\r\n");
adam_z 0:150bb4605023 122 }
adam_z 0:150bb4605023 123 sensor.setGyroOffset(38,-24,-106);
adam_z 0:150bb4605023 124 sensor.setAccelOffset(-793,-511,300);
adam_z 2:53a942d1b1e5 125
adam_z 6:5bd08053e95c 126 motorCur_L.SetParams(3.3*8/0.6, Km_L, 0.04348);
adam_z 6:5bd08053e95c 127 motorCur_R.SetParams(3.3*8/0.6, Km_R, 0.04348);
adam_z 2:53a942d1b1e5 128
adam_z 8:9f4c10787775 129 WIPVTimer.attach_us(WIPVTimerInterrupt, Ts*1000.0*1000.0);
adam_z 7:f33a935eb77a 130 blueTooth.attach(&bluetoothRx, Serial::RxIrq);
adam_z 7:f33a935eb77a 131 LeftSerial.attach(&RXIrqLeft, Serial::RxIrq);
adam_z 8:9f4c10787775 132 //RightSerial.attach(&RXIrqRight, Serial::RxIrq);
adam_z 8:9f4c10787775 133
adam_z 8:9f4c10787775 134 SCEnable.rise(&SCEnableFunc);
adam_z 8:9f4c10787775 135 SCEnalbeIndicator = 0;
adam_z 7:f33a935eb77a 136
adam_z 2:53a942d1b1e5 137 while(true) {
adam_z 4:a2d38818c4e7 138 //pc.printf("%5.4f\t", 10*pitch_angle);
adam_z 8:9f4c10787775 139 // pc.printf("%5.3f\n", 10*sensor.pitch*3.14159/180);
adam_z 8:9f4c10787775 140 // pc.printf("%5.3f\r\n", 10*curCmd_L);
adam_z 8:9f4c10787775 141
adam_z 8:9f4c10787775 142
adam_z 8:9f4c10787775 143 // pc.printf("%5.4f\t", slipAcceleration_L_f);
adam_z 8:9f4c10787775 144 // pc.printf("%5.4f\r\n", slipAcceleration_R_f);
adam_z 6:5bd08053e95c 145
adam_z 6:5bd08053e95c 146
adam_z 8:9f4c10787775 147 // blueTooth.putc(0xFE);
adam_z 8:9f4c10787775 148 //blueTooth.putc(48);
adam_z 8:9f4c10787775 149 // blueTooth.putc(48);
adam_z 8:9f4c10787775 150 // blueTooth.putc(48);
adam_z 8:9f4c10787775 151 // blueTooth.putc(48);
adam_z 8:9f4c10787775 152 // blueTooth.putc(48);
adam_z 8:9f4c10787775 153 // blueTooth.putc(48);
adam_z 8:9f4c10787775 154 // blueTooth.putc(48);
adam_z 8:9f4c10787775 155 // blueTooth.putc(48);
adam_z 7:f33a935eb77a 156
adam_z 7:f33a935eb77a 157 // pc.putc(fromPhoton_l[0]);
adam_z 7:f33a935eb77a 158 // pc.putc(fromPhoton_l[1]);
adam_z 7:f33a935eb77a 159 // pc.putc(fromPhoton_r[0]);
adam_z 7:f33a935eb77a 160 // pc.putc(fromPhoton_r[1]);
adam_z 8:9f4c10787775 161
adam_z 8:9f4c10787775 162
adam_z 8:9f4c10787775 163 //if(sent_flag == 0) {///
adam_z 8:9f4c10787775 164 // pc.putc(data_sent[send_i]);
adam_z 8:9f4c10787775 165 // send_i++;
adam_z 8:9f4c10787775 166 // if(send_i >= 18) {
adam_z 8:9f4c10787775 167 // send_i = 0;
adam_z 8:9f4c10787775 168 // sent_flag = 1;
adam_z 8:9f4c10787775 169 // }
adam_z 8:9f4c10787775 170 // }///
adam_z 8:9f4c10787775 171
adam_z 8:9f4c10787775 172
adam_z 8:9f4c10787775 173
adam_z 8:9f4c10787775 174
adam_z 6:5bd08053e95c 175
adam_z 2:53a942d1b1e5 176 }
adam_z 0:150bb4605023 177 }
adam_z 0:150bb4605023 178
adam_z 0:150bb4605023 179
adam_z 0:150bb4605023 180 void WIPVTimerInterrupt()
adam_z 0:150bb4605023 181 {
adam_z 2:53a942d1b1e5 182 if(tim_counter <100)tim_counter++;
adam_z 2:53a942d1b1e5 183 else if (tim_counter >= 100 && tim_counter <=109) {
adam_z 4:a2d38818c4e7 184 motorCur_L.currentOffset += motorCur_L.currentAnalogIn.read();
adam_z 4:a2d38818c4e7 185 motorCur_R.currentOffset += motorCur_R.currentAnalogIn.read();
adam_z 2:53a942d1b1e5 186 tim_counter++;
adam_z 2:53a942d1b1e5 187 if(tim_counter == 110) {
adam_z 4:a2d38818c4e7 188 motorCur_L.currentOffset = motorCur_L.currentOffset/10;
adam_z 4:a2d38818c4e7 189 motorCur_R.currentOffset = motorCur_R.currentOffset/10;
adam_z 2:53a942d1b1e5 190 }
adam_z 2:53a942d1b1e5 191
adam_z 2:53a942d1b1e5 192 } else {
adam_z 2:53a942d1b1e5 193
adam_z 0:150bb4605023 194 /*
adam_z 0:150bb4605023 195 int16_t data_array[6];
adam_z 2:53a942d1b1e5 196
adam_z 0:150bb4605023 197 data_array[0] = sensor.readRawAccelX();
adam_z 0:150bb4605023 198 data_array[1] = sensor.readRawAccelY();
adam_z 0:150bb4605023 199 data_array[2] = sensor.readRawAccelZ();
adam_z 0:150bb4605023 200 data_array[3] = sensor.readRawGyroX();
adam_z 0:150bb4605023 201 data_array[4] = sensor.readRawGyroY();
adam_z 0:150bb4605023 202 data_array[5] = sensor.readRawGyroZ();
adam_z 2:53a942d1b1e5 203
adam_z 0:150bb4605023 204 pc.printf("%d, ", data_array[0]);
adam_z 0:150bb4605023 205 pc.printf("%d, ", data_array[1]);
adam_z 0:150bb4605023 206 pc.printf("%d, ", data_array[2]);
adam_z 0:150bb4605023 207 pc.printf("%d, ", data_array[3]);
adam_z 0:150bb4605023 208 pc.printf("%d, ", data_array[4]);
adam_z 0:150bb4605023 209 pc.printf("%d;\r\n ", data_array[5]);
adam_z 0:150bb4605023 210 */
adam_z 2:53a942d1b1e5 211
adam_z 2:53a942d1b1e5 212
adam_z 5:842372be775c 213 float data_array[6];//Gs and deg/s
adam_z 0:150bb4605023 214 data_array[0] = sensor.readFloatAccelX();
adam_z 0:150bb4605023 215 data_array[1] = sensor.readFloatAccelY();
adam_z 8:9f4c10787775 216 // data_array[2] = sensor.readFloatAccelZ();
adam_z 8:9f4c10787775 217 // data_array[3] = sensor.readFloatGyroX();
adam_z 0:150bb4605023 218 data_array[4] = sensor.readFloatGyroY();
adam_z 0:150bb4605023 219 data_array[5] = sensor.readFloatGyroZ();
adam_z 8:9f4c10787775 220
adam_z 4:a2d38818c4e7 221 sensor.complementaryFilter(data_array,Ts);
adam_z 4:a2d38818c4e7 222 //SensorAcquisition(data_array, Ts);
adam_z 6:5bd08053e95c 223
adam_z 6:5bd08053e95c 224 //===============wheel speed calculation============//
adam_z 2:53a942d1b1e5 225 wheel_L.Calculate();
adam_z 2:53a942d1b1e5 226 wheel_R.Calculate();
adam_z 6:5bd08053e95c 227
adam_z 6:5bd08053e95c 228 /////////////Balancing Control/////////////////////////
adam_z 6:5bd08053e95c 229 //SI dimension
adam_z 6:5bd08053e95c 230 state[0] = sensor.pitch*3.14159/180.0;
adam_z 8:9f4c10787775 231 state[1] = sensorFilter1.filter(data_array[5]*3.14159/180.0, 9.0);
adam_z 6:5bd08053e95c 232 state[2] = sensorFilter2.filter(wheel_L.getAngularSpeed(),60.0);
adam_z 6:5bd08053e95c 233 state[3] = -sensorFilter3.filter(wheel_R.getAngularSpeed(),60.0);
adam_z 6:5bd08053e95c 234
adam_z 6:5bd08053e95c 235 if(accelerateFlag == 1) {
adam_z 6:5bd08053e95c 236 if(velocityCmd[0]>=7 || velocityCmd[1]>=7)accelerateFlag = 0;
adam_z 6:5bd08053e95c 237 else {
adam_z 6:5bd08053e95c 238 velocityCmd[0] += 0.004;
adam_z 6:5bd08053e95c 239 velocityCmd[1] += 0.004;
adam_z 6:5bd08053e95c 240 }
adam_z 6:5bd08053e95c 241 }
adam_z 6:5bd08053e95c 242
adam_z 6:5bd08053e95c 243 ref[2] = velocityCmd[0];
adam_z 6:5bd08053e95c 244 ref[3] = velocityCmd[1];
adam_z 6:5bd08053e95c 245
adam_z 7:f33a935eb77a 246 yawRate = sensorFilter4.filter(data_array[4],20);
adam_z 6:5bd08053e95c 247
adam_z 6:5bd08053e95c 248
adam_z 8:9f4c10787775 249 //===============integration of z1_prime=========================
adam_z 8:9f4c10787775 250 z1_prime[0] += z1_prime_dot[0]*Ts;
adam_z 8:9f4c10787775 251 z1_prime[1] += z1_prime_dot[1]*Ts;
adam_z 8:9f4c10787775 252 z1_prime[2] += z1_prime_dot[2]*Ts;
adam_z 8:9f4c10787775 253 z1_prime[3] += z1_prime_dot[3]*Ts;
adam_z 8:9f4c10787775 254
adam_z 8:9f4c10787775 255
adam_z 8:9f4c10787775 256 yc[0] = (KL[0]*(ref[0] - (state[0] - z1_prime[0])) + KL[1]*(ref[1] - (state[1] - z1_prime[1]))\
adam_z 8:9f4c10787775 257 + KL[2]*(ref[2] - (state[2] - z1_prime[2])) + KL[3]*(ref[3] - (state[3] - z1_prime[3])));
adam_z 8:9f4c10787775 258
adam_z 8:9f4c10787775 259 yc[1] = (KR[0]*(ref[0] - (state[0] - z1_prime[0])) + KR[1]*(ref[1] - (state[1] - z1_prime[1]))\
adam_z 8:9f4c10787775 260 + KR[2]*(ref[2] - (state[2] - z1_prime[2])) + KR[3]*(ref[3] - (state[3] - z1_prime[3])));
adam_z 8:9f4c10787775 261
adam_z 8:9f4c10787775 262
adam_z 7:f33a935eb77a 263 //=========================Anti slip control=============================//
adam_z 8:9f4c10787775 264 //***********filtering the slip acceleration of two wheels********************
adam_z 8:9f4c10787775 265 a_vehicle = (data_array[0]*cos(state[0]) - data_array[1]*sin(state[0]))*9.791;//compute acceleration of vehicle using lsm9ds0
adam_z 8:9f4c10787775 266
adam_z 8:9f4c10787775 267 slipA_L_p = slipAcceleration_L_m;
adam_z 8:9f4c10787775 268 slipA_R_p = slipAcceleration_R_m;
adam_z 8:9f4c10787775 269
adam_z 8:9f4c10787775 270 if(SCEnalbeIndicator == 0) {
adam_z 8:9f4c10787775 271 slipAcceleration_L_f = 0;
adam_z 8:9f4c10787775 272 slipAcceleration_R_f = 0;
adam_z 8:9f4c10787775 273
adam_z 8:9f4c10787775 274 } else {
adam_z 8:9f4c10787775 275
adam_z 8:9f4c10787775 276 slipAcceleration_L_f = (1 - 30*2*3.141593*Ts)*slipAcceleration_L_f + 30*2*3.141593*Ts*slipA_L_p;
adam_z 8:9f4c10787775 277 slipAcceleration_R_f = (1 - 30*2*3.141593*Ts)*slipAcceleration_R_f + 30*2*3.141593*Ts*slipA_R_p;
adam_z 8:9f4c10787775 278
adam_z 8:9f4c10787775 279 }
adam_z 8:9f4c10787775 280
adam_z 8:9f4c10787775 281 //***************simulated plant feedback**************
adam_z 8:9f4c10787775 282 v1[0] = -(Ks0[0]*z1_prime[0] + Ks0[1]*z1_prime[1] + Ks0[2]*z1_prime[2] + Ks0[3]*z1_prime[3]);
adam_z 8:9f4c10787775 283 v1[1] = -(Ks1[0]*z1_prime[0] + Ks1[1]*z1_prime[1] + Ks1[2]*z1_prime[2] + Ks1[3]*z1_prime[3]);
adam_z 8:9f4c10787775 284
adam_z 8:9f4c10787775 285 //**********simulated dynamics*****************
adam_z 8:9f4c10787775 286 z1_prime_dot[0] = A1_prime0[0]*z1_prime[0] + A1_prime0[1]*z1_prime[1]+A1_prime0[2]*z1_prime[2]+A1_prime0[3]*z1_prime[3]\
adam_z 8:9f4c10787775 287 + B11_prime0[0]*v1[0]+ B11_prime0[1]*v1[1]\
adam_z 8:9f4c10787775 288 + B31_0[0]*slipAcceleration_L_f+ B31_0[1]*slipAcceleration_R_f;
adam_z 8:9f4c10787775 289
adam_z 8:9f4c10787775 290 z1_prime_dot[1] = A1_prime1[0]*z1_prime[0] + A1_prime1[1]*z1_prime[1]+A1_prime1[2]*z1_prime[2]+A1_prime1[3]*z1_prime[3]\
adam_z 8:9f4c10787775 291 + B11_prime1[0]*v1[0]+ B11_prime1[1]*v1[1]\
adam_z 8:9f4c10787775 292 + B31_1[0]*slipAcceleration_L_f+ B31_1[1]*slipAcceleration_R_f;
adam_z 8:9f4c10787775 293
adam_z 8:9f4c10787775 294 z1_prime_dot[2] = A1_prime2[0]*z1_prime[0] + A1_prime2[1]*z1_prime[1]+A1_prime2[2]*z1_prime[2]+A1_prime2[3]*z1_prime[3]\
adam_z 8:9f4c10787775 295 + B11_prime2[0]*v1[0]+ B11_prime2[1]*v1[1]\
adam_z 8:9f4c10787775 296 + B31_2[0]*slipAcceleration_L_f+ B31_2[1]*slipAcceleration_R_f;
adam_z 8:9f4c10787775 297
adam_z 8:9f4c10787775 298 z1_prime_dot[3] = A1_prime3[0]*z1_prime[0] + A1_prime3[1]*z1_prime[1]+A1_prime3[2]*z1_prime[2]+A1_prime3[3]*z1_prime[3]\
adam_z 8:9f4c10787775 299 + B11_prime3[0]*v1[0]+ B11_prime3[1]*v1[1]\
adam_z 8:9f4c10787775 300 + B31_3[0]*slipAcceleration_L_f+ B31_3[1]*slipAcceleration_R_f;
adam_z 8:9f4c10787775 301
adam_z 8:9f4c10787775 302 torque_L = yc[0] + v1[0];
adam_z 8:9f4c10787775 303 torque_R = yc[1] + v1[1];
adam_z 6:5bd08053e95c 304
adam_z 8:9f4c10787775 305 //************motor torque control*****************
adam_z 8:9f4c10787775 306 // motorCur_L.Control(saturation((-torque_L)/Km_L + 0.008*yawRate,1.3,-1.3), state[2]);
adam_z 8:9f4c10787775 307 // motorCur_R.Control(saturation((torque_R)/Km_R + 0.008*yawRate,1.3,-1.3), -state[3]);
adam_z 8:9f4c10787775 308
adam_z 8:9f4c10787775 309 //**************sending data to PC******************
adam_z 8:9f4c10787775 310 if(send_counter < 40)send_counter++;
adam_z 8:9f4c10787775 311
adam_z 8:9f4c10787775 312 else if( sent_flag == 1 & send_counter >= 40) {
adam_z 8:9f4c10787775 313 send_counter = 0;
adam_z 8:9f4c10787775 314 int multiplier = 500;
adam_z 8:9f4c10787775 315 data_sent[0] = 0xAA;
adam_z 8:9f4c10787775 316 data_sent[1] = 0x55;
adam_z 8:9f4c10787775 317
adam_z 8:9f4c10787775 318 data_sent[2] = ((int16_t)((state[0])*multiplier)) >>8;
adam_z 8:9f4c10787775 319 data_sent[3] = ((int16_t)((state[0])*multiplier)) & 0x00FF;
adam_z 8:9f4c10787775 320 data_sent[4] = ((int16_t)(state[1]*multiplier)) >>8;
adam_z 8:9f4c10787775 321 data_sent[5] = ((int16_t)(state[1]*multiplier)) & 0x00FF;
adam_z 8:9f4c10787775 322
adam_z 8:9f4c10787775 323 data_sent[6] = ((int16_t)((v1[0])*multiplier)) >>8;
adam_z 8:9f4c10787775 324 data_sent[7] = ((int16_t)((v1[0])*multiplier)) & 0x00FF;
adam_z 8:9f4c10787775 325 data_sent[8] = ((int16_t)((v1[1])*multiplier)) >>8;
adam_z 8:9f4c10787775 326 data_sent[9] = ((int16_t)((v1[1])*multiplier)) & 0x00FF;
adam_z 8:9f4c10787775 327
adam_z 8:9f4c10787775 328 data_sent[10] = ((int16_t)((yc[0])*multiplier)) >>8;
adam_z 8:9f4c10787775 329 data_sent[11] = ((int16_t)((yc[0])*multiplier)) & 0x00FF;
adam_z 8:9f4c10787775 330 data_sent[12] = ((int16_t)((yc[1])*multiplier)) >>8;
adam_z 8:9f4c10787775 331 data_sent[13] = ((int16_t)((yc[1])*multiplier)) & 0x00FF;
adam_z 8:9f4c10787775 332 //data_sent[10] = ((int16_t)((-a_vehicle)*multiplier)) >>8;
adam_z 8:9f4c10787775 333 // data_sent[11] = ((int16_t)((-a_vehicle)*multiplier)) & 0x00FF;
adam_z 8:9f4c10787775 334 // data_sent[12] = ((int16_t)((slipAcceleration_R_m)*multiplier)) >>8;
adam_z 8:9f4c10787775 335 // data_sent[13] = ((int16_t)((slipAcceleration_R_m)*multiplier)) & 0x00FF;
adam_z 8:9f4c10787775 336 data_sent[14] = ((int16_t)((slipAcceleration_L)*multiplier)) >>8;
adam_z 8:9f4c10787775 337 data_sent[15] = ((int16_t)((slipAcceleration_L)*multiplier)) & 0x00FF;
adam_z 8:9f4c10787775 338 data_sent[16] = ((int16_t)((slipAcceleration_L_f)*multiplier)) >>8;
adam_z 8:9f4c10787775 339 data_sent[17] = ((int16_t)((slipAcceleration_L_f)*multiplier)) & 0x00FF;
adam_z 8:9f4c10787775 340
adam_z 8:9f4c10787775 341
adam_z 8:9f4c10787775 342 sent_flag = 0;
adam_z 8:9f4c10787775 343
adam_z 8:9f4c10787775 344 }
adam_z 8:9f4c10787775 345
adam_z 8:9f4c10787775 346
adam_z 8:9f4c10787775 347
adam_z 6:5bd08053e95c 348
adam_z 7:f33a935eb77a 349
adam_z 6:5bd08053e95c 350 /* //PD Balancing Control
adam_z 6:5bd08053e95c 351 balancingPD.Compute(0.0, sensor.pitch*3.14159/180);
adam_z 6:5bd08053e95c 352 curCmd_R = sensorFilter.filter(saturation(0.5*( -balancingPD.output + 0.002*data_array[5]),1.0, -1.0),10);
adam_z 6:5bd08053e95c 353 //======================current control=========================//
adam_z 6:5bd08053e95c 354 tim += Ts;
adam_z 6:5bd08053e95c 355 if(tim >= 4*pi/omega)tim = 0.0;
adam_z 6:5bd08053e95c 356 //curCmd_R = amp*sin(omega*tim); //current command
adam_z 6:5bd08053e95c 357 //curCmd_L = 0.8;
adam_z 6:5bd08053e95c 358
adam_z 6:5bd08053e95c 359 motorCur_R.SetPWMDuty(0.75);
adam_z 6:5bd08053e95c 360
adam_z 6:5bd08053e95c 361 motorCur_L.Control(-curCmd_R + 0.002*data_array[4], wheel_L.getAngularSpeed());
adam_z 6:5bd08053e95c 362 motorCur_R.Control(curCmd_R + 0.002*data_array[4], wheel_R.getAngularSpeed());
adam_z 6:5bd08053e95c 363 */
adam_z 6:5bd08053e95c 364
adam_z 2:53a942d1b1e5 365 }
adam_z 2:53a942d1b1e5 366
adam_z 2:53a942d1b1e5 367
adam_z 4:a2d38818c4e7 368 }
adam_z 4:a2d38818c4e7 369
adam_z 4:a2d38818c4e7 370
adam_z 7:f33a935eb77a 371 void bluetoothRx()
adam_z 6:5bd08053e95c 372 {
adam_z 8:9f4c10787775 373 while(pc.readable()) {
adam_z 8:9f4c10787775 374 char charRx = pc.getc();
adam_z 6:5bd08053e95c 375 switch(charRx) {
adam_z 6:5bd08053e95c 376 case 'w'://forward
adam_z 6:5bd08053e95c 377 velocityCmd[0] = 2.5;
adam_z 6:5bd08053e95c 378 velocityCmd[1] = 2.5;
adam_z 6:5bd08053e95c 379 accelerateFlag = 0;
adam_z 6:5bd08053e95c 380 break;
adam_z 6:5bd08053e95c 381 case 's'://backward
adam_z 6:5bd08053e95c 382 velocityCmd[0] = -3.0;
adam_z 6:5bd08053e95c 383 velocityCmd[1] = -3.0;
adam_z 6:5bd08053e95c 384 accelerateFlag = 0;
adam_z 6:5bd08053e95c 385 break;
adam_z 6:5bd08053e95c 386 case 'a'://turn left
adam_z 6:5bd08053e95c 387 velocityCmd[0] = -4.0;
adam_z 6:5bd08053e95c 388 velocityCmd[1] = 4.0;
adam_z 6:5bd08053e95c 389 accelerateFlag = 0;
adam_z 6:5bd08053e95c 390 break;
adam_z 6:5bd08053e95c 391 case 'd'://turn right
adam_z 6:5bd08053e95c 392 velocityCmd[0] = 4.0;
adam_z 6:5bd08053e95c 393 velocityCmd[1] = -4.0;
adam_z 6:5bd08053e95c 394 accelerateFlag = 0;
adam_z 6:5bd08053e95c 395 break;
adam_z 6:5bd08053e95c 396 case 'x'://stop
adam_z 6:5bd08053e95c 397 velocityCmd[0] = 0.0;
adam_z 6:5bd08053e95c 398 velocityCmd[1] = 0.0;
adam_z 6:5bd08053e95c 399 accelerateFlag = 0;
adam_z 6:5bd08053e95c 400 break;
adam_z 7:f33a935eb77a 401
adam_z 6:5bd08053e95c 402 case 'q'://accelerate
adam_z 8:9f4c10787775 403 // debugLed_l = !debugLed_l;
adam_z 6:5bd08053e95c 404 accelerateFlag = 1;
adam_z 6:5bd08053e95c 405 break;
adam_z 6:5bd08053e95c 406 }
adam_z 6:5bd08053e95c 407 }
adam_z 6:5bd08053e95c 408 }
adam_z 6:5bd08053e95c 409
adam_z 7:f33a935eb77a 410 void RXIrqLeft()
adam_z 7:f33a935eb77a 411 {
adam_z 7:f33a935eb77a 412 // slipAcceleration_L += 0.1;
adam_z 7:f33a935eb77a 413 while(!LeftSerial.readable());
adam_z 7:f33a935eb77a 414 uint8_t c = LeftSerial.getc();
adam_z 7:f33a935eb77a 415 if(!headerCaptured_l & cLast_l == 0xAA & c == 0x55) {
adam_z 7:f33a935eb77a 416 headerCaptured_l = 1;
adam_z 7:f33a935eb77a 417 i_l = 0;
adam_z 7:f33a935eb77a 418 debugLed_l = 1;
adam_z 7:f33a935eb77a 419 } else if(headerCaptured_l) {
adam_z 7:f33a935eb77a 420 if(c == 0xAA | c == 0x55 ) {
adam_z 7:f33a935eb77a 421 headerCaptured_l = 0;
adam_z 7:f33a935eb77a 422 i_l = 0;
adam_z 7:f33a935eb77a 423 debugLed_l = 0;
adam_z 8:9f4c10787775 424 } else {
adam_z 7:f33a935eb77a 425 fromPhoton_l[i_l] = c;
adam_z 7:f33a935eb77a 426 i_l++;
adam_z 7:f33a935eb77a 427 if(i_l == 2) {
adam_z 7:f33a935eb77a 428 headerCaptured_l = 0;
adam_z 7:f33a935eb77a 429 debugLed_l = 0;
adam_z 8:9f4c10787775 430 slipAcceleration_L = (float)((int16_t)(fromPhoton_l[0]*256+fromPhoton_l[1]))/1000.0;
adam_z 7:f33a935eb77a 431
adam_z 8:9f4c10787775 432 if((abs(slipAcceleration_L) < 15.0 ))if((abs(slipAcceleration_L - slipAcceleration_L_m)< 0.4))\
adam_z 8:9f4c10787775 433 slipAcceleration_L_m = slipAcceleration_L;
adam_z 8:9f4c10787775 434
adam_z 8:9f4c10787775 435
adam_z 7:f33a935eb77a 436 }
adam_z 7:f33a935eb77a 437 }
adam_z 7:f33a935eb77a 438 }
adam_z 7:f33a935eb77a 439 cLast_l = c;
adam_z 8:9f4c10787775 440 pc.printf("%5.4f\r\n", (float)cLast_l);
adam_z 7:f33a935eb77a 441
adam_z 7:f33a935eb77a 442 }
adam_z 7:f33a935eb77a 443
adam_z 7:f33a935eb77a 444 void RXIrqRight()
adam_z 7:f33a935eb77a 445 {
adam_z 7:f33a935eb77a 446 // slipAcceleration_L += 0.1;
adam_z 7:f33a935eb77a 447 while(!RightSerial.readable());
adam_z 7:f33a935eb77a 448 uint8_t c = RightSerial.getc();
adam_z 7:f33a935eb77a 449 if(!headerCaptured_r & cLast_r == 0xAA & c == 0x55) {
adam_z 7:f33a935eb77a 450 headerCaptured_r = 1;
adam_z 7:f33a935eb77a 451 i_r = 0;
adam_z 7:f33a935eb77a 452 debugLed_r = 1;
adam_z 7:f33a935eb77a 453 } else if(headerCaptured_r) {
adam_z 7:f33a935eb77a 454 if(c == 0xAA | c == 0x55 ) {
adam_z 7:f33a935eb77a 455 headerCaptured_r = 0;
adam_z 7:f33a935eb77a 456 i_r = 0;
adam_z 7:f33a935eb77a 457 debugLed_r = 0;
adam_z 8:9f4c10787775 458 } else {
adam_z 7:f33a935eb77a 459 fromPhoton_r[i_r] = c;
adam_z 7:f33a935eb77a 460 i_r++;
adam_z 7:f33a935eb77a 461 if(i_r == 2) {
adam_z 7:f33a935eb77a 462 headerCaptured_r = 0;
adam_z 7:f33a935eb77a 463 debugLed_r = 0;
adam_z 8:9f4c10787775 464 slipAcceleration_R = -(float)((int16_t)(fromPhoton_r[0]*256+fromPhoton_r[1]))/1000.0;
adam_z 8:9f4c10787775 465
adam_z 8:9f4c10787775 466 if((abs(slipAcceleration_R) < 15.0 ))if((abs(slipAcceleration_R - slipAcceleration_R_m)< 0.4))\
adam_z 8:9f4c10787775 467 slipAcceleration_R_m = slipAcceleration_R;
adam_z 7:f33a935eb77a 468 }
adam_z 7:f33a935eb77a 469 }
adam_z 7:f33a935eb77a 470 }
adam_z 7:f33a935eb77a 471 cLast_r = c;
adam_z 7:f33a935eb77a 472
adam_z 7:f33a935eb77a 473 }
adam_z 7:f33a935eb77a 474
adam_z 6:5bd08053e95c 475
adam_z 6:5bd08053e95c 476
adam_z 4:a2d38818c4e7 477 float saturation(float input, float limit_H, float limit_L)
adam_z 4:a2d38818c4e7 478 {
adam_z 4:a2d38818c4e7 479 float output;
adam_z 4:a2d38818c4e7 480 if(input >= limit_H)output = limit_H;
adam_z 4:a2d38818c4e7 481 else if (input <= limit_L)output = limit_L;
adam_z 4:a2d38818c4e7 482 else output = input;
adam_z 4:a2d38818c4e7 483 return output;
adam_z 4:a2d38818c4e7 484 }
adam_z 4:a2d38818c4e7 485
adam_z 4:a2d38818c4e7 486
adam_z 8:9f4c10787775 487 //void SensorAcquisition(float * data, float samplingTime)
adam_z 8:9f4c10787775 488 //{
adam_z 8:9f4c10787775 489 //
adam_z 8:9f4c10787775 490 // axm = data[0]*(-1)*9.81;//accelerometer dimension from g to m/s^2
adam_z 8:9f4c10787775 491 // aym = data[1]*(-1)*9.81;
adam_z 8:9f4c10787775 492 // azm = data[2]*(-1)*9.81;
adam_z 8:9f4c10787775 493 // u1 = data[0]*3.14159/180; //gyroscope :deg/s to rad/s
adam_z 8:9f4c10787775 494 // u2 = data[1]*3.14159/180;
adam_z 8:9f4c10787775 495 // u3 = data[2]*3.14159/180;
adam_z 8:9f4c10787775 496 //
adam_z 8:9f4c10787775 497 //
adam_z 8:9f4c10787775 498 // if(conv_init <= 3) {
adam_z 8:9f4c10787775 499 // axm_f_old = axm;
adam_z 8:9f4c10787775 500 // aym_f_old = aym;
adam_z 8:9f4c10787775 501 // azm_f_old = azm;
adam_z 8:9f4c10787775 502 //
adam_z 8:9f4c10787775 503 // conv_init++;
adam_z 8:9f4c10787775 504 // } else {
adam_z 8:9f4c10787775 505 // pitch_fusion(axm, aym,azm,u3,u2,20, samplingTime);
adam_z 8:9f4c10787775 506 // roll_fusion(axm, aym,azm,u3,u1,20, samplingTime);
adam_z 8:9f4c10787775 507 // x3_hat_estimat(axm,aym,azm,u2,u1,20, samplingTime);
adam_z 8:9f4c10787775 508 // }
adam_z 8:9f4c10787775 509 //
adam_z 8:9f4c10787775 510 //}
adam_z 6:5bd08053e95c 511
adam_z 6:5bd08053e95c 512
adam_z 8:9f4c10787775 513 void SCEnableFunc()
adam_z 8:9f4c10787775 514 {
adam_z 8:9f4c10787775 515 debugLed_l = !debugLed_l;
adam_z 6:5bd08053e95c 516
adam_z 8:9f4c10787775 517 SCEnalbeIndicator = !SCEnalbeIndicator;
adam_z 4:a2d38818c4e7 518 }