Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Dependencies: HIDScope MODSERIAL QEI biquadFilter mbed Servo
Diff: main.cpp
- Branch:
- bla
- Revision:
- 17:1f93c83e211f
- Parent:
- 16:0280a604cf7e
- Child:
- 22:31065a83d9e8
--- a/main.cpp Thu Oct 25 17:50:26 2018 +0000 +++ b/main.cpp Thu Oct 25 22:01:12 2018 +0000 @@ -5,6 +5,7 @@ #include "BiQuad.h" #include "PID_controller.h" #include "kinematics.h" +#include "processing_chain_emg.h" //Define objects MODSERIAL pc(USBTX, USBRX); @@ -24,6 +25,7 @@ QEI motor_1_encoder(D12,D13,NC,32); QEI motor_2_encoder(D10,D11,NC,32); +// other objects AnalogIn potmeter1(A2); AnalogIn potmeter2(A3); DigitalIn button(D0); @@ -37,24 +39,21 @@ //Global variables/objects States current_state; -double des_vx, des_vy, x, y, q1, q2, qref1, qref2, e1, e2, u1, u2, emg_raw_0, processed_emg_0, emg_raw_1, processed_emg_1; //will be set by the motor_controller function +double des_vx, des_vy, x, y, q1, q2, qref1, qref2, e1, e2, u1, u2, raw_emg_0, process_emg_0, raw_emg_1, process_emg_1; //will be set by the motor_controller function +double vxmax = 1.0, vymax = 1.0; int counts_per_rotation = 32; bool state_changed = false; const double T = 0.001; -float processing_chain_emg(int num) { - return 6.0; -} - +// Functions void measure_all() { q1 = motor_1_encoder.getPulses()*2.0f*3.1415926535f/counts_per_rotation; //do this here, and not in the encoder interrupt, to reduce computational load q2 = motor_2_encoder.getPulses()*2.0f*3.1415926535f/counts_per_rotation; forwardkinematics_function(q1,q2,x,y); //motor_angle is global, this function ne - emg_raw_0 = emg0.read(); //sample analog voltages (all sampling theory applies, you might get aliasing etc.) - emg_raw_1 = emg1.read(); - processed_emg_0 = processing_chain_emg(0); // some function ‘float my_emg_processing_chain()’ that returns a float. The raw emg is global - processed_emg_1 = processing_chain_emg(1); + raw_emg_0 = emg0.read(); //sample analog voltages (all sampling theory applies, you might get aliasing etc.) + raw_emg_1 = emg1.read(); + processing_chain_emg(raw_emg_0, raw_emg_1, process_emg_0, process_emg_1); // processes the emg signals } void output_all() { @@ -93,24 +92,36 @@ break; case calib_emg: //calibrate emg-signals - + current_state = operational; break; case operational: //interpreting emg-signals to move the end effector if (state_changed==true) { ; } - // example + + // here we have to determine the desired velocity based on the processed emg signals and calibration + if (process_emg_0 >= 0.16) { des_vx = vxmax; } + else if(process_emg_0 >= 0.09) { des_vx = vxmax * 0.66; } + else if(process_emg_0 >= 0.02) { des_vx = vxmax * 0.33; } + else { des_vx = 0; } + + if (process_emg_1 >= 0.16) { des_vy = vymax; } + else if(process_emg_1 >= 0.09) { des_vy = vymax * 0.66; } + else if(process_emg_1 >= 0.02) { des_vy = vymax * 0.33; } + else { des_vy = 0; } + if (button.read() == true) { current_state = demo; } break; case demo: //moving according to a specified trajectory - if (button.read() == true) { current_state = demo; } + if (button.read() == true) { current_state = operational; } break; case failure: //no way to get out u1 = 0.0f; + u2 = 0.0f; break; } } @@ -121,7 +132,7 @@ inversekinematics_function(x,y,T,qref1,qref2,q1,q2,des_vx,des_vy); //many different states can modify your reference position, so just do the inverse kinematics once, here e1 = qref1 - q1; //tracking error (q_ref - q_meas) e2 = qref2 - q2; - PID_controller(e1,e2,u1,u2); //feedback controller or with possibly fancy controller additions...; pass by reference + PID_controller(e1,e2,u1,u2,T); //feedback controller or with possibly fancy controller additions...; pass by reference } //otherwise we just don’t mess with the value of control variable ‘u’ that is set somewhere in the state-machine. } @@ -142,7 +153,8 @@ current_state = waiting; //we start in state ‘waiting’ and current_state can be accessed by all functions u1 = 0.0f; //initial output to motors is 0. u2 = 0.0f; - loop_ticker.attach(&loop_function, 1/samplingfreq); //Run the function loop_function 1000 times per second + bqc.add(&bqhigh).add(&bqnotch); // filter cascade for emg + loop_ticker.attach(&loop_function, T); //Run the function loop_function 1000 times per second while (true) { } //Do nothing here (timing purposes) }