StateMachine PTR

Dependencies:   MODSERIAL QEI MovingAverage biquadFilter mbed

Committer:
rubenlucas
Date:
Wed Oct 31 09:03:51 2018 +0000
Revision:
6:d7ae5f8fd460
Parent:
5:cbcff21e74a0
Child:
7:f4f0939f9df3
version 3

Who changed what in which revision?

UserRevisionLine numberNew contents of line
rubenlucas 2:c2ae5044ec82 1 #include "mbed.h"
rubenlucas 2:c2ae5044ec82 2 #include "math.h"
rubenlucas 2:c2ae5044ec82 3 #include "MODSERIAL.h"
rubenlucas 2:c2ae5044ec82 4 #include "QEI.h"
rubenlucas 2:c2ae5044ec82 5 #include "BiQuad.h"
rubenlucas 3:97cac1d5ba8a 6 #include "MovingAverage.h"
rubenlucas 3:97cac1d5ba8a 7 #define NSAMPLE 200
rubenlucas 3:97cac1d5ba8a 8
rubenlucas 2:c2ae5044ec82 9 //states
rubenlucas 3:97cac1d5ba8a 10 enum States {Waiting, Homing, Emergency, EMGCal, MotorCal, Operation, Demo};
rubenlucas 2:c2ae5044ec82 11
rubenlucas 2:c2ae5044ec82 12 // Global variables
rubenlucas 2:c2ae5044ec82 13 States CurrentState;
rubenlucas 2:c2ae5044ec82 14 Ticker TickerLoop;
rubenlucas 2:c2ae5044ec82 15 Timer TimerLoop;
rubenlucas 2:c2ae5044ec82 16
rubenlucas 2:c2ae5044ec82 17 //Communication
rubenlucas 2:c2ae5044ec82 18 MODSERIAL pc(USBTX,USBRX);
rubenlucas 3:97cac1d5ba8a 19 QEI Encoder1(D10,D11,NC,32); // Encoder motor q1 (arm)
rubenlucas 3:97cac1d5ba8a 20 QEI Encoder2(D12,D13,NC,32); // Encoder motor q2 (end-effector)
rubenlucas 2:c2ae5044ec82 21
rubenlucas 3:97cac1d5ba8a 22 //EMG settings
rubenlucas 3:97cac1d5ba8a 23 AnalogIn emg0(A0); //Biceps Left
rubenlucas 3:97cac1d5ba8a 24 AnalogIn emg1(A1); //Biceps Right
rubenlucas 3:97cac1d5ba8a 25 MovingAverage <double>Movag_LB(NSAMPLE,0.0); //Make Moving Average, Define NSAMPLE above
rubenlucas 3:97cac1d5ba8a 26 MovingAverage <double>Movag_RB(NSAMPLE,0.0);
rubenlucas 3:97cac1d5ba8a 27
rubenlucas 3:97cac1d5ba8a 28 // filters
rubenlucas 3:97cac1d5ba8a 29 //Make Biquad filters Left(a0, a1, a2, b1, b2)
rubenlucas 3:97cac1d5ba8a 30 BiQuadChain bqc1; //chain voor High Pass en Notch
rubenlucas 3:97cac1d5ba8a 31 BiQuad bq1(0.39131200825291007, -0.7826240165058201, 0.39131200825291007, -0.36950493743858204, 0.1957430955730582); //High Pass Filter
rubenlucas 3:97cac1d5ba8a 32 BiQuad bq2(9.91104e-01, -1.60364e+00, 9.91104e-01, -1.60364e+00, 9.82207e-01); //Notch Filter
rubenlucas 3:97cac1d5ba8a 33 //Make Biquad filters Right
rubenlucas 3:97cac1d5ba8a 34 BiQuadChain bqc2; //chain voor High Pass en Notch
rubenlucas 3:97cac1d5ba8a 35 BiQuad bq3(0.39131200825291007, -0.7826240165058201, 0.39131200825291007, -0.36950493743858204, 0.1957430955730582); //High Pass Filter
rubenlucas 3:97cac1d5ba8a 36 BiQuad bq4(9.91104e-01, -1.60364e+00, 9.91104e-01, -1.60364e+00, 9.82207e-01); //Notch Filter
rubenlucas 3:97cac1d5ba8a 37
rubenlucas 3:97cac1d5ba8a 38
rubenlucas 3:97cac1d5ba8a 39 //Global pin variables Motors 1
rubenlucas 3:97cac1d5ba8a 40 PwmOut PwmPin1(D5);
rubenlucas 3:97cac1d5ba8a 41 DigitalOut DirectionPin1(D4);
rubenlucas 3:97cac1d5ba8a 42
rubenlucas 3:97cac1d5ba8a 43 //Global pin variables Motors 2
rubenlucas 3:97cac1d5ba8a 44 PwmOut PwmPin2(D6);
rubenlucas 3:97cac1d5ba8a 45 DigitalOut DirectionPin2(D7);
rubenlucas 2:c2ae5044ec82 46
rubenlucas 2:c2ae5044ec82 47 //Output LED
rubenlucas 2:c2ae5044ec82 48 DigitalOut LedRed (LED_RED);
rubenlucas 2:c2ae5044ec82 49 DigitalOut LedGreen (LED_GREEN);
rubenlucas 2:c2ae5044ec82 50 DigitalOut LedBlue (LED_BLUE);
rubenlucas 2:c2ae5044ec82 51
rubenlucas 3:97cac1d5ba8a 52 // Buttons
rubenlucas 6:d7ae5f8fd460 53 DigitalIn BUTSW2(SW2);
rubenlucas 3:97cac1d5ba8a 54 DigitalIn BUTSW3(SW3);
rubenlucas 3:97cac1d5ba8a 55 DigitalIn BUT1(D8);
rubenlucas 3:97cac1d5ba8a 56 DigitalIn BUT2(D9);
rubenlucas 2:c2ae5044ec82 57
rubenlucas 3:97cac1d5ba8a 58 //Constant variables
rubenlucas 3:97cac1d5ba8a 59 const float L0 = 0.1; // Distance between origin frame and joint 1 [m[
rubenlucas 3:97cac1d5ba8a 60 const float L1 = 0.326; // Length link 1 (shaft to shaft) [m]
rubenlucas 3:97cac1d5ba8a 61 const float L2 = 0.209; // Length link 2 (end-effector length) [m]
rubenlucas 4:4728763bbb44 62 const double Ts = 0.002; //Sampling time 500 Hz
rubenlucas 3:97cac1d5ba8a 63
rubenlucas 3:97cac1d5ba8a 64
rubenlucas 3:97cac1d5ba8a 65 // Volatile variables
rubenlucas 3:97cac1d5ba8a 66 //EMG
rubenlucas 3:97cac1d5ba8a 67 volatile bool EMGBoolLeft; // Boolean EMG 1 (left)
rubenlucas 3:97cac1d5ba8a 68 volatile bool EMGBoolRight; // Boolean EMG 2 (right)
rubenlucas 3:97cac1d5ba8a 69 volatile double LeftBicepsOut; // Final value left of processed EMG
rubenlucas 3:97cac1d5ba8a 70 volatile double RightBicepsOut; // Final value right of processed EMG
rubenlucas 3:97cac1d5ba8a 71 volatile double ThresholdLeft = 1; //Threshold to compare with value (start off with max value = 1)
rubenlucas 3:97cac1d5ba8a 72 volatile double ThresholdRight = 1; //Threshold to compare with value (start off with max value = 1)
rubenlucas 3:97cac1d5ba8a 73
rubenlucas 6:d7ae5f8fd460 74 // Reference positions
rubenlucas 6:d7ae5f8fd460 75 volatile float q1Ref = 0;
rubenlucas 6:d7ae5f8fd460 76 volatile float q2Ref = 0;
rubenlucas 3:97cac1d5ba8a 77
rubenlucas 3:97cac1d5ba8a 78 //Motors
rubenlucas 3:97cac1d5ba8a 79 volatile float q1; // Current angle of motor 1 (arm)
rubenlucas 3:97cac1d5ba8a 80 volatile float q2; // Current angle of motor 2 (end-effector)
rubenlucas 3:97cac1d5ba8a 81 volatile float MotorValue1; // Inputvalue to set motor 1
rubenlucas 3:97cac1d5ba8a 82 volatile float MotorValue2; // Inputvalue to set motor 2
rubenlucas 3:97cac1d5ba8a 83
rubenlucas 3:97cac1d5ba8a 84 //Inverse kinematics
rubenlucas 3:97cac1d5ba8a 85 volatile float VdesX; // Desired velocity in x direction
rubenlucas 3:97cac1d5ba8a 86 volatile float VdesY; // Desired velocity in y direction
rubenlucas 3:97cac1d5ba8a 87 volatile float Error1; // Difference in reference angle and current angle motor 1
rubenlucas 3:97cac1d5ba8a 88 volatile float Error2; // Difference in reference angle and current angle motor 2
rubenlucas 3:97cac1d5ba8a 89
rubenlucas 6:d7ae5f8fd460 90 //Print to screen
rubenlucas 6:d7ae5f8fd460 91 volatile int PrintFlag = false;
rubenlucas 6:d7ae5f8fd460 92 volatile int CounterPrint = 0;
rubenlucas 2:c2ae5044ec82 93
rubenlucas 2:c2ae5044ec82 94
rubenlucas 3:97cac1d5ba8a 95 //------------------------------------------------------------------------------
rubenlucas 2:c2ae5044ec82 96 //------------------------------------------------------------------------------
rubenlucas 2:c2ae5044ec82 97
rubenlucas 6:d7ae5f8fd460 98 void PrintToScreen()
rubenlucas 6:d7ae5f8fd460 99 {
rubenlucas 6:d7ae5f8fd460 100 CounterPrint++;
rubenlucas 6:d7ae5f8fd460 101 if (CounterPrint == 100)
rubenlucas 6:d7ae5f8fd460 102 {
rubenlucas 6:d7ae5f8fd460 103 PrintFlag = true;
rubenlucas 6:d7ae5f8fd460 104 CounterPrint = 0;
rubenlucas 6:d7ae5f8fd460 105 }
rubenlucas 6:d7ae5f8fd460 106 }
rubenlucas 6:d7ae5f8fd460 107
rubenlucas 6:d7ae5f8fd460 108 // Function to set motors off
rubenlucas 6:d7ae5f8fd460 109 void SetMotorsOff()
rubenlucas 6:d7ae5f8fd460 110 {
rubenlucas 6:d7ae5f8fd460 111 // Turn motors off
rubenlucas 6:d7ae5f8fd460 112 PwmPin1 = 0;
rubenlucas 6:d7ae5f8fd460 113 PwmPin2 = 0;
rubenlucas 6:d7ae5f8fd460 114 }
rubenlucas 6:d7ae5f8fd460 115
rubenlucas 3:97cac1d5ba8a 116 // Function for processing EMG
rubenlucas 3:97cac1d5ba8a 117 void ProcessingEMG()
rubenlucas 3:97cac1d5ba8a 118 {
rubenlucas 3:97cac1d5ba8a 119 //Filter Left Biceps
rubenlucas 3:97cac1d5ba8a 120 double LB_Filter_1 = bqc1.step(emg0.read()); //High Pass + Notch
rubenlucas 3:97cac1d5ba8a 121 double LB_Rectify = fabs(LB_Filter_1); //Rectify Signal
rubenlucas 3:97cac1d5ba8a 122 Movag_LB.Insert(LB_Rectify); //Moving Average
rubenlucas 3:97cac1d5ba8a 123 LeftBicepsOut = Movag_LB.GetAverage(); //Get final value
rubenlucas 3:97cac1d5ba8a 124
rubenlucas 3:97cac1d5ba8a 125 //Filter Right Biceps
rubenlucas 3:97cac1d5ba8a 126 double RB_Filter_1 = bqc2.step(emg1.read()); //High Pass + Notch
rubenlucas 3:97cac1d5ba8a 127 double RB_Rectify = fabs(RB_Filter_1); //Rectify Signal
rubenlucas 3:97cac1d5ba8a 128 Movag_RB.Insert(RB_Rectify); //Moving Average
rubenlucas 3:97cac1d5ba8a 129 RightBicepsOut = Movag_RB.GetAverage(); //Get final value
rubenlucas 3:97cac1d5ba8a 130
rubenlucas 3:97cac1d5ba8a 131 if (LeftBicepsOut > ThresholdLeft)
rubenlucas 3:97cac1d5ba8a 132 {
rubenlucas 3:97cac1d5ba8a 133 EMGBoolLeft = true;
rubenlucas 3:97cac1d5ba8a 134 }
rubenlucas 3:97cac1d5ba8a 135 else
rubenlucas 3:97cac1d5ba8a 136 {
rubenlucas 3:97cac1d5ba8a 137 EMGBoolLeft = false;
rubenlucas 3:97cac1d5ba8a 138 }
rubenlucas 3:97cac1d5ba8a 139 if (RightBicepsOut > ThresholdRight)
rubenlucas 3:97cac1d5ba8a 140 {
rubenlucas 3:97cac1d5ba8a 141 EMGBoolRight = true;
rubenlucas 3:97cac1d5ba8a 142 }
rubenlucas 3:97cac1d5ba8a 143 else
rubenlucas 3:97cac1d5ba8a 144 {
rubenlucas 3:97cac1d5ba8a 145 EMGBoolRight = false;
rubenlucas 3:97cac1d5ba8a 146 }
rubenlucas 3:97cac1d5ba8a 147
rubenlucas 3:97cac1d5ba8a 148 }
rubenlucas 3:97cac1d5ba8a 149
rubenlucas 3:97cac1d5ba8a 150 void MeasureAll()
rubenlucas 3:97cac1d5ba8a 151 {
rubenlucas 3:97cac1d5ba8a 152 //Processing and reading EMG
rubenlucas 3:97cac1d5ba8a 153 ProcessingEMG();
rubenlucas 3:97cac1d5ba8a 154
rubenlucas 3:97cac1d5ba8a 155 //Measure current motor angles
rubenlucas 3:97cac1d5ba8a 156 q1 = Encoder1.getPulses()/8400*(2*6.28318530718); //angle motor 1 (Times 2 to compensate for endcoding X4 --> X2)
rubenlucas 3:97cac1d5ba8a 157 q2 = Encoder2.getPulses()/8400*(2*6.28318530718); // angle motor 2 (Times 2 to compensate for endcoding X4 --> X2)
rubenlucas 3:97cac1d5ba8a 158
rubenlucas 3:97cac1d5ba8a 159 }
rubenlucas 3:97cac1d5ba8a 160
rubenlucas 6:d7ae5f8fd460 161 // Function to set desired cartesian velocities of end-effector
rubenlucas 6:d7ae5f8fd460 162 void Vdesired()
rubenlucas 6:d7ae5f8fd460 163 {
rubenlucas 6:d7ae5f8fd460 164 double Vconst = 0.001; // m/s (10 cm per second)
rubenlucas 6:d7ae5f8fd460 165 VdesX = EMGBoolLeft*Vconst; // Left biceps is X-direction
rubenlucas 6:d7ae5f8fd460 166 VdesY = -1*EMGBoolRight*Vconst; // Right biceps is minus Y-direction
rubenlucas 6:d7ae5f8fd460 167 }
rubenlucas 6:d7ae5f8fd460 168
rubenlucas 6:d7ae5f8fd460 169 // Inverse Kinematics
rubenlucas 6:d7ae5f8fd460 170 void InverseKinematics()
rubenlucas 6:d7ae5f8fd460 171 {
rubenlucas 6:d7ae5f8fd460 172 // matrix inverse Jacobian
rubenlucas 6:d7ae5f8fd460 173 double InvJac11 = (L2*(cos(q1)*sin(q2) + cos(q2)*sin(q1)) + cos(q1)*(L0 + L1 - cos(q2)*(L0 + L1)) - L0*cos(q1) - L1*cos(q1) + (cos(q1)*cos(q2) - sin(q1)*sin(q2))*(L0 + L1) + sin(q1)*sin(q2)*(L0 + L1))/((L2*(cos(q1)*cos(q2) - sin(q1)*sin(q2)) - sin(q1)*(L0 + L1 - cos(q2)*(L0 + L1)) + L0*sin(q1) - (cos(q1)*sin(q2) + cos(q2)*sin(q1))*(L0 + L1) + cos(q1)*sin(q2)*(L0 + L1))*(L2*(cos(q1)*sin(q2) + cos(q2)*sin(q1)) + cos(q1)*(L0 + L1 - cos(q2)*(L0 + L1)) - L0*cos(q1) - L1*cos(q1) + (cos(q1)*cos(q2) - sin(q1)*sin(q2))*(L0 + L1) + sin(q1)*sin(q2)*(L0 + L1)) - (L2*(cos(q1)*sin(q2) + cos(q2)*sin(q1)) + cos(q1)*(L0 + L1 - cos(q2)*(L0 + L1)) - L0*cos(q1) + (cos(q1)*cos(q2) - sin(q1)*sin(q2))*(L0 + L1) + sin(q1)*sin(q2)*(L0 + L1))*(L2*(cos(q1)*cos(q2) - sin(q1)*sin(q2)) - sin(q1)*(L0 + L1 - cos(q2)*(L0 + L1)) + L0*sin(q1) + L1*sin(q1) - (cos(q1)*sin(q2) + cos(q2)*sin(q1))*(L0 + L1) + cos(q1)*sin(q2)*(L0 + L1)));
rubenlucas 6:d7ae5f8fd460 174 double InvJac12 = -(L2*(cos(q1)*cos(q2) - sin(q1)*sin(q2)) - sin(q1)*(L0 + L1 - cos(q2)*(L0 + L1)) + L0*sin(q1) + L1*sin(q1) - (cos(q1)*sin(q2) + cos(q2)*sin(q1))*(L0 + L1) + cos(q1)*sin(q2)*(L0 + L1))/((L2*(cos(q1)*cos(q2) - sin(q1)*sin(q2)) - sin(q1)*(L0 + L1 - cos(q2)*(L0 + L1)) + L0*sin(q1) - (cos(q1)*sin(q2) + cos(q2)*sin(q1))*(L0 + L1) + cos(q1)*sin(q2)*(L0 + L1))*(L2*(cos(q1)*sin(q2) + cos(q2)*sin(q1)) + cos(q1)*(L0 + L1 - cos(q2)*(L0 + L1)) - L0*cos(q1) - L1*cos(q1) + (cos(q1)*cos(q2) - sin(q1)*sin(q2))*(L0 + L1) + sin(q1)*sin(q2)*(L0 + L1)) - (L2*(cos(q1)*sin(q2) + cos(q2)*sin(q1)) + cos(q1)*(L0 + L1 - cos(q2)*(L0 + L1)) - L0*cos(q1) + (cos(q1)*cos(q2) - sin(q1)*sin(q2))*(L0 + L1) + sin(q1)*sin(q2)*(L0 + L1))*(L2*(cos(q1)*cos(q2) - sin(q1)*sin(q2)) - sin(q1)*(L0 + L1 - cos(q2)*(L0 + L1)) + L0*sin(q1) + L1*sin(q1) - (cos(q1)*sin(q2) + cos(q2)*sin(q1))*(L0 + L1) + cos(q1)*sin(q2)*(L0 + L1)));
rubenlucas 6:d7ae5f8fd460 175 double InvJac21 = -(L2*(cos(q1)*sin(q2) + cos(q2)*sin(q1)) + cos(q1)*(L0 + L1 - cos(q2)*(L0 + L1)) - L0*cos(q1) + (cos(q1)*cos(q2) - sin(q1)*sin(q2))*(L0 + L1) + sin(q1)*sin(q2)*(L0 + L1))/((L2*(cos(q1)*cos(q2) - sin(q1)*sin(q2)) - sin(q1)*(L0 + L1 - cos(q2)*(L0 + L1)) + L0*sin(q1) - (cos(q1)*sin(q2) + cos(q2)*sin(q1))*(L0 + L1) + cos(q1)*sin(q2)*(L0 + L1))*(L2*(cos(q1)*sin(q2) + cos(q2)*sin(q1)) + cos(q1)*(L0 + L1 - cos(q2)*(L0 + L1)) - L0*cos(q1) - L1*cos(q1) + (cos(q1)*cos(q2) - sin(q1)*sin(q2))*(L0 + L1) + sin(q1)*sin(q2)*(L0 + L1)) - (L2*(cos(q1)*sin(q2) + cos(q2)*sin(q1)) + cos(q1)*(L0 + L1 - cos(q2)*(L0 + L1)) - L0*cos(q1) + (cos(q1)*cos(q2) - sin(q1)*sin(q2))*(L0 + L1) + sin(q1)*sin(q2)*(L0 + L1))*(L2*(cos(q1)*cos(q2) - sin(q1)*sin(q2)) - sin(q1)*(L0 + L1 - cos(q2)*(L0 + L1)) + L0*sin(q1) + L1*sin(q1) - (cos(q1)*sin(q2) + cos(q2)*sin(q1))*(L0 + L1) + cos(q1)*sin(q2)*(L0 + L1)));
rubenlucas 6:d7ae5f8fd460 176 double InvJac22 = (L2*(cos(q1)*cos(q2) - sin(q1)*sin(q2)) - sin(q1)*(L0 + L1 - cos(q2)*(L0 + L1)) + L0*sin(q1) - (cos(q1)*sin(q2) + cos(q2)*sin(q1))*(L0 + L1) + cos(q1)*sin(q2)*(L0 + L1))/((L2*(cos(q1)*cos(q2) - sin(q1)*sin(q2)) - sin(q1)*(L0 + L1 - cos(q2)*(L0 + L1)) + L0*sin(q1) - (cos(q1)*sin(q2) + cos(q2)*sin(q1))*(L0 + L1) + cos(q1)*sin(q2)*(L0 + L1))*(L2*(cos(q1)*sin(q2) + cos(q2)*sin(q1)) + cos(q1)*(L0 + L1 - cos(q2)*(L0 + L1)) - L0*cos(q1) - L1*cos(q1) + (cos(q1)*cos(q2) - sin(q1)*sin(q2))*(L0 + L1) + sin(q1)*sin(q2)*(L0 + L1)) - (L2*(cos(q1)*sin(q2) + cos(q2)*sin(q1)) + cos(q1)*(L0 + L1 - cos(q2)*(L0 + L1)) - L0*cos(q1) + (cos(q1)*cos(q2) - sin(q1)*sin(q2))*(L0 + L1) + sin(q1)*sin(q2)*(L0 + L1))*(L2*(cos(q1)*cos(q2) - sin(q1)*sin(q2)) - sin(q1)*(L0 + L1 - cos(q2)*(L0 + L1)) + L0*sin(q1) + L1*sin(q1) - (cos(q1)*sin(q2) + cos(q2)*sin(q1))*(L0 + L1) + cos(q1)*sin(q2)*(L0 + L1)));
rubenlucas 6:d7ae5f8fd460 177
rubenlucas 6:d7ae5f8fd460 178 //Gear Ratio's
rubenlucas 6:d7ae5f8fd460 179 double RatioGears = 134.0/30.0; //Gear Ratio for motor 1
rubenlucas 6:d7ae5f8fd460 180 double RatioPulleys = 87.4/27.5; // Gear Ratio for motor 2
rubenlucas 6:d7ae5f8fd460 181
rubenlucas 6:d7ae5f8fd460 182 double q1DotRef = (InvJac11*VdesX + InvJac12*VdesY)*RatioGears; //reference angular velocity motor 1
rubenlucas 6:d7ae5f8fd460 183 double q2DotRef = (InvJac21*VdesX + InvJac22*VdesY)*RatioPulleys; //reference angular velocity motor 2
rubenlucas 6:d7ae5f8fd460 184
rubenlucas 6:d7ae5f8fd460 185 Error1 = q1DotRef*Ts; // difference between qReference and current q1
rubenlucas 6:d7ae5f8fd460 186 Error2 = q2DotRef*Ts; // difference between qReference and current q2
rubenlucas 6:d7ae5f8fd460 187
rubenlucas 6:d7ae5f8fd460 188 q1Ref = q1 + Error1;
rubenlucas 6:d7ae5f8fd460 189 q2Ref = q2 + Error2;
rubenlucas 6:d7ae5f8fd460 190 }
rubenlucas 6:d7ae5f8fd460 191
rubenlucas 3:97cac1d5ba8a 192 //State machine
rubenlucas 3:97cac1d5ba8a 193 void StateMachine()
rubenlucas 2:c2ae5044ec82 194 {
rubenlucas 2:c2ae5044ec82 195 switch (CurrentState)
rubenlucas 2:c2ae5044ec82 196 {
rubenlucas 2:c2ae5044ec82 197 case Waiting:
rubenlucas 6:d7ae5f8fd460 198 SetMotorsOff();
rubenlucas 2:c2ae5044ec82 199 LedRed = 0;
rubenlucas 2:c2ae5044ec82 200 LedGreen = 0;
rubenlucas 2:c2ae5044ec82 201 LedBlue = 1; //Yellow
rubenlucas 5:cbcff21e74a0 202
rubenlucas 5:cbcff21e74a0 203 if (BUT2 == false)
rubenlucas 5:cbcff21e74a0 204 {
rubenlucas 5:cbcff21e74a0 205 CurrentState = EMGCal;
rubenlucas 6:d7ae5f8fd460 206 TimerLoop.reset();
rubenlucas 5:cbcff21e74a0 207 }
rubenlucas 5:cbcff21e74a0 208
rubenlucas 2:c2ae5044ec82 209 break;
rubenlucas 2:c2ae5044ec82 210
rubenlucas 2:c2ae5044ec82 211 case Homing:
rubenlucas 2:c2ae5044ec82 212 LedRed = 0;
rubenlucas 2:c2ae5044ec82 213 LedGreen = 0;
rubenlucas 2:c2ae5044ec82 214 LedBlue = 0; //White
rubenlucas 6:d7ae5f8fd460 215 if (BUT2 == false)
rubenlucas 6:d7ae5f8fd460 216 {
rubenlucas 6:d7ae5f8fd460 217 CurrentState = Demo;
rubenlucas 6:d7ae5f8fd460 218 TimerLoop.reset();
rubenlucas 6:d7ae5f8fd460 219 }
rubenlucas 6:d7ae5f8fd460 220
rubenlucas 6:d7ae5f8fd460 221 if (BUT1 == false)
rubenlucas 6:d7ae5f8fd460 222 {
rubenlucas 6:d7ae5f8fd460 223 CurrentState = Operation;
rubenlucas 6:d7ae5f8fd460 224 TimerLoop.reset();
rubenlucas 6:d7ae5f8fd460 225 }
rubenlucas 2:c2ae5044ec82 226 break;
rubenlucas 2:c2ae5044ec82 227
rubenlucas 2:c2ae5044ec82 228 case Emergency:
rubenlucas 2:c2ae5044ec82 229 LedRed = 0;
rubenlucas 2:c2ae5044ec82 230 LedGreen = 1;
rubenlucas 2:c2ae5044ec82 231 LedBlue = 1; //Red
rubenlucas 2:c2ae5044ec82 232 break;
rubenlucas 2:c2ae5044ec82 233
rubenlucas 2:c2ae5044ec82 234 case EMGCal:
rubenlucas 2:c2ae5044ec82 235 LedRed = 0;
rubenlucas 2:c2ae5044ec82 236 LedGreen = 1;
rubenlucas 2:c2ae5044ec82 237 LedBlue = 0; //Pink
rubenlucas 4:4728763bbb44 238 static double MaxLeft = 0;
rubenlucas 4:4728763bbb44 239 static double MaxRight = 0;
rubenlucas 4:4728763bbb44 240
rubenlucas 4:4728763bbb44 241 if(LeftBicepsOut > MaxLeft)
rubenlucas 4:4728763bbb44 242 {
rubenlucas 4:4728763bbb44 243 MaxLeft = LeftBicepsOut;
rubenlucas 4:4728763bbb44 244 }
rubenlucas 4:4728763bbb44 245
rubenlucas 4:4728763bbb44 246 if(RightBicepsOut > MaxRight)
rubenlucas 4:4728763bbb44 247 {
rubenlucas 4:4728763bbb44 248 MaxRight = RightBicepsOut;
rubenlucas 4:4728763bbb44 249 }
rubenlucas 4:4728763bbb44 250
rubenlucas 4:4728763bbb44 251 if (BUT1 == false)
rubenlucas 4:4728763bbb44 252 {
rubenlucas 4:4728763bbb44 253 ThresholdLeft = abs(0.15000*MaxLeft);
rubenlucas 4:4728763bbb44 254 ThresholdRight = abs(0.15000*MaxRight);
rubenlucas 6:d7ae5f8fd460 255 pc.printf("ThresholdLeft = %f and ThresholdRight = %f\r\n",ThresholdLeft,ThresholdRight);
rubenlucas 4:4728763bbb44 256 TimerLoop.reset();
rubenlucas 4:4728763bbb44 257 }
rubenlucas 6:d7ae5f8fd460 258 if ((ThresholdLeft<0.9) && (ThresholdRight <0.9) && (TimerLoop.read() >= 2.0))
rubenlucas 4:4728763bbb44 259 {
rubenlucas 4:4728763bbb44 260 CurrentState = MotorCal;
rubenlucas 4:4728763bbb44 261 TimerLoop.reset();
rubenlucas 4:4728763bbb44 262 }
rubenlucas 2:c2ae5044ec82 263 break;
rubenlucas 2:c2ae5044ec82 264
rubenlucas 2:c2ae5044ec82 265 case MotorCal:
rubenlucas 2:c2ae5044ec82 266 LedRed = 1;
rubenlucas 2:c2ae5044ec82 267 LedGreen = 0;
rubenlucas 2:c2ae5044ec82 268 LedBlue = 0; //Turqoise
rubenlucas 6:d7ae5f8fd460 269 if (BUTSW2 == false)
rubenlucas 6:d7ae5f8fd460 270 {
rubenlucas 6:d7ae5f8fd460 271 CurrentState = Homing;
rubenlucas 6:d7ae5f8fd460 272 TimerLoop.reset();
rubenlucas 6:d7ae5f8fd460 273 }
rubenlucas 2:c2ae5044ec82 274 break;
rubenlucas 2:c2ae5044ec82 275
rubenlucas 2:c2ae5044ec82 276 case Operation:
rubenlucas 2:c2ae5044ec82 277 LedRed = 1;
rubenlucas 2:c2ae5044ec82 278 LedGreen = 0;
rubenlucas 2:c2ae5044ec82 279 LedBlue = 1; //Green
rubenlucas 2:c2ae5044ec82 280 break;
rubenlucas 2:c2ae5044ec82 281
rubenlucas 2:c2ae5044ec82 282 case Demo:
rubenlucas 2:c2ae5044ec82 283 LedRed = 1;
rubenlucas 2:c2ae5044ec82 284 LedGreen = 1;
rubenlucas 6:d7ae5f8fd460 285 LedBlue = 0; //Blue
rubenlucas 6:d7ae5f8fd460 286 PrintToScreen();
rubenlucas 6:d7ae5f8fd460 287 if (TimerLoop.read() <= 5.0)
rubenlucas 6:d7ae5f8fd460 288 {
rubenlucas 6:d7ae5f8fd460 289 if((EMGBoolLeft == true) || (EMGBoolRight == true))
rubenlucas 6:d7ae5f8fd460 290 {
rubenlucas 6:d7ae5f8fd460 291 TimerLoop.reset();
rubenlucas 6:d7ae5f8fd460 292 Vdesired();
rubenlucas 6:d7ae5f8fd460 293 InverseKinematics();
rubenlucas 6:d7ae5f8fd460 294 }
rubenlucas 6:d7ae5f8fd460 295 }
rubenlucas 6:d7ae5f8fd460 296 else
rubenlucas 6:d7ae5f8fd460 297 {
rubenlucas 6:d7ae5f8fd460 298 q1Ref = 0;
rubenlucas 6:d7ae5f8fd460 299 q2Ref = 0;
rubenlucas 6:d7ae5f8fd460 300 Error1 = q1Ref - q1;
rubenlucas 6:d7ae5f8fd460 301 Error2 = q2Ref - q2;
rubenlucas 6:d7ae5f8fd460 302 if ((Error1 <= 0.1) && (Error2 <= 0.1))
rubenlucas 6:d7ae5f8fd460 303 {
rubenlucas 6:d7ae5f8fd460 304 TimerLoop.reset();
rubenlucas 6:d7ae5f8fd460 305 }
rubenlucas 6:d7ae5f8fd460 306 }
rubenlucas 2:c2ae5044ec82 307 break;
rubenlucas 2:c2ae5044ec82 308
rubenlucas 2:c2ae5044ec82 309
rubenlucas 2:c2ae5044ec82 310 }
rubenlucas 2:c2ae5044ec82 311 }
rubenlucas 2:c2ae5044ec82 312
rubenlucas 3:97cac1d5ba8a 313 //------------------------------------------------------------------------------
rubenlucas 4:4728763bbb44 314
rubenlucas 2:c2ae5044ec82 315
rubenlucas 2:c2ae5044ec82 316
rubenlucas 3:97cac1d5ba8a 317 //------------------------------------------------------------------------------
rubenlucas 3:97cac1d5ba8a 318 // controller motor 1
rubenlucas 3:97cac1d5ba8a 319 void PID_Controller1()
rubenlucas 3:97cac1d5ba8a 320 {
rubenlucas 4:4728763bbb44 321 double Kp = 19.8; // proportional gain
rubenlucas 4:4728763bbb44 322 double Ki = 40.9;//integral gain
rubenlucas 4:4728763bbb44 323 double Kd = 3; //derivative gain
rubenlucas 3:97cac1d5ba8a 324 static double ErrorIntegral = 0;
rubenlucas 3:97cac1d5ba8a 325 static double ErrorPrevious = Error1;
rubenlucas 3:97cac1d5ba8a 326 static BiQuad LowPassFilter(0.0640, 0.1279, 0.0640, -1.1683, 0.4241);
rubenlucas 3:97cac1d5ba8a 327
rubenlucas 3:97cac1d5ba8a 328 //Proportional part:
rubenlucas 3:97cac1d5ba8a 329 double u_k = Kp * Error1;
rubenlucas 3:97cac1d5ba8a 330
rubenlucas 3:97cac1d5ba8a 331 //Integral part:
rubenlucas 3:97cac1d5ba8a 332 ErrorIntegral = ErrorIntegral + Error1*Ts;
rubenlucas 3:97cac1d5ba8a 333 double u_i = Ki * ErrorIntegral;
rubenlucas 3:97cac1d5ba8a 334
rubenlucas 3:97cac1d5ba8a 335 //Derivative part:
rubenlucas 3:97cac1d5ba8a 336 double ErrorDerivative = (Error1 - ErrorPrevious)/Ts;
rubenlucas 3:97cac1d5ba8a 337 double FilteredErrorDerivative = LowPassFilter.step(ErrorDerivative);
rubenlucas 3:97cac1d5ba8a 338 double u_d = Kd * FilteredErrorDerivative;
rubenlucas 3:97cac1d5ba8a 339 ErrorPrevious = Error1;
rubenlucas 3:97cac1d5ba8a 340
rubenlucas 3:97cac1d5ba8a 341 MotorValue1 = u_k + u_i + u_d; //This will become the MotorValue to set motor 1
rubenlucas 3:97cac1d5ba8a 342 }
rubenlucas 3:97cac1d5ba8a 343
rubenlucas 3:97cac1d5ba8a 344 // controller motor 2
rubenlucas 3:97cac1d5ba8a 345 void PID_Controller2()
rubenlucas 3:97cac1d5ba8a 346 {
rubenlucas 4:4728763bbb44 347 double Kp = 11.1; // proportional gain
rubenlucas 4:4728763bbb44 348 double Ki = 22.81;//integral gain
rubenlucas 4:4728763bbb44 349 double Kd = 1.7; //derivative gain
rubenlucas 2:c2ae5044ec82 350 static double ErrorIntegral = 0;
rubenlucas 3:97cac1d5ba8a 351 static double ErrorPrevious = Error2;
rubenlucas 2:c2ae5044ec82 352 static BiQuad LowPassFilter(0.0640, 0.1279, 0.0640, -1.1683, 0.4241);
rubenlucas 2:c2ae5044ec82 353
rubenlucas 2:c2ae5044ec82 354 //Proportional part:
rubenlucas 3:97cac1d5ba8a 355 double u_k = Kp * Error2;
rubenlucas 2:c2ae5044ec82 356
rubenlucas 2:c2ae5044ec82 357 //Integral part:
rubenlucas 3:97cac1d5ba8a 358 ErrorIntegral = ErrorIntegral + Error2*Ts;
rubenlucas 2:c2ae5044ec82 359 double u_i = Ki * ErrorIntegral;
rubenlucas 2:c2ae5044ec82 360
rubenlucas 2:c2ae5044ec82 361 //Derivative part:
rubenlucas 3:97cac1d5ba8a 362 double ErrorDerivative = (Error2 - ErrorPrevious)/Ts;
rubenlucas 2:c2ae5044ec82 363 double FilteredErrorDerivative = LowPassFilter.step(ErrorDerivative);
rubenlucas 2:c2ae5044ec82 364 double u_d = Kd * FilteredErrorDerivative;
rubenlucas 3:97cac1d5ba8a 365 ErrorPrevious = Error2;
rubenlucas 2:c2ae5044ec82 366
rubenlucas 3:97cac1d5ba8a 367 MotorValue2 = u_k + u_i + u_d; //This will become the MotorValue to set motor 2
rubenlucas 3:97cac1d5ba8a 368 }
rubenlucas 3:97cac1d5ba8a 369
rubenlucas 3:97cac1d5ba8a 370 // Main function for motorcontrol
rubenlucas 3:97cac1d5ba8a 371 void MotorControllers()
rubenlucas 3:97cac1d5ba8a 372 {
rubenlucas 3:97cac1d5ba8a 373 PID_Controller1();
rubenlucas 3:97cac1d5ba8a 374 PID_Controller2();
rubenlucas 3:97cac1d5ba8a 375
rubenlucas 2:c2ae5044ec82 376 }
rubenlucas 3:97cac1d5ba8a 377 //------------------------------------------------------------------------------
rubenlucas 2:c2ae5044ec82 378
rubenlucas 2:c2ae5044ec82 379 //Ticker function set motorvalues
rubenlucas 3:97cac1d5ba8a 380 void SetMotors()
rubenlucas 2:c2ae5044ec82 381 {
rubenlucas 3:97cac1d5ba8a 382 // Motor 1
rubenlucas 3:97cac1d5ba8a 383 if (MotorValue1 >=0) // set direction
rubenlucas 2:c2ae5044ec82 384 {
rubenlucas 3:97cac1d5ba8a 385 DirectionPin1 = 1;
rubenlucas 2:c2ae5044ec82 386 }
rubenlucas 2:c2ae5044ec82 387 else
rubenlucas 2:c2ae5044ec82 388 {
rubenlucas 3:97cac1d5ba8a 389 DirectionPin1 = 0;
rubenlucas 2:c2ae5044ec82 390 }
rubenlucas 2:c2ae5044ec82 391
rubenlucas 3:97cac1d5ba8a 392 if (fabs(MotorValue1)>1) // set duty cycle
rubenlucas 3:97cac1d5ba8a 393 {
rubenlucas 3:97cac1d5ba8a 394 PwmPin1 = 1;
rubenlucas 3:97cac1d5ba8a 395 }
rubenlucas 3:97cac1d5ba8a 396 else
rubenlucas 2:c2ae5044ec82 397 {
rubenlucas 3:97cac1d5ba8a 398 PwmPin1 = fabs(MotorValue1);
rubenlucas 3:97cac1d5ba8a 399 }
rubenlucas 3:97cac1d5ba8a 400
rubenlucas 3:97cac1d5ba8a 401 // Motor 2
rubenlucas 3:97cac1d5ba8a 402 if (MotorValue2 >=0) // set direction
rubenlucas 3:97cac1d5ba8a 403 {
rubenlucas 3:97cac1d5ba8a 404 DirectionPin2 = 1;
rubenlucas 2:c2ae5044ec82 405 }
rubenlucas 2:c2ae5044ec82 406 else
rubenlucas 2:c2ae5044ec82 407 {
rubenlucas 3:97cac1d5ba8a 408 DirectionPin2 = 0;
rubenlucas 2:c2ae5044ec82 409 }
rubenlucas 3:97cac1d5ba8a 410
rubenlucas 3:97cac1d5ba8a 411 if (fabs(MotorValue2)>1) // set duty cycle
rubenlucas 3:97cac1d5ba8a 412 {
rubenlucas 3:97cac1d5ba8a 413 PwmPin2 = 1;
rubenlucas 3:97cac1d5ba8a 414 }
rubenlucas 3:97cac1d5ba8a 415 else
rubenlucas 3:97cac1d5ba8a 416 {
rubenlucas 3:97cac1d5ba8a 417 PwmPin2 = fabs(MotorValue2);
rubenlucas 3:97cac1d5ba8a 418 }
rubenlucas 3:97cac1d5ba8a 419
rubenlucas 2:c2ae5044ec82 420 }
rubenlucas 2:c2ae5044ec82 421
rubenlucas 6:d7ae5f8fd460 422
rubenlucas 6:d7ae5f8fd460 423
rubenlucas 2:c2ae5044ec82 424
rubenlucas 2:c2ae5044ec82 425 //-----------------------------------------------------------------------------
rubenlucas 2:c2ae5044ec82 426
rubenlucas 2:c2ae5044ec82 427
rubenlucas 2:c2ae5044ec82 428 // Execution function
rubenlucas 2:c2ae5044ec82 429 void LoopFunction()
rubenlucas 2:c2ae5044ec82 430 {
rubenlucas 6:d7ae5f8fd460 431 MeasureAll();
rubenlucas 6:d7ae5f8fd460 432 StateMachine();
rubenlucas 6:d7ae5f8fd460 433 MotorControllers();
rubenlucas 6:d7ae5f8fd460 434 SetMotors();
rubenlucas 2:c2ae5044ec82 435 }
rubenlucas 2:c2ae5044ec82 436
rubenlucas 2:c2ae5044ec82 437 int main()
rubenlucas 2:c2ae5044ec82 438 {
rubenlucas 2:c2ae5044ec82 439 pc.baud(115200);
rubenlucas 2:c2ae5044ec82 440 pc.printf("Hi I'm PTR, you can call me Peter!\r\n");
rubenlucas 3:97cac1d5ba8a 441 TimerLoop.start(); // start Timer
rubenlucas 2:c2ae5044ec82 442 CurrentState = Waiting; // set initial state as Waiting
rubenlucas 3:97cac1d5ba8a 443 bqc1.add( &bq1 ).add( &bq2 ); //make BiQuadChain EMG left
rubenlucas 3:97cac1d5ba8a 444 bqc2.add( &bq3 ).add( &bq4 ); //make BiQuadChain EMG right
rubenlucas 2:c2ae5044ec82 445 TickerLoop.attach(&LoopFunction, 0.002f); //ticker for function calls 500 Hz
rubenlucas 2:c2ae5044ec82 446
rubenlucas 2:c2ae5044ec82 447 while (true)
rubenlucas 2:c2ae5044ec82 448 {
rubenlucas 6:d7ae5f8fd460 449 if (PrintFlag == true)
rubenlucas 6:d7ae5f8fd460 450 {
rubenlucas 6:d7ae5f8fd460 451 pc.printf("EMG left = %i, EMG right = %i, q1Ref = %f, q1 = %f, q2Ref = %f, q2 = %f\r",EMGBoolLeft,EMGBoolRight,q1Ref,q1,q2Ref,q2);
rubenlucas 6:d7ae5f8fd460 452 }
rubenlucas 2:c2ae5044ec82 453 }
rubenlucas 2:c2ae5044ec82 454
rubenlucas 2:c2ae5044ec82 455 }