Ramon Waninge / Mbed 2 deprecated Milestone1

Dependencies:   FastPWM mbed QEI biquadFilter HIDScope MODSERIAL

Committer:
efvanmarrewijk
Date:
Tue Oct 30 09:17:31 2018 +0000
Revision:
28:aec0d9bdb949
Parent:
27:3430dfb4c9fb
Child:
29:d8e51f4cf080
Working version with control, motor still doesn't turn back

Who changed what in which revision?

UserRevisionLine numberNew contents of line
efvanmarrewijk 16:720365110953 1 // Inclusion of libraries
Ramonwaninge 0:3ea1bbfbeaae 2 #include "mbed.h"
efvanmarrewijk 11:3efd6a324f16 3 #include "FastPWM.h"
efvanmarrewijk 11:3efd6a324f16 4 #include "QEI.h" // Includes library for encoder
efvanmarrewijk 13:6556cd086d07 5 #include "MODSERIAL.h"
efvanmarrewijk 13:6556cd086d07 6 #include "HIDScope.h"
efvanmarrewijk 13:6556cd086d07 7 #include "BiQuad.h"
Ramonwaninge 0:3ea1bbfbeaae 8
efvanmarrewijk 14:e21cb701ccb8 9 // Input
efvanmarrewijk 27:3430dfb4c9fb 10 AnalogIn pot1(A1);
efvanmarrewijk 27:3430dfb4c9fb 11 AnalogIn pot2(A2);
efvanmarrewijk 21:363271dcfe1f 12 InterruptIn button1(D0);
efvanmarrewijk 21:363271dcfe1f 13 InterruptIn button2(D1);
efvanmarrewijk 21:363271dcfe1f 14 InterruptIn emergencybutton(SW2); /* This is not yet implemented!
efvanmarrewijk 21:363271dcfe1f 15 The button SW2 on the K64F is the emergency button: if you press this,
efvanmarrewijk 21:363271dcfe1f 16 everything will abort as soon as possible
efvanmarrewijk 21:363271dcfe1f 17 */
efvanmarrewijk 21:363271dcfe1f 18
efvanmarrewijk 27:3430dfb4c9fb 19 DigitalIn pin8(D8); // Encoder 1 B
efvanmarrewijk 27:3430dfb4c9fb 20 DigitalIn pin9(D9); // Encoder 1 A
efvanmarrewijk 27:3430dfb4c9fb 21 DigitalIn pin10(D10); // Encoder 2 B
efvanmarrewijk 27:3430dfb4c9fb 22 DigitalIn pin11(D11); // Encoder 2 A
efvanmarrewijk 27:3430dfb4c9fb 23 DigitalIn pin12(D12); // Encoder 3 B
efvanmarrewijk 27:3430dfb4c9fb 24 DigitalIn pin13(D13); // Encoder 3 A
efvanmarrewijk 9:65c52c1f4a57 25
efvanmarrewijk 14:e21cb701ccb8 26 // Output
efvanmarrewijk 26:b48708ed51ff 27 DigitalOut pin2(D2); // Motor 3 direction
efvanmarrewijk 26:b48708ed51ff 28 FastPWM pin3(D3); // Motor 3 pwm
efvanmarrewijk 26:b48708ed51ff 29 DigitalOut pin4(D4); // Motor 2 direction
efvanmarrewijk 26:b48708ed51ff 30 FastPWM pin5(D5); // Motor 2 pwm
efvanmarrewijk 26:b48708ed51ff 31 FastPWM pin6(D6); // Motor 1 pwm
efvanmarrewijk 26:b48708ed51ff 32 DigitalOut pin7(D7); // Motor 1 direction
efvanmarrewijk 26:b48708ed51ff 33
efvanmarrewijk 26:b48708ed51ff 34 DigitalOut greenled(LED_GREEN,1);
efvanmarrewijk 26:b48708ed51ff 35 DigitalOut redled(LED_RED,1);
efvanmarrewijk 26:b48708ed51ff 36 DigitalOut blueled(LED_BLUE,1);
Ramonwaninge 2:d8a552d1d33a 37
efvanmarrewijk 16:720365110953 38 // Utilisation of libraries
efvanmarrewijk 16:720365110953 39 MODSERIAL pc(USBTX, USBRX);
efvanmarrewijk 18:ca084c362855 40 QEI Encoder1(D11,D10,NC,4200); // Counterclockwise motor rotation is the positive direction
efvanmarrewijk 18:ca084c362855 41 QEI Encoder2(D9,D8,NC,4200); // Counterclockwise motor rotation is the positive direction
efvanmarrewijk 18:ca084c362855 42 QEI Encoder3(D13,D12,NC,4200); // Counterclockwise motor rotation is the positive direction
efvanmarrewijk 20:695140b8db2f 43 Ticker motor;
efvanmarrewijk 24:d255752065d1 44 Ticker encoders;
efvanmarrewijk 9:65c52c1f4a57 45
efvanmarrewijk 16:720365110953 46 // Global variables
efvanmarrewijk 24:d255752065d1 47 const float pi = 3.14159265358979;
efvanmarrewijk 25:76e9e5597416 48 float u3 = 0.0; // Normalised variable for the movement of motor 3
efvanmarrewijk 24:d255752065d1 49 const float fCountsRad = 4200.0;
efvanmarrewijk 27:3430dfb4c9fb 50 const double dt = 0.5;
efvanmarrewijk 26:b48708ed51ff 51 const double Kp = 17.5; // given value is 17.5
efvanmarrewijk 26:b48708ed51ff 52 const double Ki = 1.02; // given value is 1.02
efvanmarrewijk 26:b48708ed51ff 53 //const double Ts = 0.0025; // Sample time in seconds
efvanmarrewijk 16:720365110953 54
efvanmarrewijk 16:720365110953 55 // Functions
efvanmarrewijk 28:aec0d9bdb949 56 //Subfunctions
efvanmarrewijk 27:3430dfb4c9fb 57 int Counts1input()
efvanmarrewijk 27:3430dfb4c9fb 58 { int counts1;
efvanmarrewijk 27:3430dfb4c9fb 59 counts1 = Encoder1.getPulses();
efvanmarrewijk 27:3430dfb4c9fb 60 return counts1;
efvanmarrewijk 27:3430dfb4c9fb 61 }
efvanmarrewijk 27:3430dfb4c9fb 62 int Counts2input()
efvanmarrewijk 27:3430dfb4c9fb 63 { int counts2;
efvanmarrewijk 27:3430dfb4c9fb 64 counts2 = Encoder2.getPulses();
efvanmarrewijk 27:3430dfb4c9fb 65 return counts2;
efvanmarrewijk 27:3430dfb4c9fb 66 }
efvanmarrewijk 27:3430dfb4c9fb 67 int Counts3input()
efvanmarrewijk 27:3430dfb4c9fb 68 { int counts3;
efvanmarrewijk 27:3430dfb4c9fb 69 counts3 = Encoder3.getPulses();
efvanmarrewijk 27:3430dfb4c9fb 70 return counts3;
efvanmarrewijk 27:3430dfb4c9fb 71 }
efvanmarrewijk 27:3430dfb4c9fb 72
efvanmarrewijk 27:3430dfb4c9fb 73 float CurrentAngle(float counts)
efvanmarrewijk 27:3430dfb4c9fb 74 { float angle = ((float)counts*2.0*pi)/fCountsRad;
efvanmarrewijk 27:3430dfb4c9fb 75 while (angle > pi)
efvanmarrewijk 27:3430dfb4c9fb 76 { angle = angle - 2.0*pi;
efvanmarrewijk 27:3430dfb4c9fb 77 }
efvanmarrewijk 27:3430dfb4c9fb 78 while (angle < pi)
efvanmarrewijk 27:3430dfb4c9fb 79 { angle = angle + 2.0*pi;
efvanmarrewijk 27:3430dfb4c9fb 80 }
efvanmarrewijk 27:3430dfb4c9fb 81 return angle;
efvanmarrewijk 27:3430dfb4c9fb 82 }
efvanmarrewijk 27:3430dfb4c9fb 83
efvanmarrewijk 27:3430dfb4c9fb 84 double ErrorCalc(double yref,double CurAngle)
efvanmarrewijk 27:3430dfb4c9fb 85 { double error = yref - CurAngle;
efvanmarrewijk 28:aec0d9bdb949 86 return error;
efvanmarrewijk 27:3430dfb4c9fb 87 }
efvanmarrewijk 27:3430dfb4c9fb 88
efvanmarrewijk 27:3430dfb4c9fb 89 double Pcontroller(double yref,double CurAngle)
efvanmarrewijk 27:3430dfb4c9fb 90 { double error = ErrorCalc(yref,CurAngle);
efvanmarrewijk 27:3430dfb4c9fb 91 //double Kp = 50.0*pot1; // Normalised variable for value of potmeter 1
efvanmarrewijk 27:3430dfb4c9fb 92 // Proportional part:
efvanmarrewijk 27:3430dfb4c9fb 93 double u_k = Kp * error;
efvanmarrewijk 27:3430dfb4c9fb 94 // Sum all parts and return it
efvanmarrewijk 27:3430dfb4c9fb 95 //pc.printf("error: %d",error);
efvanmarrewijk 27:3430dfb4c9fb 96 return u_k;
efvanmarrewijk 27:3430dfb4c9fb 97 }
efvanmarrewijk 27:3430dfb4c9fb 98
efvanmarrewijk 27:3430dfb4c9fb 99 double PIcontroller(double yref,double CurAngle)
efvanmarrewijk 27:3430dfb4c9fb 100 { double error = yref - CurAngle;
efvanmarrewijk 27:3430dfb4c9fb 101 static double error_integral = 0;
efvanmarrewijk 27:3430dfb4c9fb 102 // Proportional part:
efvanmarrewijk 27:3430dfb4c9fb 103 double u_k = Kp * error;
efvanmarrewijk 27:3430dfb4c9fb 104 // Integral part
efvanmarrewijk 27:3430dfb4c9fb 105 error_integral = error_integral + error * dt;
efvanmarrewijk 27:3430dfb4c9fb 106 double u_i = Ki * error_integral;
efvanmarrewijk 27:3430dfb4c9fb 107 // Sum all parts and return it
efvanmarrewijk 27:3430dfb4c9fb 108 return u_k + u_i;
efvanmarrewijk 27:3430dfb4c9fb 109 }
efvanmarrewijk 27:3430dfb4c9fb 110
efvanmarrewijk 27:3430dfb4c9fb 111
efvanmarrewijk 27:3430dfb4c9fb 112 void turn1() // main function, all below functions with an extra tab are called
efvanmarrewijk 26:b48708ed51ff 113 {
efvanmarrewijk 27:3430dfb4c9fb 114 double refvalue1 = pi/4;
efvanmarrewijk 27:3430dfb4c9fb 115 int counts1 = Counts1input();
efvanmarrewijk 27:3430dfb4c9fb 116 float angle1 = CurrentAngle(counts1);
efvanmarrewijk 27:3430dfb4c9fb 117 double PIcontr = PIcontroller(refvalue1,angle1);
efvanmarrewijk 27:3430dfb4c9fb 118 double error = ErrorCalc(refvalue1,angle1);
efvanmarrewijk 27:3430dfb4c9fb 119
efvanmarrewijk 27:3430dfb4c9fb 120 pin6 = fabs(PIcontr)/pi;
efvanmarrewijk 27:3430dfb4c9fb 121 if (error > 0)
efvanmarrewijk 26:b48708ed51ff 122 { pin7 = true;
efvanmarrewijk 24:d255752065d1 123 }
efvanmarrewijk 27:3430dfb4c9fb 124 else if (error < 0)
efvanmarrewijk 26:b48708ed51ff 125 { pin7 = false;
efvanmarrewijk 27:3430dfb4c9fb 126 }
efvanmarrewijk 26:b48708ed51ff 127 //pc.printf("%i\r\n",refvalue1);
efvanmarrewijk 26:b48708ed51ff 128 //pc.printf("Counts1,2,3: %i Angle1,2,3: %f \r\n",counts1,angle1);
efvanmarrewijk 18:ca084c362855 129 }
efvanmarrewijk 26:b48708ed51ff 130
efvanmarrewijk 25:76e9e5597416 131 /*double RefVelocity(float pot)
efvanmarrewijk 25:76e9e5597416 132 { // Returns reference velocity in rad/s.
efvanmarrewijk 25:76e9e5597416 133 // Positive value means clockwise rotation.
efvanmarrewijk 25:76e9e5597416 134 const float maxVelocity=8.4; // in rad/s of course!
efvanmarrewijk 25:76e9e5597416 135 double RefVel; // in rad/s
efvanmarrewijk 25:76e9e5597416 136
efvanmarrewijk 25:76e9e5597416 137 if (button1 == 1)
efvanmarrewijk 25:76e9e5597416 138 { // Clockwise rotation
efvanmarrewijk 25:76e9e5597416 139 RefVel = pot*maxVelocity;
efvanmarrewijk 25:76e9e5597416 140 }
efvanmarrewijk 11:3efd6a324f16 141 else
efvanmarrewijk 25:76e9e5597416 142 { // Counterclockwise rotation
efvanmarrewijk 25:76e9e5597416 143 RefVel = -1*pot*maxVelocity;
efvanmarrewijk 14:e21cb701ccb8 144 }
efvanmarrewijk 25:76e9e5597416 145 return RefVel;
Ramonwaninge 3:d39285fdd103 146 }
efvanmarrewijk 25:76e9e5597416 147 */
efvanmarrewijk 25:76e9e5597416 148
efvanmarrewijk 25:76e9e5597416 149 /*
efvanmarrewijk 25:76e9e5597416 150 double ActualPosition(int counts, int offsetcounts)
efvanmarrewijk 25:76e9e5597416 151 { // After calibration, the counts are returned to 0;
efvanmarrewijk 25:76e9e5597416 152 double MotorPos = - (counts - offsetcounts) / dCountsRad;
efvanmarrewijk 25:76e9e5597416 153 // minus sign to correct for direction convention
efvanmarrewijk 25:76e9e5597416 154 return MotorPos;
efvanmarrewijk 25:76e9e5597416 155 }
efvanmarrewijk 25:76e9e5597416 156 */
efvanmarrewijk 11:3efd6a324f16 157
efvanmarrewijk 26:b48708ed51ff 158 void Emergency()
efvanmarrewijk 26:b48708ed51ff 159 { // Emgergency, if SW2 on biorobotics is pressed, everything will instantly abort and a red light goes on
efvanmarrewijk 26:b48708ed51ff 160 greenled = 1;
efvanmarrewijk 26:b48708ed51ff 161 blueled = 1;
efvanmarrewijk 26:b48708ed51ff 162 redled = 0;
efvanmarrewijk 26:b48708ed51ff 163 pin3 = 0;
efvanmarrewijk 26:b48708ed51ff 164 pin5 = 0;
efvanmarrewijk 26:b48708ed51ff 165 pin6 = 0;
efvanmarrewijk 26:b48708ed51ff 166 exit (0); //Abort mission!!
efvanmarrewijk 26:b48708ed51ff 167 }
efvanmarrewijk 26:b48708ed51ff 168
efvanmarrewijk 16:720365110953 169 // Main program
efvanmarrewijk 11:3efd6a324f16 170 int main()
efvanmarrewijk 18:ca084c362855 171 {
efvanmarrewijk 26:b48708ed51ff 172 pc.baud(115200);
efvanmarrewijk 18:ca084c362855 173
efvanmarrewijk 25:76e9e5597416 174 pin3.period(0.1);
efvanmarrewijk 25:76e9e5597416 175 pin5.period(0.1);
efvanmarrewijk 25:76e9e5597416 176 pin6.period(0.1);
efvanmarrewijk 25:76e9e5597416 177 motor.attach(turn1,dt);
efvanmarrewijk 28:aec0d9bdb949 178
efvanmarrewijk 26:b48708ed51ff 179 emergencybutton.rise(Emergency); //If the button is pressed, stop program
efvanmarrewijk 17:0ae9e8c958f8 180
efvanmarrewijk 16:720365110953 181 while (true)
efvanmarrewijk 25:76e9e5597416 182 {
efvanmarrewijk 27:3430dfb4c9fb 183 // Nothing here
Ramonwaninge 3:d39285fdd103 184 }
Ramonwaninge 0:3ea1bbfbeaae 185 }