Dependencies:   MODSERIAL QEI biquadFilter mbed

Committer:
CasperBerkhout
Date:
Thu Nov 02 12:11:41 2017 +0000
Revision:
4:de0923cf6bcc
Parent:
3:455b79d42636
Child:
5:9e8847a0492c
Better D action LPF added.

Who changed what in which revision?

UserRevisionLine numberNew contents of line
CasperBerkhout 0:4141aef83f4b 1 #include "QEI.h"
CasperBerkhout 0:4141aef83f4b 2 #include "math.h"
CasperBerkhout 0:4141aef83f4b 3 #include "mbed.h"
CasperBerkhout 0:4141aef83f4b 4 //#include "HIDScope.h" //set mbed library version to 119 for HIDScope to work
CasperBerkhout 0:4141aef83f4b 5 #include "MODSERIAL.h"
CasperBerkhout 0:4141aef83f4b 6 #include "BiQuad.h"
CasperBerkhout 0:4141aef83f4b 7
CasperBerkhout 0:4141aef83f4b 8 //left pot to set reference position.
CasperBerkhout 0:4141aef83f4b 9 //right pot to set Kp, right pot sets Ki when (right)button is pressed down
CasperBerkhout 0:4141aef83f4b 10
CasperBerkhout 0:4141aef83f4b 11
CasperBerkhout 0:4141aef83f4b 12 //--------------object creation------------------
CasperBerkhout 0:4141aef83f4b 13 Serial pc(USBTX, USBRX);
CasperBerkhout 0:4141aef83f4b 14 //Use X4 encoding.
CasperBerkhout 0:4141aef83f4b 15 //QEI wheel(p29, p30, NC, 624, QEI::X4_ENCODING);
CasperBerkhout 0:4141aef83f4b 16 //Use X2 encoding by default.
CasperBerkhout 0:4141aef83f4b 17 QEI enc1(D13, D12, NC, 32); //enable the encoder
CasperBerkhout 0:4141aef83f4b 18 QEI enc2(D15, D14, NC, 32); //enable the encoder
CasperBerkhout 0:4141aef83f4b 19 PwmOut M1_speed(D6);
CasperBerkhout 0:4141aef83f4b 20 PwmOut M2_speed(D5);
CasperBerkhout 0:4141aef83f4b 21 DigitalOut M1_direction(D7);
CasperBerkhout 0:4141aef83f4b 22 DigitalOut M2_direction(D4);
CasperBerkhout 0:4141aef83f4b 23 AnalogIn potmeter(A0); //left pot
CasperBerkhout 0:4141aef83f4b 24 AnalogIn potmeter2(A1); //right pot
CasperBerkhout 1:d7299175a12e 25 InterruptIn button1(D2); //hardware interrupt for stopping motors - right button
CasperBerkhout 1:d7299175a12e 26 DigitalIn LimSW1(D9);
CasperBerkhout 1:d7299175a12e 27 DigitalIn LimSW2(D8);
CasperBerkhout 1:d7299175a12e 28 DigitalIn HomStart(D3); // - left button
CasperBerkhout 1:d7299175a12e 29
CasperBerkhout 4:de0923cf6bcc 30 BiQuad bqlowpass(0.4354, 0.8709, 0.4354, 0.5179, 0.2238);
CasperBerkhout 0:4141aef83f4b 31 //create scope objects - note: script won't run when HID usb port is not connected
CasperBerkhout 0:4141aef83f4b 32 //HIDScope scope(5); //set # of channels
CasperBerkhout 1:d7299175a12e 33
CasperBerkhout 1:d7299175a12e 34 Ticker motor_update1;
CasperBerkhout 1:d7299175a12e 35 Ticker motor_update2;
CasperBerkhout 1:d7299175a12e 36 Ticker error_update;
CasperBerkhout 0:4141aef83f4b 37
CasperBerkhout 0:4141aef83f4b 38
CasperBerkhout 0:4141aef83f4b 39 //-----------------variable decleration----------------
CasperBerkhout 0:4141aef83f4b 40 int pwm_freq = 500;
CasperBerkhout 0:4141aef83f4b 41 float set_speed;
CasperBerkhout 0:4141aef83f4b 42 float reference_pos;
CasperBerkhout 0:4141aef83f4b 43
CasperBerkhout 0:4141aef83f4b 44
CasperBerkhout 0:4141aef83f4b 45
CasperBerkhout 0:4141aef83f4b 46 double M1_home;
CasperBerkhout 0:4141aef83f4b 47 double M1_error_pos = 0;
CasperBerkhout 1:d7299175a12e 48 float M1_Kp = 2;
CasperBerkhout 1:d7299175a12e 49 float M1_Ki = 4;
CasperBerkhout 3:455b79d42636 50 float M1_Kd = 0.19;
CasperBerkhout 0:4141aef83f4b 51 double M1_e_int=0;
CasperBerkhout 0:4141aef83f4b 52 double M1_e_prior=0;
CasperBerkhout 0:4141aef83f4b 53
CasperBerkhout 0:4141aef83f4b 54 double M2_home;
CasperBerkhout 0:4141aef83f4b 55 double M2_error_pos = 0;
CasperBerkhout 4:de0923cf6bcc 56 float M2_Kp = 1.5;
CasperBerkhout 4:de0923cf6bcc 57 float M2_Ki = 0.5;
CasperBerkhout 1:d7299175a12e 58 float M2_Kd = 0;
CasperBerkhout 0:4141aef83f4b 59 double M2_e_int=0;
CasperBerkhout 0:4141aef83f4b 60 double M2_e_prior=0;
CasperBerkhout 0:4141aef83f4b 61
CasperBerkhout 2:c7369b41f7ae 62 double setpoint = 0;
CasperBerkhout 2:c7369b41f7ae 63
CasperBerkhout 2:c7369b41f7ae 64 double M1_rel_pos;
CasperBerkhout 2:c7369b41f7ae 65 double M2_rel_pos;
CasperBerkhout 2:c7369b41f7ae 66
CasperBerkhout 0:4141aef83f4b 67 float Ts = 0.002; //500hz sample freq
CasperBerkhout 0:4141aef83f4b 68
CasperBerkhout 1:d7299175a12e 69 bool M1homflag;
CasperBerkhout 1:d7299175a12e 70 bool M2homflag;
CasperBerkhout 1:d7299175a12e 71 bool Homstartflag;
CasperBerkhout 1:d7299175a12e 72
CasperBerkhout 1:d7299175a12e 73
CasperBerkhout 0:4141aef83f4b 74
CasperBerkhout 0:4141aef83f4b 75
CasperBerkhout 0:4141aef83f4b 76 void kinemtaica(double q1, double q2, double vdx, double vdy, double &q1_new, double &q2_new){
CasperBerkhout 0:4141aef83f4b 77 double q1_dot = (2.5*cos(q1+q2))/(sin(q2)) *vdx + (2.5*sin(q1+q2))/(sin(q2))*vdy;
CasperBerkhout 0:4141aef83f4b 78 double q2_dot = -(0.3*cos(q1+q2)+0.4*cos(q1))/(0.12*sin(q2))*vdx -(0.3*sin(q1+q2)+0.4*sin(q2))/(0.12*sin(q2))*vdy;
CasperBerkhout 0:4141aef83f4b 79 q1_new = q1 +q1_dot*Ts;
CasperBerkhout 0:4141aef83f4b 80 q2_new = q2 +q2_dot*Ts;
CasperBerkhout 0:4141aef83f4b 81 return;
CasperBerkhout 0:4141aef83f4b 82 }
CasperBerkhout 0:4141aef83f4b 83
CasperBerkhout 0:4141aef83f4b 84 float PID(double e, const double Kp, const double Ki, const double Kd, double Ts, double &e_int, double &e_prior){ //PID calculator
CasperBerkhout 0:4141aef83f4b 85 e_int += Ts*e;
CasperBerkhout 0:4141aef83f4b 86 double e_diff = (e-e_prior)/Ts;
CasperBerkhout 0:4141aef83f4b 87 e_prior = e;
CasperBerkhout 0:4141aef83f4b 88 double e_diff_filter = bqlowpass.step(e_diff);
CasperBerkhout 0:4141aef83f4b 89 return(Kp*e+Ki*e_int+Kd*e_diff_filter);
CasperBerkhout 0:4141aef83f4b 90 }
CasperBerkhout 0:4141aef83f4b 91
CasperBerkhout 0:4141aef83f4b 92 void M1_control(){
CasperBerkhout 0:4141aef83f4b 93
CasperBerkhout 0:4141aef83f4b 94 //call PID func and set new motor speed
CasperBerkhout 0:4141aef83f4b 95 set_speed = PID(M1_error_pos,M1_Kp,M1_Ki,M1_Kd,Ts,M1_e_int,M1_e_prior);
CasperBerkhout 0:4141aef83f4b 96 if(set_speed > 0){
CasperBerkhout 0:4141aef83f4b 97 M1_speed.write(abs(set_speed));
CasperBerkhout 0:4141aef83f4b 98 M1_direction.write(0);
CasperBerkhout 0:4141aef83f4b 99 }
CasperBerkhout 0:4141aef83f4b 100 else if (set_speed < 0){
CasperBerkhout 0:4141aef83f4b 101 M1_speed.write(abs(set_speed));
CasperBerkhout 0:4141aef83f4b 102 M1_direction.write(1);
CasperBerkhout 0:4141aef83f4b 103 }
CasperBerkhout 0:4141aef83f4b 104 else{M1_speed.write(0);}
CasperBerkhout 4:de0923cf6bcc 105
CasperBerkhout 0:4141aef83f4b 106 }
CasperBerkhout 0:4141aef83f4b 107
CasperBerkhout 0:4141aef83f4b 108 void M2_control(){
CasperBerkhout 0:4141aef83f4b 109 set_speed = PID(M2_error_pos,M2_Kp,M2_Ki,M2_Kd,Ts,M2_e_int,M2_e_prior);
CasperBerkhout 0:4141aef83f4b 110 if(set_speed > 0){
CasperBerkhout 0:4141aef83f4b 111 M2_speed.write(abs(set_speed));
CasperBerkhout 0:4141aef83f4b 112 M2_direction.write(0);
CasperBerkhout 0:4141aef83f4b 113 }
CasperBerkhout 0:4141aef83f4b 114 else if (set_speed < 0){
CasperBerkhout 0:4141aef83f4b 115 M2_speed.write(abs(set_speed));
CasperBerkhout 0:4141aef83f4b 116 M2_direction.write(1);
CasperBerkhout 0:4141aef83f4b 117 }
CasperBerkhout 0:4141aef83f4b 118 else{M2_speed.write(0);}
CasperBerkhout 4:de0923cf6bcc 119 pc.printf("M2 integral = %f\n\r", M2_e_int);
CasperBerkhout 0:4141aef83f4b 120 }
CasperBerkhout 0:4141aef83f4b 121
CasperBerkhout 2:c7369b41f7ae 122 void homing_system () {
CasperBerkhout 2:c7369b41f7ae 123 LimSW1.mode(PullDown);
CasperBerkhout 2:c7369b41f7ae 124 LimSW2.mode(PullDown);
CasperBerkhout 2:c7369b41f7ae 125 M1_speed.write(0);
CasperBerkhout 2:c7369b41f7ae 126 M2_speed.write(0);
CasperBerkhout 2:c7369b41f7ae 127 M1_direction.write(0);
CasperBerkhout 2:c7369b41f7ae 128 M2_direction.write(1);
CasperBerkhout 2:c7369b41f7ae 129
CasperBerkhout 2:c7369b41f7ae 130 while(1){
CasperBerkhout 3:455b79d42636 131 if (HomStart.read() == 0){
CasperBerkhout 3:455b79d42636 132 setpoint += 0.003; //move setpoint 0.2 radian per second (at 100hz)
CasperBerkhout 4:de0923cf6bcc 133 pc.printf("Homing... \n\r");
CasperBerkhout 4:de0923cf6bcc 134 }
CasperBerkhout 4:de0923cf6bcc 135
CasperBerkhout 4:de0923cf6bcc 136 double M1_rel_pos = enc1.getPulses()/32.0/131.25*2.0*3.1416;
CasperBerkhout 4:de0923cf6bcc 137 double M2_rel_pos = enc2.getPulses()/32.0/131.25*2.0*3.1416;
CasperBerkhout 3:455b79d42636 138 if(LimSW1.read() == 0){
CasperBerkhout 3:455b79d42636 139 M1_error_pos = 1.5*setpoint - M1_rel_pos;
CasperBerkhout 3:455b79d42636 140 }
CasperBerkhout 3:455b79d42636 141 if(LimSW2.read() == 0){
CasperBerkhout 3:455b79d42636 142 M2_error_pos = -(0.5*setpoint - M2_rel_pos);
CasperBerkhout 3:455b79d42636 143 }
CasperBerkhout 3:455b79d42636 144 M1_control();
CasperBerkhout 3:455b79d42636 145 M2_control();
CasperBerkhout 4:de0923cf6bcc 146
CasperBerkhout 4:de0923cf6bcc 147
CasperBerkhout 2:c7369b41f7ae 148 if(LimSW1.read() == 1){
CasperBerkhout 2:c7369b41f7ae 149 M1_error_pos = 0;
CasperBerkhout 2:c7369b41f7ae 150 M1_speed.write(0);
CasperBerkhout 2:c7369b41f7ae 151 M1_home = enc1.getPulses()/32.0/131.25*2.0*3.1416; //in radians
CasperBerkhout 2:c7369b41f7ae 152 }
CasperBerkhout 2:c7369b41f7ae 153 if (LimSW2.read() == 1) {
CasperBerkhout 2:c7369b41f7ae 154 M2_error_pos = 0;
CasperBerkhout 2:c7369b41f7ae 155 M2_speed.write(0);
CasperBerkhout 2:c7369b41f7ae 156 M2_home = enc2.getPulses()/32.0/131.25*2.0*3.1416; //in radians
CasperBerkhout 2:c7369b41f7ae 157 }
CasperBerkhout 2:c7369b41f7ae 158
CasperBerkhout 2:c7369b41f7ae 159 if (LimSW1.read() == 1 && LimSW2.read() ==1) {
CasperBerkhout 2:c7369b41f7ae 160 pc.printf("Homing finished \n\r");
CasperBerkhout 2:c7369b41f7ae 161 M1_speed.write(0);
CasperBerkhout 2:c7369b41f7ae 162 M2_speed.write(0);
CasperBerkhout 2:c7369b41f7ae 163 wait(0.5);
CasperBerkhout 2:c7369b41f7ae 164 M1_home = enc1.getPulses()/32.0/131.25*2.0*3.1416; //in radians
CasperBerkhout 2:c7369b41f7ae 165 M2_home = enc2.getPulses()/32.0/131.25*2.0*3.1416; //in radians
CasperBerkhout 4:de0923cf6bcc 166 //break;
CasperBerkhout 4:de0923cf6bcc 167 while(1); //stop after homing.
CasperBerkhout 2:c7369b41f7ae 168 }
CasperBerkhout 4:de0923cf6bcc 169 wait(0.01);
CasperBerkhout 2:c7369b41f7ae 170 }
CasperBerkhout 0:4141aef83f4b 171
CasperBerkhout 2:c7369b41f7ae 172 }
CasperBerkhout 0:4141aef83f4b 173
CasperBerkhout 0:4141aef83f4b 174 void scopesend(){
CasperBerkhout 0:4141aef83f4b 175
CasperBerkhout 0:4141aef83f4b 176
CasperBerkhout 0:4141aef83f4b 177
CasperBerkhout 0:4141aef83f4b 178 }
CasperBerkhout 0:4141aef83f4b 179 void StopMotors(){
CasperBerkhout 0:4141aef83f4b 180 while(1){
CasperBerkhout 0:4141aef83f4b 181 M1_speed.write(0);
CasperBerkhout 0:4141aef83f4b 182 M2_speed.write(0);
CasperBerkhout 0:4141aef83f4b 183 }
CasperBerkhout 0:4141aef83f4b 184 }
CasperBerkhout 0:4141aef83f4b 185
CasperBerkhout 0:4141aef83f4b 186 void geterror(){
CasperBerkhout 0:4141aef83f4b 187 double M1_rel_pos = enc1.getPulses()/32.0/131.25*2.0*3.1416; //relative position in radians
CasperBerkhout 0:4141aef83f4b 188 double M2_rel_pos = enc2.getPulses()/32.0/131.25*2.0*3.1416; //relative position in radians
CasperBerkhout 2:c7369b41f7ae 189
CasperBerkhout 2:c7369b41f7ae 190 float Arm1_home = 122.0/180.0*3.1416;//home position of large link attached to base in radians - 112 degrees
CasperBerkhout 2:c7369b41f7ae 191 float Arm2_home = 19.0/180.0*3.1416;//home position of small link attached to base
CasperBerkhout 0:4141aef83f4b 192
CasperBerkhout 2:c7369b41f7ae 193 double M1_actual_pos = Arm1_home + (M1_rel_pos - M1_home)/2; //!!!!!!!Gearing ratio of timing belt = 2!!!!!!!!!! - Also known as angle theta
CasperBerkhout 2:c7369b41f7ae 194 double M2_actual_pos = Arm2_home + (M2_rel_pos - M2_home)/2; //!!!!!!!Gearing ratio of timing belt = 2!!!!!!!!!! - Also known as angle Alpha
CasperBerkhout 0:4141aef83f4b 195
CasperBerkhout 0:4141aef83f4b 196 double q1 = M1_actual_pos;
CasperBerkhout 2:c7369b41f7ae 197 double q2 = q1 + M2_actual_pos; //see drawing
CasperBerkhout 0:4141aef83f4b 198
CasperBerkhout 1:d7299175a12e 199 //double M1_reference_pos = 1+potmeter.read()*0.5*3.1416; //should cover the right range - radians
CasperBerkhout 3:455b79d42636 200 double M1_reference_pos = 0.5*3.1416-potmeter.read(); //should cover the right range - radians
CasperBerkhout 1:d7299175a12e 201 double M2_reference_pos = 0.5+potmeter2.read()*0.25*3.1416;
CasperBerkhout 0:4141aef83f4b 202
CasperBerkhout 3:455b79d42636 203
CasperBerkhout 1:d7299175a12e 204 //M2_error_pos = M2_reference_pos - M2_actual_pos;
CasperBerkhout 1:d7299175a12e 205 M2_error_pos = 0;
CasperBerkhout 3:455b79d42636 206 if(M1_reference_pos > Arm1_home){
CasperBerkhout 3:455b79d42636 207 M1_reference_pos = Arm1_home;
CasperBerkhout 3:455b79d42636 208 }
CasperBerkhout 3:455b79d42636 209 else{
CasperBerkhout 3:455b79d42636 210 M1_error_pos = M1_reference_pos - M1_actual_pos;
CasperBerkhout 3:455b79d42636 211 }
CasperBerkhout 3:455b79d42636 212 if(M2_reference_pos > Arm2_home){
CasperBerkhout 3:455b79d42636 213 M2_reference_pos = Arm2_home;
CasperBerkhout 3:455b79d42636 214 }
CasperBerkhout 3:455b79d42636 215 else{
CasperBerkhout 3:455b79d42636 216 M2_error_pos = M2_reference_pos - M2_actual_pos;
CasperBerkhout 3:455b79d42636 217 }
CasperBerkhout 0:4141aef83f4b 218 }
CasperBerkhout 0:4141aef83f4b 219
CasperBerkhout 0:4141aef83f4b 220 int main() {
CasperBerkhout 0:4141aef83f4b 221
CasperBerkhout 0:4141aef83f4b 222 //initialize serial comm and set motor PWM freq
CasperBerkhout 0:4141aef83f4b 223 M1_speed.period(1.0/pwm_freq);
CasperBerkhout 0:4141aef83f4b 224 M2_speed.period(1.0/pwm_freq);
CasperBerkhout 0:4141aef83f4b 225 pc.baud(115200);
CasperBerkhout 1:d7299175a12e 226 pc.printf("starting homing function now. Push button to start procedure \n\r");
CasperBerkhout 0:4141aef83f4b 227 //commence homing procedure
CasperBerkhout 0:4141aef83f4b 228 homing_system();
CasperBerkhout 1:d7299175a12e 229 pc.printf("Setting home position complete\n\r");
CasperBerkhout 0:4141aef83f4b 230 //attach all interrupt
CasperBerkhout 1:d7299175a12e 231 pc.printf("attaching interrupt tickers now \n\r");
CasperBerkhout 0:4141aef83f4b 232 button1.fall(StopMotors); //stop motor interrupt
CasperBerkhout 1:d7299175a12e 233 motor_update1.attach(&M1_control,0.01);
CasperBerkhout 1:d7299175a12e 234 motor_update2.attach(&M2_control,0.01);
CasperBerkhout 1:d7299175a12e 235 error_update.attach(&geterror,0.01);
CasperBerkhout 0:4141aef83f4b 236
CasperBerkhout 1:d7299175a12e 237 pc.printf("initialization complete - position control of motors now active\n\r");
CasperBerkhout 0:4141aef83f4b 238
CasperBerkhout 0:4141aef83f4b 239 while(1){
CasperBerkhout 0:4141aef83f4b 240
CasperBerkhout 0:4141aef83f4b 241
CasperBerkhout 0:4141aef83f4b 242 }
CasperBerkhout 0:4141aef83f4b 243
CasperBerkhout 0:4141aef83f4b 244 }