FINAL VERSION
Dependencies: biquadFilter MODSERIAL QEI Servo mbed
Fork of Robot_Battle_met_ARVID by
Diff: main.cpp
- Revision:
- 9:40c9a18c3430
- Parent:
- 8:ec3ea0623620
- Child:
- 10:2325e545ce11
--- a/main.cpp Thu Nov 01 16:40:11 2018 +0000 +++ b/main.cpp Thu Nov 01 17:09:18 2018 +0000 @@ -1,15 +1,33 @@ -// EMG, RKI, PID, MOTOR +// EMG + KINEMATICS + PID + MOTOR CONTROL + +//----------------~INITIATING------------------------- #include "mbed.h" + +// EMG -- DEPENDENCIES #include <iostream> #include "BiQuad.h" #include "BiQuadchains_zelfbeun.h" #include "MODSERIAL.h" +// KINEMATICS -- DEPENDENCIES +#include "stdio.h" +#define _USE_MATH_DEFINES +#include <math.h> +#define M_PI 3.14159265358979323846 /* pi */ + +// PID CONTROLLER -- DEPENDENCIES +#include "BiQuad.h" +#include "QEI.h" +//#include "HIDScope.h" + + +// GENERAL PIN DEFENITIONS MODSERIAL pc(USBTX, USBRX); +// EMG -- PIN DEFENITIONS DigitalOut gpo(D0); -DigitalIn button2(SW3); +DigitalIn button2(SW3); DigitalIn button1(SW2); //or SW2 DigitalOut led1(LED_GREEN); @@ -22,18 +40,126 @@ Timer t; //timer try out for Astrid Timer timer_calibration; //timer for EMG calibration - - //Input system AnalogIn emg1(A0); //right biceps AnalogIn emg2(A1); //right triceps AnalogIn emg3(A2); //left biceps AnalogIn emg4(A3); //left triceps + +// PID CONTROLLER -- PIN DEFENITIONS +//AnalogIn button2(A4); +//AnalogIn button1(A3); +//DigitalIn button3(SW2); +//DigitalIn button4(SW3); + +DigitalOut directionpin1(D7); // motor 1 +DigitalOut directionpin2(D4); // motor 2 +DigitalOut directionpin3(D13); // motor 3 +PwmOut pwmpin1(D6); // motor 1 +PwmOut pwmpin2(D5); // motor 2 +PwmOut pwmpin3(D12); // motor 3 + +QEI encoder1 (D9, D8, NC, 8400, QEI::X4_ENCODING); +QEI encoder2 (D11, D10, NC, 8400, QEI::X4_ENCODING); // motor 2 +QEI encoder3 (D3, D2, NC, 8400, QEI::X4_ENCODING); // motor 3 +// HIDScope scope(2); + +// PID - TICKERS +Ticker ref_rot; +Ticker show_counts; +Ticker Scope_Data; + +//----------------GLOBALS-------------------------- +// GLOBALS EMG + //Filtered EMG signals from the end of the chains volatile double emg1_filtered, emg2_filtered, emg3_filtered, emg4_filtered; int i = 0; +//Define doubles for calibration and ticker +double ts = 0.001; //tijdsstap +double calibration_time = 55; //time EMG calibration should take + +volatile double temp_highest_emg1 = 0; //highest detected value right biceps +volatile double temp_highest_emg2 = 0; +volatile double temp_highest_emg3 = 0; +volatile double temp_highest_emg4 = 0; + +//Doubles for calculation threshold +double biceps_p_t = 0.4; //set threshold at percentage of highest value +double triceps_p_t = 0.5; //set threshold at percentage of highest value +volatile double threshold1; +volatile double threshold2; +volatile double threshold3; +volatile double threshold4; + +// thresholdreads bools +int bicepsR; +int tricepsR; +int bicepsL; +int tricepsL; + +// VARIABLES ROBOT KINEMATICS +// constants +const float la = 0.256; // lengte actieve arm +const float lp = 0.21; // lengte passieve arm +const float rp = 0.052; // straal van midden end effector tot hoekpunt +const float rm = 0.23; // straal van global midden tot motor +const float a = 0.09; // zijde van de driehoek +const float xas = 0.40; // afstand van motor 1 tot motor 3 +const float yas = 0.346; // afstand van xas tot motor 2 +const float thetap = 0; // rotatiehoek van de end effector + + +// motor locatie +const int a1x = 0; //x locatie motor 1 +const int a1y = 0; //y locatie motor 1 +const float a2x = (0.5)*xas; // x locatie motor 2 +const float a2y = yas; // y locatie motor 2 +const float a3x = xas; // x locatie motor 3 +const int a3y = 0; // y locatie motor 3 + +// script voor het bepalen van de desired position aan de hand van emg (1/0) + +// EMG OUTPUT +int EMGxplus; +int EMGxmin ; +int EMGyplus; +int EMGymin ; + +// Dit moet experimenteel geperfectioneerd worden +float tijdstap = 0.005; //nu wss heel langzaam, kan miss omhoog KEER V GEEFT VERANDERING IN POSITIE +float v = 0.1; // snelheid kan wss ook hoger + +float px = 0.2; //starting x // BOUNDARIES +float py = 0.155; // starting y // BOUNDARIES + +// verschil horizontale as met de actieve arm +float da1 = 1.619685; // verschil a1 hoek en motor +float da2 = -0.609780; +float da3 = 3.372859; + +// limits (since no forward kinematics) +float upperxlim = 0.275; //36, 0.04, 0.315, -0.085niet helemaal naar requierments ff kijken of ie groter kan +float lowerxlim = 0.10; +float upperylim = 0.225; +float lowerylim = 0.03; //0.03 is goed + +// VARIABLES PID CONTROLLER +double PI = M_PI;// CHANGE THIS INTO M_PI +double Kp = 14; //200 , 50 +double Ki = 0; //1, 0.5 +double Kd = 3; //200, 10 +double Ts = 0.1; // Sample time in seconds +double reference_rotation; //define as radians +double motor_position; +bool AlwaysTrue; + + +//----------------FUNCTIONS-------------------------- + +// ~~~~~~~~~~~~~~~~~~~EMG FUNCTIONS~~~~~~~~~~~~~~~~~~ void emgsample() { //All EMG signal through Highpass @@ -64,28 +190,8 @@ emg2_filtered = lowp2.step(emg2_abs); emg3_filtered = lowp3.step(emg3_abs); emg4_filtered = lowp4.step(emg4_abs); - - } - -//Define doubles for calibration and ticker -double ts = 0.001; //tijdsstap -double calibration_time = 55; //time EMG calibration should take - -volatile double temp_highest_emg1 = 0; //highest detected value right biceps -volatile double temp_highest_emg2 = 0; -volatile double temp_highest_emg3 = 0; -volatile double temp_highest_emg4 = 0; - -//Doubles for calculation threshold -double biceps_p_t = 0.4; //set threshold at percentage of highest value -double triceps_p_t = 0.5; //set threshold at percentage of highest value -volatile double threshold1; -volatile double threshold2; -volatile double threshold3; -volatile double threshold4; - void CalibrationEMG() { //static float samples = calibration_time/ts; @@ -137,15 +243,13 @@ led1=1; led2=1; led3=1; - - } - +/* pc.printf("Highest value right biceps= %f \r\n", temp_highest_emg1); pc.printf("Highest value right triceps= %f \r\n", temp_highest_emg2); pc.printf("Highest value left biceps= %f \r\n", temp_highest_emg3); pc.printf("Highest value left triceps= %f \r\n", temp_highest_emg4); - +*/ threshold1 = temp_highest_emg1*biceps_p_t; //Right Biceps threshold2 = temp_highest_emg2*triceps_p_t; //Right Triceps @@ -154,11 +258,6 @@ } //Check if emg_filtered has reached their threshold -int bicepsR; -int tricepsR; -int bicepsL; -int tricepsL; - void threshold_check() { @@ -193,11 +292,8 @@ pc.printf("Biceps Left = %i", bicepsL); pc.printf("Triceps Left = %i", tricepsL); */ - - } - //Activate ticker for Movement state, filtering and Threshold checking void movement_ticker_activator() { @@ -210,6 +306,178 @@ threshold_check_ticker.detach(); } +// ~~~~~~~~~~~~~~ROBOT KINEMATICS ~~~~~~~~~~~~~~~~~~ + +// functie x positie +float positionx(int EMGxplus,int EMGxmin) +{ + float EMGx = EMGxplus - EMGxmin; + + float verplaatsingx = EMGx * tijdstap * v; + float pxnieuw = px + verplaatsingx; + // x limit + if (pxnieuw <= upperxlim && pxnieuw >= lowerxlim) { + px = pxnieuw; + } else { + if (pxnieuw >= lowerxlim) { + px = upperxlim; + } else { + px = lowerxlim; + } + } +//printf("X eindpunt (%f) en verplaatsing: (%f)\n\r",px,verplaatsingx); + return px; +} + + +// functie y positie +float positiony(int EMGyplus,int EMGymin) +{ + float EMGy = EMGyplus - EMGymin; + + float verplaatsingy = EMGy * tijdstap * v; + float pynieuw = py + verplaatsingy; + + // y limit + if (pynieuw <= upperylim && pynieuw >= lowerylim) { + py = pynieuw; + } else { + if (pynieuw >= lowerylim) { + py = upperylim; + } else { + py = lowerylim; + } + } +//printf("Y eindpunt (%f) en verplaatsing: (%f) \n\r",py,verplaatsingy); + return (py); +} + + +//~~~~~~~~~~~~CALCULATIING MOTOR ANGLES ~~~~~~~~ +// arm 1 --> reference angle motor 1 +float hoek1(float px, float py) // input: ref x, ref y +{ + float c1x = px - rp * cos(thetap +(M_PI/6)); // x locatie hoekpunt end-effector + float c1y = py - rp*sin(thetap+(M_PI/6)); // y locatie hoekpunt end-effector + float alpha1 = atan2((c1y-a1y),(c1x-a1x)); // hoek tussen horizontaal en lijn van motor naar bijbehorende end-effector punt + 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 + float a1 = alpha1 + psi1 - da1; //hoek tussen horizontaal en actieve arm + //printf("arm 1 = %f \n\r",a1); + return a1; +} + +// arm 2 --> reference angle motor 2 +float hoek2(float px, float py) +{ + float c2x = px - rp * cos(thetap -(M_PI/2)); + float c2y = py - rp*sin(thetap-(M_PI/2)); + float alpha2 = atan2((c2y-a2y),(c2x-a2x)); + 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) ))); + float a2 = alpha2 + psi2 - da2; + //printf("arm 2 = %f \n\r",a2); + return a2; +} + +//arm 3 --> reference angle motor 3 +float hoek3(float px, float py) +{ + float c3x = px - rp * cos(thetap +(5*M_PI/6)); + float c3y = py - rp*sin(thetap+(5*M_PI/6)); + float alpha3 = atan2((c3y-a3y),(c3x-a3x)); + 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) ))); + float a3 = alpha3 + psi3 - da3; + //printf("arm 3 = %f \n\r",a3); + return a3; +} + +// ~~~~~~~~~~~~~~PID CONTROLLER~~~~~~~~~~~~~~~~~~ + +double PID_controller(double error) +{ + static double error_integral = 0; + static double error_prev = error; // initialization with this value only done once! + static BiQuad LowPassFilter(0.0640, 0.1279, 0.0640, -1.1683, 0.4241); + + // Proportional part: + double u_k = Kp * error; + + // Integral part + error_integral = error_integral + error * Ts; + double u_i = Ki * error_integral; + + // Derivative part + double error_derivative = (error - error_prev)/Ts; + double filtered_error_derivative = LowPassFilter.step(error_derivative); + double u_d = Kd * filtered_error_derivative; + error_prev = error; + + // Sum all parts and return it + return u_k + u_i + u_d; +} + + +// DIRECTON AND SPEED CONTROL +void moter_control(double u) +{ + + directionpin1= u > 0.0f; //eithertrueor false + if (fabs(u)> 0.7f) { + u = 0.7f; + } else { + u= u; + } + pwmpin1= fabs(u); //pwmduty cycle canonlybepositive, floatingpoint absolute value +} + +void moter2_control(double u) +{ + directionpin2= u > 0.0f; //eithertrueor false + if (fabs(u)> 0.7f) { + u = 0.7f; + } else { + u= u; + } + pwmpin2= fabs(u); //pwmduty cycle canonlybepositive, floatingpoint absolute value +} + +void moter3_control(double u) +{ + directionpin3= u > 0.0f; //eithertrueor false + if (fabs(u)> 0.7f) { + u = 0.7f; + } else { + u= u; + } + pwmpin3 = fabs(u); //pwmduty cycle canonlybepositive, floatingpoint absolute value +} + +// CONTROLLING THE MOTOR +void Motor_mover() +{ + double motor_position = encoder1.getPulses(); //output in counts + double reference_rotation = hoek1(px, py); + double error = reference_rotation - motor_position*(2*PI)/8400; + double u = PID_controller(error); + moter_control(u); + + double motor_position2 = encoder2.getPulses(); //output in counts + double reference_rotation2 = hoek2(px, py); + double error_2 = reference_rotation2 - motor_position2*(2*PI)/8400; + double u_2 = PID_controller(error_2); + moter2_control(u_2); + + double motor_position3 = encoder3.getPulses(); //output in counts + double reference_rotation3 = hoek3(px, py); + double error_3 = reference_rotation3 - motor_position3*(2*PI)/8400; + double u_3 = PID_controller(error_3); + moter3_control(u_3); + + +} + + + +//-------------------- STATE MACHINE -------------------------- enum states {MOTORS_OFF,CALIBRATION,HOMING,DEMO,MOVEMENT,CLICK}; states currentState = MOTORS_OFF; //Chosen startingposition for states bool stateChanged = true; // Make sure the initialization of first state is executed @@ -430,6 +698,9 @@ } } +// --------------------------MAIN-------------------- + + int main() { //BiQuad Chain add @@ -453,6 +724,9 @@ led1 = 1; led2 = 1; led3 = 1; + + pwmpin1.period_us(60); // setup motor + ref_rot.attach(Motor_mover, 0.001);// HAS TO GO TO STATE MACHINE while (true) { ProcessStateMachine();