working PID + Kinematics + Motorcontrol

Dependencies:   HIDScope MODSERIAL QEI biquadFilter mbed

Committer:
cmaas
Date:
Wed Oct 31 15:08:58 2018 +0000
Revision:
2:44758d95cb0b
Parent:
0:a6f2b6cc83ca
Child:
3:4b6b3b5e3a1b
Child:
4:85770b268599
Met button besturing en correcte kp, kd waarde

Who changed what in which revision?

UserRevisionLine numberNew contents of line
cmaas 0:a6f2b6cc83ca 1 // KINEMATICS + PID + MOTOR CONTROL
cmaas 0:a6f2b6cc83ca 2
cmaas 0:a6f2b6cc83ca 3 //----------------~INITIATING-------------------------
cmaas 0:a6f2b6cc83ca 4 #include "mbed.h"
cmaas 0:a6f2b6cc83ca 5
cmaas 0:a6f2b6cc83ca 6 // KINEMATICS -- DEPENDENCIES
cmaas 0:a6f2b6cc83ca 7 #include "stdio.h"
cmaas 0:a6f2b6cc83ca 8 #define _USE_MATH_DEFINES
cmaas 0:a6f2b6cc83ca 9 #include <math.h>
cmaas 0:a6f2b6cc83ca 10 #define M_PI 3.14159265358979323846 /* pi */
cmaas 0:a6f2b6cc83ca 11
cmaas 0:a6f2b6cc83ca 12 // PID CONTROLLER -- DEPENDENCIES
cmaas 0:a6f2b6cc83ca 13 #include "BiQuad.h"
cmaas 0:a6f2b6cc83ca 14 #include "QEI.h"
cmaas 0:a6f2b6cc83ca 15 #include "MODSERIAL.h"
cmaas 0:a6f2b6cc83ca 16 #include "HIDScope.h"
cmaas 0:a6f2b6cc83ca 17 //#include "Math.h"
cmaas 0:a6f2b6cc83ca 18
cmaas 0:a6f2b6cc83ca 19 // PID CONTROLLER -- PIN DEFENITIONS
cmaas 0:a6f2b6cc83ca 20 AnalogIn button2(A4);
cmaas 2:44758d95cb0b 21 AnalogIn button1(A3);
cmaas 0:a6f2b6cc83ca 22 DigitalOut directionpin1(D7); // motor 1
cmaas 0:a6f2b6cc83ca 23 PwmOut pwmpin1(D6); // motor 1
cmaas 0:a6f2b6cc83ca 24
cmaas 0:a6f2b6cc83ca 25 QEI encoder1 (D9, D8, NC, 8400, QEI::X4_ENCODING);
cmaas 0:a6f2b6cc83ca 26 MODSERIAL pc(USBTX, USBRX);
cmaas 0:a6f2b6cc83ca 27 HIDScope scope(2);
cmaas 0:a6f2b6cc83ca 28
cmaas 0:a6f2b6cc83ca 29 // TICKERS
cmaas 0:a6f2b6cc83ca 30 Ticker ref_rot;
cmaas 0:a6f2b6cc83ca 31 Ticker show_counts;
cmaas 0:a6f2b6cc83ca 32 Ticker Scope_Data;
cmaas 0:a6f2b6cc83ca 33
cmaas 0:a6f2b6cc83ca 34 //----------------GLOBALS--------------------------
cmaas 0:a6f2b6cc83ca 35
cmaas 0:a6f2b6cc83ca 36 // CONSTANTS PID CONTROLLER
cmaas 0:a6f2b6cc83ca 37 double PI = M_PI;// CHANGE THIS INTO M_PI
cmaas 2:44758d95cb0b 38 double Kp = 14; //200 , 50
cmaas 0:a6f2b6cc83ca 39 double Ki = 0; //1, 0.5
cmaas 2:44758d95cb0b 40 double Kd = 3; //200, 10
cmaas 0:a6f2b6cc83ca 41 double Ts = 0.1; // Sample time in seconds
cmaas 0:a6f2b6cc83ca 42 double reference_rotation; //define as radians
cmaas 0:a6f2b6cc83ca 43 double motor_position;
cmaas 0:a6f2b6cc83ca 44 bool AlwaysTrue;
cmaas 0:a6f2b6cc83ca 45
cmaas 0:a6f2b6cc83ca 46 //CONSTANTS KINEMATICS
cmaas 0:a6f2b6cc83ca 47 // constants
cmaas 0:a6f2b6cc83ca 48 const float la = 0.256; // lengte actieve arm
cmaas 0:a6f2b6cc83ca 49 const float lp = 0.21; // lengte passieve arm
cmaas 0:a6f2b6cc83ca 50 const float rp = 0.052; // straal van midden end effector tot hoekpunt
cmaas 0:a6f2b6cc83ca 51 const float rm = 0.23; // straal van global midden tot motor
cmaas 0:a6f2b6cc83ca 52 const float a = 0.09; // zijde van de driehoek
cmaas 0:a6f2b6cc83ca 53 const float xas = 0.40; // afstand van motor 1 tot motor 3
cmaas 0:a6f2b6cc83ca 54 const float yas = 0.346; // afstand van xas tot motor 2
cmaas 0:a6f2b6cc83ca 55 const float thetap = 0; // rotatiehoek van de end effector
cmaas 0:a6f2b6cc83ca 56
cmaas 0:a6f2b6cc83ca 57 // motor locatie
cmaas 0:a6f2b6cc83ca 58 const int a1x = 0; //x locatie motor 1
cmaas 0:a6f2b6cc83ca 59 const int a1y = 0; //y locatie motor 1
cmaas 0:a6f2b6cc83ca 60 const float a2x = (0.5)*xas; // x locatie motor 2
cmaas 0:a6f2b6cc83ca 61 const float a2y = yas; // y locatie motor 2
cmaas 0:a6f2b6cc83ca 62 const float a3x = xas; // x locatie motor 3
cmaas 0:a6f2b6cc83ca 63 const int a3y = 0; // y locatie motor 3
cmaas 0:a6f2b6cc83ca 64
cmaas 0:a6f2b6cc83ca 65 // script voor het bepalen van de desired position aan de hand van emg (1/0)
cmaas 0:a6f2b6cc83ca 66
cmaas 0:a6f2b6cc83ca 67 // EMG OUTPUT
cmaas 0:a6f2b6cc83ca 68 int EMGxplus;
cmaas 0:a6f2b6cc83ca 69 int EMGxmin ;
cmaas 0:a6f2b6cc83ca 70 int EMGyplus;
cmaas 0:a6f2b6cc83ca 71 int EMGymin ;
cmaas 0:a6f2b6cc83ca 72
cmaas 0:a6f2b6cc83ca 73 // Dit moet experimenteel geperfectioneerd worden
cmaas 0:a6f2b6cc83ca 74 float tijdstap = 0.05; //nu wss heel langzaam, kan miss omhoog
cmaas 0:a6f2b6cc83ca 75 float v = 0.1; // snelheid kan wss ook hoger
cmaas 0:a6f2b6cc83ca 76
cmaas 0:a6f2b6cc83ca 77 float px = 0.2; //starting x
cmaas 0:a6f2b6cc83ca 78 float py = 0.155; // starting y
cmaas 0:a6f2b6cc83ca 79
cmaas 0:a6f2b6cc83ca 80 // limits (since no forward kinematics)
cmaas 0:a6f2b6cc83ca 81 float upperxlim = 0.36; //niet helemaal naar requierments ff kijken of ie groter kan
cmaas 0:a6f2b6cc83ca 82 float lowerxlim = 0.04;
cmaas 0:a6f2b6cc83ca 83 float upperylim = 0.30;
cmaas 0:a6f2b6cc83ca 84 float lowerylim = 0.04;
cmaas 0:a6f2b6cc83ca 85
cmaas 0:a6f2b6cc83ca 86
cmaas 0:a6f2b6cc83ca 87 //----------------FUNCTIONS--------------------------
cmaas 0:a6f2b6cc83ca 88
cmaas 0:a6f2b6cc83ca 89 // ~~~~~~~~~~~~~~ROBOT KINEMATICS ~~~~~~~~~~~~~~~~~~
cmaas 0:a6f2b6cc83ca 90
cmaas 0:a6f2b6cc83ca 91 // functie x positie
cmaas 0:a6f2b6cc83ca 92 float positionx(int EMGxplus,int EMGxmin)
cmaas 0:a6f2b6cc83ca 93 {
cmaas 0:a6f2b6cc83ca 94 float EMGx = EMGxplus - EMGxmin;
cmaas 0:a6f2b6cc83ca 95
cmaas 0:a6f2b6cc83ca 96 float verplaatsingx = EMGx * tijdstap * v;
cmaas 0:a6f2b6cc83ca 97 float pxnieuw = px + verplaatsingx;
cmaas 0:a6f2b6cc83ca 98 // x limit
cmaas 0:a6f2b6cc83ca 99 if (pxnieuw <= upperxlim && pxnieuw >= lowerxlim)
cmaas 0:a6f2b6cc83ca 100 {
cmaas 0:a6f2b6cc83ca 101 px = pxnieuw;
cmaas 0:a6f2b6cc83ca 102 }
cmaas 0:a6f2b6cc83ca 103 else
cmaas 0:a6f2b6cc83ca 104 {
cmaas 0:a6f2b6cc83ca 105 if (pxnieuw >= lowerxlim)
cmaas 0:a6f2b6cc83ca 106 {
cmaas 0:a6f2b6cc83ca 107 px = upperxlim;
cmaas 0:a6f2b6cc83ca 108 }
cmaas 0:a6f2b6cc83ca 109 else
cmaas 0:a6f2b6cc83ca 110 {
cmaas 0:a6f2b6cc83ca 111 px = lowerxlim;
cmaas 0:a6f2b6cc83ca 112 }
cmaas 0:a6f2b6cc83ca 113 }
cmaas 0:a6f2b6cc83ca 114 //printf("X eindpunt (%f) en verplaatsing: (%f)\n\r",px,verplaatsingx);
cmaas 0:a6f2b6cc83ca 115 return px;
cmaas 0:a6f2b6cc83ca 116 }
cmaas 0:a6f2b6cc83ca 117
cmaas 0:a6f2b6cc83ca 118
cmaas 0:a6f2b6cc83ca 119 // functie y positie
cmaas 0:a6f2b6cc83ca 120 float positiony(int EMGyplus,int EMGymin)
cmaas 0:a6f2b6cc83ca 121 {
cmaas 0:a6f2b6cc83ca 122 float EMGy = EMGyplus - EMGymin;
cmaas 0:a6f2b6cc83ca 123
cmaas 0:a6f2b6cc83ca 124 float verplaatsingy = EMGy * tijdstap * v;
cmaas 0:a6f2b6cc83ca 125 float pynieuw = py + verplaatsingy;
cmaas 0:a6f2b6cc83ca 126
cmaas 0:a6f2b6cc83ca 127 // y limit
cmaas 0:a6f2b6cc83ca 128 if (pynieuw <= upperylim && pynieuw >= lowerylim)
cmaas 0:a6f2b6cc83ca 129 {
cmaas 0:a6f2b6cc83ca 130 py = pynieuw;
cmaas 0:a6f2b6cc83ca 131 }
cmaas 0:a6f2b6cc83ca 132 else
cmaas 0:a6f2b6cc83ca 133 {
cmaas 0:a6f2b6cc83ca 134 if (pynieuw >= lowerylim)
cmaas 0:a6f2b6cc83ca 135 {
cmaas 0:a6f2b6cc83ca 136 py = upperylim;
cmaas 0:a6f2b6cc83ca 137 }
cmaas 0:a6f2b6cc83ca 138 else
cmaas 0:a6f2b6cc83ca 139 {
cmaas 0:a6f2b6cc83ca 140 py = lowerylim;
cmaas 0:a6f2b6cc83ca 141 }
cmaas 0:a6f2b6cc83ca 142 }
cmaas 0:a6f2b6cc83ca 143 //printf("Y eindpunt (%f) en verplaatsing: (%f) \n\r",py,verplaatsingy);
cmaas 0:a6f2b6cc83ca 144 return (py);
cmaas 0:a6f2b6cc83ca 145 }
cmaas 0:a6f2b6cc83ca 146
cmaas 0:a6f2b6cc83ca 147
cmaas 0:a6f2b6cc83ca 148 //~~~~~~~~~~~~CALCULATIING MOTOR ANGLES ~~~~~~~~
cmaas 0:a6f2b6cc83ca 149 // arm 1 --> reference angle motor 1
cmaas 0:a6f2b6cc83ca 150 float hoek1(float px, float py) // input: ref x, ref y
cmaas 0:a6f2b6cc83ca 151 {
cmaas 0:a6f2b6cc83ca 152 float c1x = px - rp * cos(thetap +(M_PI/6)); // x locatie hoekpunt end-effector
cmaas 0:a6f2b6cc83ca 153 float c1y = py - rp*sin(thetap+(M_PI/6)); // y locatie hoekpunt end-effector
cmaas 0:a6f2b6cc83ca 154 float alpha1 = atan2((c1y-a1y),(c1x-a1x)); // hoek tussen horizontaal en lijn van motor naar bijbehorende end-effector punt
cmaas 0:a6f2b6cc83ca 155 float psi1 = acos(( pow(la,2)-pow(lp,2)+pow((c1x-a1x),2)+pow((c1y-a1y),2))/(2*la*sqrt(pow ((c1x-a1x),2)+pow((c1y-a1y),2) ))); //Hoek tussen lijn van motor naar bijbehorende end=effector punt en actieve arm
cmaas 0:a6f2b6cc83ca 156 float a1 = alpha1 + psi1; //hoek tussen horizontaal en actieve arm
cmaas 0:a6f2b6cc83ca 157 //printf("arm 1 = %f \n\r",a1);
cmaas 0:a6f2b6cc83ca 158 return a1;
cmaas 0:a6f2b6cc83ca 159 }
cmaas 0:a6f2b6cc83ca 160
cmaas 0:a6f2b6cc83ca 161 // arm 2 --> reference angle motor 2
cmaas 0:a6f2b6cc83ca 162 float hoek2(float px, float py)
cmaas 0:a6f2b6cc83ca 163 {
cmaas 0:a6f2b6cc83ca 164 float c2x = px - rp * cos(thetap -(M_PI/2));
cmaas 0:a6f2b6cc83ca 165 float c2y = py - rp*sin(thetap-(M_PI/2));
cmaas 0:a6f2b6cc83ca 166 float alpha2 = atan2((c2y-a2y),(c2x-a2x));
cmaas 0:a6f2b6cc83ca 167 float psi2 = acos(( pow(la,2)-pow(lp,2)+pow((c2x-a2x),2)+pow((c2y-a2y),2))/(2*la*sqrt(pow ((c2x-a2x),2)+pow((c2y-a2y),2) )));
cmaas 0:a6f2b6cc83ca 168 float a2 = alpha2 + psi2;
cmaas 0:a6f2b6cc83ca 169 //printf("arm 2 = %f \n\r",a2);
cmaas 0:a6f2b6cc83ca 170 return a2;
cmaas 0:a6f2b6cc83ca 171 }
cmaas 0:a6f2b6cc83ca 172
cmaas 0:a6f2b6cc83ca 173 //arm 3 --> reference angle motor 3
cmaas 0:a6f2b6cc83ca 174 float hoek3(float px, float py)
cmaas 0:a6f2b6cc83ca 175 {
cmaas 0:a6f2b6cc83ca 176 float c3x = px - rp * cos(thetap +(5*M_PI/6));
cmaas 0:a6f2b6cc83ca 177 float c3y = py - rp*sin(thetap+(5*M_PI/6));
cmaas 0:a6f2b6cc83ca 178 float alpha3 = atan2((c3y-a3y),(c3x-a3x));
cmaas 0:a6f2b6cc83ca 179 float psi3 = acos(( pow(la,2)-pow(lp,2)+pow((c3x-a3x),2)+pow((c3y-a3y),2))/(2*la*sqrt(pow ((c3x-a3x),2)+pow((c3y-a3y),2) )));
cmaas 0:a6f2b6cc83ca 180 float a3 = alpha3 + psi3;
cmaas 0:a6f2b6cc83ca 181 //printf("arm 3 = %f \n\r",a3);
cmaas 0:a6f2b6cc83ca 182 return a3;
cmaas 0:a6f2b6cc83ca 183 }
cmaas 0:a6f2b6cc83ca 184
cmaas 0:a6f2b6cc83ca 185 // ~~~~~~~~~~~~~~PID CONTROLLER~~~~~~~~~~~~~~~~~~
cmaas 0:a6f2b6cc83ca 186
cmaas 0:a6f2b6cc83ca 187 double PID_controller(double error)
cmaas 0:a6f2b6cc83ca 188 {
cmaas 0:a6f2b6cc83ca 189 static double error_integral = 0;
cmaas 0:a6f2b6cc83ca 190 static double error_prev = error; // initialization with this value only done once!
cmaas 0:a6f2b6cc83ca 191 static BiQuad LowPassFilter(0.0640, 0.1279, 0.0640, -1.1683, 0.4241);
cmaas 0:a6f2b6cc83ca 192
cmaas 0:a6f2b6cc83ca 193 // Proportional part:
cmaas 0:a6f2b6cc83ca 194 double u_k = Kp * error;
cmaas 0:a6f2b6cc83ca 195
cmaas 0:a6f2b6cc83ca 196 // Integral part
cmaas 0:a6f2b6cc83ca 197 error_integral = error_integral + error * Ts;
cmaas 0:a6f2b6cc83ca 198 double u_i = Ki * error_integral;
cmaas 0:a6f2b6cc83ca 199
cmaas 0:a6f2b6cc83ca 200 // Derivative part
cmaas 0:a6f2b6cc83ca 201 double error_derivative = (error - error_prev)/Ts;
cmaas 0:a6f2b6cc83ca 202 double filtered_error_derivative = LowPassFilter.step(error_derivative);
cmaas 0:a6f2b6cc83ca 203 double u_d = Kd * filtered_error_derivative;
cmaas 0:a6f2b6cc83ca 204 error_prev = error;
cmaas 0:a6f2b6cc83ca 205
cmaas 0:a6f2b6cc83ca 206 // Sum all parts and return it
cmaas 0:a6f2b6cc83ca 207 return u_k + u_i + u_d;
cmaas 0:a6f2b6cc83ca 208 }
cmaas 0:a6f2b6cc83ca 209
cmaas 0:a6f2b6cc83ca 210
cmaas 0:a6f2b6cc83ca 211 // DIRECTON AND SPEED CONTROL
cmaas 0:a6f2b6cc83ca 212 void moter_control(double u)
cmaas 0:a6f2b6cc83ca 213 {
cmaas 0:a6f2b6cc83ca 214 directionpin1= u > 0.0f; //eithertrueor false
cmaas 0:a6f2b6cc83ca 215 pwmpin1= fabs(u); //pwmduty cycle canonlybepositive, floatingpoint absolute value
cmaas 0:a6f2b6cc83ca 216 }
cmaas 0:a6f2b6cc83ca 217
cmaas 0:a6f2b6cc83ca 218
cmaas 0:a6f2b6cc83ca 219 // CONTROLLING THE MOTOR
cmaas 0:a6f2b6cc83ca 220 void Motor_mover()
cmaas 0:a6f2b6cc83ca 221 {
cmaas 0:a6f2b6cc83ca 222 double motor_position = encoder1.getPulses(); //output in counts
cmaas 2:44758d95cb0b 223 double reference_rotation = hoek2(px, py);
cmaas 0:a6f2b6cc83ca 224 double error = reference_rotation - motor_position*(2*PI)/8400;
cmaas 0:a6f2b6cc83ca 225 double u = PID_controller(error);
cmaas 0:a6f2b6cc83ca 226 moter_control(u);
cmaas 0:a6f2b6cc83ca 227 }
cmaas 0:a6f2b6cc83ca 228
cmaas 0:a6f2b6cc83ca 229 //PRINT TICKER
cmaas 0:a6f2b6cc83ca 230 void PrintFlag()
cmaas 0:a6f2b6cc83ca 231 {
cmaas 0:a6f2b6cc83ca 232 AlwaysTrue = true;
cmaas 0:a6f2b6cc83ca 233 }
cmaas 0:a6f2b6cc83ca 234
cmaas 0:a6f2b6cc83ca 235 // HIDSCOPE
cmaas 0:a6f2b6cc83ca 236 void ScopeData()
cmaas 0:a6f2b6cc83ca 237 {
cmaas 0:a6f2b6cc83ca 238 double y = encoder1.getPulses();
cmaas 0:a6f2b6cc83ca 239 scope.set(0, y);
cmaas 0:a6f2b6cc83ca 240 scope.send();
cmaas 0:a6f2b6cc83ca 241 }
cmaas 0:a6f2b6cc83ca 242
cmaas 0:a6f2b6cc83ca 243
cmaas 0:a6f2b6cc83ca 244 //----------------------MAIN---------------------------------
cmaas 0:a6f2b6cc83ca 245 int main()
cmaas 0:a6f2b6cc83ca 246 {
cmaas 0:a6f2b6cc83ca 247 // ~~~~~~~~~~~~~~~~ INITIATING ~~~~~~~~~~~~
cmaas 0:a6f2b6cc83ca 248 pwmpin1.period_us(60); // setup motor
cmaas 0:a6f2b6cc83ca 249
cmaas 0:a6f2b6cc83ca 250 // setup printing service
cmaas 0:a6f2b6cc83ca 251 pc.baud(9600);
cmaas 0:a6f2b6cc83ca 252 pc.printf("test");
cmaas 0:a6f2b6cc83ca 253
cmaas 0:a6f2b6cc83ca 254 // Tickers
cmaas 0:a6f2b6cc83ca 255 //show_counts.attach(PrintFlag, 0.2);
cmaas 0:a6f2b6cc83ca 256 ref_rot.attach(Motor_mover, 0.01);
cmaas 0:a6f2b6cc83ca 257 Scope_Data.attach(ScopeData, 0.01);
cmaas 0:a6f2b6cc83ca 258
cmaas 0:a6f2b6cc83ca 259
cmaas 2:44758d95cb0b 260 while(true){
cmaas 2:44758d95cb0b 261
cmaas 2:44758d95cb0b 262
cmaas 2:44758d95cb0b 263 if (button2 == false)
cmaas 2:44758d95cb0b 264 {
cmaas 2:44758d95cb0b 265 wait(0.05f);
cmaas 2:44758d95cb0b 266
cmaas 2:44758d95cb0b 267 // berekenen positie
cmaas 2:44758d95cb0b 268 float px = positionx(1,0); // EMG: +x, -x
cmaas 2:44758d95cb0b 269 float py = positiony(1,0); // EMG: +y, -y
cmaas 2:44758d95cb0b 270 //printf("positie (%f,%f)\n\r",px,py);
cmaas 2:44758d95cb0b 271 }
cmaas 0:a6f2b6cc83ca 272
cmaas 2:44758d95cb0b 273 if (button1 == false){
cmaas 2:44758d95cb0b 274 wait(0.05f);
cmaas 2:44758d95cb0b 275 // berekenen positie
cmaas 2:44758d95cb0b 276 float px = positionx(0,1); // EMG: +x, -x
cmaas 2:44758d95cb0b 277 float py = positiony(0,1); // EMG: +y, -y
cmaas 2:44758d95cb0b 278 //printf("positie (%f,%f)\n\r",px,py);
cmaas 2:44758d95cb0b 279 }
cmaas 2:44758d95cb0b 280 }
cmaas 0:a6f2b6cc83ca 281 // berekenen hoeken
cmaas 0:a6f2b6cc83ca 282 /*
cmaas 0:a6f2b6cc83ca 283 float a1 = hoek1(px, py);
cmaas 0:a6f2b6cc83ca 284 float a2 = hoek2(px, py);
cmaas 0:a6f2b6cc83ca 285 float a3 = hoek3(px, py);
cmaas 0:a6f2b6cc83ca 286
cmaas 0:a6f2b6cc83ca 287 printf("hoek(%f,%f,%f)\n\r",a1,a2,a3);
cmaas 0:a6f2b6cc83ca 288
cmaas 0:a6f2b6cc83ca 289 return 0;
cmaas 0:a6f2b6cc83ca 290 */
cmaas 0:a6f2b6cc83ca 291 }