Alle subfiles samengevoegd

Dependencies:   HIDScope biquadFilter mbed MODSERIAL FastPWM QEI

Committer:
sjoerdbarts
Date:
Mon Oct 31 13:52:51 2016 +0000
Revision:
13:e8b8b035abbd
Parent:
12:9b0451105991
Child:
14:f114e57c3795
Added stepper test on button 3

Who changed what in which revision?

UserRevisionLine numberNew contents of line
s1600907 0:c96cf9760185 1 #include "mbed.h"
s1600907 0:c96cf9760185 2 #include "math.h"
s1600907 1:e1267e72ade8 3 #include "MODSERIAL.h"
sjoerdbarts 6:00011220b82b 4 #include "HIDScope.h"
sjoerdbarts 6:00011220b82b 5 #include "FastPWM.h"
sjoerdbarts 6:00011220b82b 6 #include "QEI.h"
sjoerdbarts 6:00011220b82b 7 #include "BiQuad.h"
sjoerdbarts 6:00011220b82b 8 #define SERIAL_BAUD 115200 // baud rate for serial communication
s1600907 0:c96cf9760185 9
sjoerdbarts 6:00011220b82b 10 // Serial connection
s1600907 1:e1267e72ade8 11 MODSERIAL pc(USBTX,USBRX);
sjoerdbarts 6:00011220b82b 12
s1600907 0:c96cf9760185 13 //EMG aansluitingen
s1600907 0:c96cf9760185 14 AnalogIn emg0( A0 ); //Biceps Rechts
s1600907 2:92593c9d6146 15 AnalogIn emg1( A1 ); //Bicpes Links
s1600907 2:92593c9d6146 16 AnalogIn emg2( A2 ); //Upper leg
sjoerdbarts 6:00011220b82b 17
sjoerdbarts 12:9b0451105991 18 // Setup Potmeters
sjoerdbarts 6:00011220b82b 19 // Potmeter 1 gives the reference position x
sjoerdbarts 6:00011220b82b 20 AnalogIn pot1(A3);
sjoerdbarts 6:00011220b82b 21 // Potmeter 2 gives the reference position y
sjoerdbarts 6:00011220b82b 22 AnalogIn pot2(A4);
sjoerdbarts 6:00011220b82b 23
sjoerdbarts 6:00011220b82b 24 // Setup Buttons
sjoerdbarts 6:00011220b82b 25 InterruptIn button1(PTB9); // button 1
sjoerdbarts 6:00011220b82b 26 InterruptIn button2(PTA1); // button 2
sjoerdbarts 6:00011220b82b 27 InterruptIn button3(PTC6); // SW2
sjoerdbarts 6:00011220b82b 28 InterruptIn button4(PTA4); // SW3
sjoerdbarts 6:00011220b82b 29
sjoerdbarts 8:676646c50aeb 30 // Setup botton values
sjoerdbarts 8:676646c50aeb 31 bool button1_value = false;
sjoerdbarts 8:676646c50aeb 32 bool button2_value = false;
sjoerdbarts 8:676646c50aeb 33
sjoerdbarts 6:00011220b82b 34 // Set motor Pinouts
sjoerdbarts 6:00011220b82b 35 DigitalOut motor1_dir(D4);
sjoerdbarts 6:00011220b82b 36 FastPWM motor1_pwm(D5);
sjoerdbarts 6:00011220b82b 37 DigitalOut motor2_dir(D7);
sjoerdbarts 6:00011220b82b 38 FastPWM motor2_pwm(D6);
sjoerdbarts 6:00011220b82b 39
sjoerdbarts 6:00011220b82b 40 // Set LED pins
sjoerdbarts 13:e8b8b035abbd 41 DigitalOut led(PTE24); // D15 LED1
sjoerdbarts 12:9b0451105991 42 DigitalOut red(LED_RED);
sjoerdbarts 12:9b0451105991 43 DigitalOut blue(LED_BLUE);
sjoerdbarts 12:9b0451105991 44 DigitalOut green(LED_GREEN);
sjoerdbarts 6:00011220b82b 45
sjoerdbarts 6:00011220b82b 46 // Set HID scope
sjoerdbarts 6:00011220b82b 47 HIDScope scope(6);
sjoerdbarts 6:00011220b82b 48
sjoerdbarts 6:00011220b82b 49 // Set encoder
sjoerdbarts 6:00011220b82b 50 QEI m1_EncoderCW(D10,D11,NC,32);
sjoerdbarts 6:00011220b82b 51 QEI m1_EncoderCCW(D11,D10,NC,32);
sjoerdbarts 6:00011220b82b 52 QEI m2_EncoderCW(D13,D12,NC,32);
sjoerdbarts 6:00011220b82b 53 QEI m2_EncoderCCW(D12,D13,NC,32);
s1600907 0:c96cf9760185 54
sjoerdbarts 7:bafc32b576c4 55 // Constants for control
sjoerdbarts 7:bafc32b576c4 56 volatile const int COUNTS_PER_REV = 8400;
sjoerdbarts 8:676646c50aeb 57 volatile const double DEGREES_PER_PULSE = 8400 / 360;
sjoerdbarts 7:bafc32b576c4 58
sjoerdbarts 7:bafc32b576c4 59 // Set initial Kp and Ki
sjoerdbarts 7:bafc32b576c4 60 volatile double Kp = 0.01; // last known good Kp: 0.01
sjoerdbarts 8:676646c50aeb 61 volatile double Ki = 0.0025; // last known good Ki: 0.0025
sjoerdbarts 7:bafc32b576c4 62 volatile double Kd = 0.0; // last known good Kd: 0.0
sjoerdbarts 7:bafc32b576c4 63
sjoerdbarts 8:676646c50aeb 64 // Set frequencies for sampling, calc and control.
sjoerdbarts 8:676646c50aeb 65 volatile const double SAMPLE_F = 500; // 500 Hz
sjoerdbarts 8:676646c50aeb 66 volatile const double SAMPLE_TS = 1.0/SAMPLE_F;
sjoerdbarts 12:9b0451105991 67 volatile const double CALC_F = 500.0; // 100 Hz
sjoerdbarts 8:676646c50aeb 68 volatile const double CALC_TS = 1.0/CALC_F;
sjoerdbarts 8:676646c50aeb 69 volatile const double CONTROLLER_TS = 0.01; // 100 Hz
sjoerdbarts 8:676646c50aeb 70
sjoerdbarts 7:bafc32b576c4 71 volatile double Ts = 0.01;
sjoerdbarts 7:bafc32b576c4 72 volatile double N = 100;
sjoerdbarts 7:bafc32b576c4 73
sjoerdbarts 7:bafc32b576c4 74 // Memory values for controllers
sjoerdbarts 7:bafc32b576c4 75 double m1_v1 = 0, m1_v2 = 0;
sjoerdbarts 7:bafc32b576c4 76 double m2_v1 = 0, m2_v2 = 0;
s1600907 0:c96cf9760185 77
s1600907 0:c96cf9760185 78 //BiQuad
s1600907 0:c96cf9760185 79 // making the biquads and chains; imported from matlab
s1600907 0:c96cf9760185 80 BiQuadChain bqc; //Chain for right biceps
s1600907 0:c96cf9760185 81 BiQuadChain bqc2; //Chain for left biceps
s1600907 0:c96cf9760185 82 BiQuadChain bqc3; //Chain for Upper leg
s1600907 0:c96cf9760185 83 // 1 to 3 are for right biceps
s1600907 0:c96cf9760185 84 BiQuad bq1( 9.14969e-01, -1.82994e+00, 9.14969e-01, -1.82269e+00, 8.37182e-01 );
s1600907 0:c96cf9760185 85 BiQuad bq2( 9.91104e-01, -1.60364e+00, 9.91104e-01, -1.60364e+00, 9.82207e-01 );
s1600907 0:c96cf9760185 86 BiQuad bq3( 8.76555e-05, 1.75311e-04, 8.76555e-05, -1.97334e+00, 9.73695e-01 );
s1600907 0:c96cf9760185 87 // 4 to 6 are for left biceps
s1600907 0:c96cf9760185 88 BiQuad bq4( 9.14969e-01, -1.82994e+00, 9.14969e-01, -1.82269e+00, 8.37182e-01 );
s1600907 0:c96cf9760185 89 BiQuad bq5( 9.91104e-01, -1.60364e+00, 9.91104e-01, -1.60364e+00, 9.82207e-01 );
s1600907 0:c96cf9760185 90 BiQuad bq6( 8.76555e-05, 1.75311e-04, 8.76555e-05, -1.97334e+00, 9.73695e-01 );
s1600907 0:c96cf9760185 91 // 7 to 9 are for upper leg
s1600907 0:c96cf9760185 92 BiQuad bq7( 9.14969e-01, -1.82994e+00, 9.14969e-01, -1.82269e+00, 8.37182e-01 );
s1600907 0:c96cf9760185 93 BiQuad bq8( 9.91104e-01, -1.60364e+00, 9.91104e-01, -1.60364e+00, 9.82207e-01 );
s1600907 0:c96cf9760185 94 BiQuad bq9( 3.91302e-05, 7.82604e-05, 3.91302e-05, -1.98223e+00, 9.82385e-01 );
s1600907 0:c96cf9760185 95
sjoerdbarts 7:bafc32b576c4 96 // Variables for filter
sjoerdbarts 7:bafc32b576c4 97 // muscle EMG < treshhold
s1600907 0:c96cf9760185 98 volatile bool BicepsLeft = false;
s1600907 0:c96cf9760185 99 volatile bool BicepsRight = false;
s1600907 0:c96cf9760185 100 volatile bool Leg = false;
s1600907 0:c96cf9760185 101
sjoerdbarts 7:bafc32b576c4 102 // Variables for MotorHoekBerekenen (MotorAngleCalculation)
s1600907 1:e1267e72ade8 103 volatile double x = 0.0; // beginpositie x en y
s1600907 1:e1267e72ade8 104 volatile double y = 305.5;
s1600907 0:c96cf9760185 105 volatile const double pi = 3.14159265359;
sjoerdbarts 10:4bd8ec9e79ff 106 volatile double Speed = 10; // Speed with which x and y are changed, in mm/s
sjoerdbarts 10:4bd8ec9e79ff 107 volatile double Theta1Gear = 60.0; // Beginpositie op 60 graden
s1600907 3:c524afedf863 108 volatile double Theta2Gear = 60.0;
s1600907 1:e1267e72ade8 109 volatile double Theta1 = Theta1Gear*42/12; // Beginpositie van MotorHoek
s1600907 1:e1267e72ade8 110 volatile double Theta2 = Theta2Gear*42/12;
sjoerdbarts 8:676646c50aeb 111
sjoerdbarts 10:4bd8ec9e79ff 112 // Stepper motor setup
sjoerdbarts 10:4bd8ec9e79ff 113 // Set constans
sjoerdbarts 10:4bd8ec9e79ff 114 volatile int stepmode = 16; // step mode
sjoerdbarts 10:4bd8ec9e79ff 115 volatile int steps = 150*stepmode; // amount of steps for 90 degree rotation = 50, full step mode: 1.8 degree per step.
sjoerdbarts 10:4bd8ec9e79ff 116 volatile int i = 0;
sjoerdbarts 10:4bd8ec9e79ff 117 volatile bool Stepper_CCW = false;
sjoerdbarts 10:4bd8ec9e79ff 118
sjoerdbarts 11:417193f23342 119 // Setup stepper motor pins
sjoerdbarts 12:9b0451105991 120 // DigitalOut pinMode(PTD2); //D11 NOW USES 3.3V OUPUT, SINCE THIS IS ALWAYS ON
sjoerdbarts 13:e8b8b035abbd 121 DigitalOut pinSleep(PTE25); //D14
sjoerdbarts 11:417193f23342 122 DigitalOut pinStep(PTC4); //D9
sjoerdbarts 11:417193f23342 123 DigitalOut pinDir(PTC12); //D8
sjoerdbarts 11:417193f23342 124
sjoerdbarts 11:417193f23342 125 // Control of the stepper motor with 1 Ticker and 1 Timeout
sjoerdbarts 11:417193f23342 126 Ticker TickerStepper;
sjoerdbarts 11:417193f23342 127 Timeout TimeoutStepper;
sjoerdbarts 11:417193f23342 128
sjoerdbarts 10:4bd8ec9e79ff 129 // Global variable Step_State
s1600907 0:c96cf9760185 130 volatile bool Stepper_State = false; // false = we zijn niet bezig met flippen
sjoerdbarts 10:4bd8ec9e79ff 131
sjoerdbarts 13:e8b8b035abbd 132 // Setup Tickers
sjoerdbarts 13:e8b8b035abbd 133 Ticker CalculationsTicker;
sjoerdbarts 13:e8b8b035abbd 134 Ticker BlinkLedTicker;
sjoerdbarts 13:e8b8b035abbd 135 Ticker PIDControlTicker;
sjoerdbarts 13:e8b8b035abbd 136 Ticker PotControlTicker;
sjoerdbarts 13:e8b8b035abbd 137
sjoerdbarts 10:4bd8ec9e79ff 138 /////////////////////// Functtions for stepper motor /////////////////////////////////////
sjoerdbarts 10:4bd8ec9e79ff 139 // Set the Step pin to 0
sjoerdbarts 10:4bd8ec9e79ff 140 void StepperFall()
sjoerdbarts 10:4bd8ec9e79ff 141 {
sjoerdbarts 10:4bd8ec9e79ff 142 pinStep = 0;
sjoerdbarts 10:4bd8ec9e79ff 143 }
sjoerdbarts 10:4bd8ec9e79ff 144 // Turn off stepper and power off driver board. Reset Stepper_CCS, i and Stepper_State
sjoerdbarts 10:4bd8ec9e79ff 145 void Stepper_Off()
sjoerdbarts 10:4bd8ec9e79ff 146 {
sjoerdbarts 10:4bd8ec9e79ff 147 TickerStepper.detach();
sjoerdbarts 10:4bd8ec9e79ff 148 pinSleep = 0;
sjoerdbarts 10:4bd8ec9e79ff 149 i=0;
sjoerdbarts 10:4bd8ec9e79ff 150 Stepper_State = false;
sjoerdbarts 10:4bd8ec9e79ff 151 Stepper_CCW = false;
sjoerdbarts 10:4bd8ec9e79ff 152 }
sjoerdbarts 10:4bd8ec9e79ff 153
sjoerdbarts 10:4bd8ec9e79ff 154 // Change direction
sjoerdbarts 10:4bd8ec9e79ff 155 void Stepper_Change_Dir()
sjoerdbarts 10:4bd8ec9e79ff 156 {
sjoerdbarts 10:4bd8ec9e79ff 157 pinDir = true;
sjoerdbarts 10:4bd8ec9e79ff 158 Stepper_CCW = true;
sjoerdbarts 10:4bd8ec9e79ff 159 i = 0;
sjoerdbarts 10:4bd8ec9e79ff 160 }
sjoerdbarts 10:4bd8ec9e79ff 161
sjoerdbarts 10:4bd8ec9e79ff 162 // Move the motor 1 step
sjoerdbarts 10:4bd8ec9e79ff 163 void StepperRise()
sjoerdbarts 10:4bd8ec9e79ff 164 {
sjoerdbarts 10:4bd8ec9e79ff 165 if((i<steps)&&(not Stepper_CCW))
sjoerdbarts 10:4bd8ec9e79ff 166 {
sjoerdbarts 10:4bd8ec9e79ff 167 pinStep=1; // Set stepper to 1
sjoerdbarts 10:4bd8ec9e79ff 168 // attach timeout to set it back to 0, min step duration is 1.8 us
sjoerdbarts 10:4bd8ec9e79ff 169 TimeoutStepper.attach_us(&StepperFall, 2);
sjoerdbarts 10:4bd8ec9e79ff 170 i=i+1;
sjoerdbarts 10:4bd8ec9e79ff 171 }
sjoerdbarts 10:4bd8ec9e79ff 172 else if (Stepper_CCW)
sjoerdbarts 10:4bd8ec9e79ff 173 {
sjoerdbarts 10:4bd8ec9e79ff 174 if(i<steps)
sjoerdbarts 10:4bd8ec9e79ff 175 {
sjoerdbarts 10:4bd8ec9e79ff 176 pinStep=1;
sjoerdbarts 10:4bd8ec9e79ff 177 TimeoutStepper.attach_us(&StepperFall, 2);
sjoerdbarts 10:4bd8ec9e79ff 178 i=i+1;
sjoerdbarts 10:4bd8ec9e79ff 179 }
sjoerdbarts 10:4bd8ec9e79ff 180 else
sjoerdbarts 10:4bd8ec9e79ff 181 {
sjoerdbarts 10:4bd8ec9e79ff 182 Stepper_Off();
sjoerdbarts 10:4bd8ec9e79ff 183 }
sjoerdbarts 10:4bd8ec9e79ff 184 }
sjoerdbarts 10:4bd8ec9e79ff 185 else
sjoerdbarts 10:4bd8ec9e79ff 186 {
sjoerdbarts 10:4bd8ec9e79ff 187 Stepper_Change_Dir();
sjoerdbarts 10:4bd8ec9e79ff 188 }
sjoerdbarts 10:4bd8ec9e79ff 189 }
sjoerdbarts 10:4bd8ec9e79ff 190
sjoerdbarts 10:4bd8ec9e79ff 191 // Activate the stepper motor
sjoerdbarts 10:4bd8ec9e79ff 192 // at a constant speed
sjoerdbarts 10:4bd8ec9e79ff 193 void Stepper_On()
sjoerdbarts 10:4bd8ec9e79ff 194 {
sjoerdbarts 13:e8b8b035abbd 195 if (Stepper_State == false)
sjoerdbarts 13:e8b8b035abbd 196 {
sjoerdbarts 10:4bd8ec9e79ff 197 // Set global variable to true
sjoerdbarts 10:4bd8ec9e79ff 198 Stepper_State = true;
sjoerdbarts 10:4bd8ec9e79ff 199 // Power on the board and set direction to CW
sjoerdbarts 10:4bd8ec9e79ff 200 pinSleep = 1;
sjoerdbarts 10:4bd8ec9e79ff 201 pinDir = false;
sjoerdbarts 10:4bd8ec9e79ff 202 // Calc the speed of the stepper
sjoerdbarts 10:4bd8ec9e79ff 203 int nPPS = 50*stepmode; // was 1200, this controlls the speed, keep this times the step mode
sjoerdbarts 11:417193f23342 204 double fFrequency_Hz = 1.f * nPPS;
sjoerdbarts 11:417193f23342 205 double fPeriod_s = 1.0f / fFrequency_Hz;
sjoerdbarts 10:4bd8ec9e79ff 206 // Check if the speed is too fast small and report back if that is the case
sjoerdbarts 10:4bd8ec9e79ff 207 if (fPeriod_s < 2e-6)
sjoerdbarts 10:4bd8ec9e79ff 208 {
sjoerdbarts 10:4bd8ec9e79ff 209 pc.printf("\r\n ERROR: fPeriod_s too small \r\n");
sjoerdbarts 10:4bd8ec9e79ff 210 fPeriod_s=2e-6;
sjoerdbarts 10:4bd8ec9e79ff 211 }
sjoerdbarts 10:4bd8ec9e79ff 212
sjoerdbarts 10:4bd8ec9e79ff 213 TickerStepper.attach(&StepperRise, // void(*fptr)(void)
sjoerdbarts 10:4bd8ec9e79ff 214 fPeriod_s // float t
sjoerdbarts 10:4bd8ec9e79ff 215 );
sjoerdbarts 13:e8b8b035abbd 216 }
sjoerdbarts 10:4bd8ec9e79ff 217 }
s1600907 0:c96cf9760185 218
sjoerdbarts 7:bafc32b576c4 219 /////////////////////// functions for filters /////////////////////////////////////////////
s1600907 0:c96cf9760185 220 void sample()
s1600907 0:c96cf9760185 221 {
s1600907 0:c96cf9760185 222 /* Sample function
s1600907 0:c96cf9760185 223 samples the emg0 (of the rightBiceps)
s1600907 0:c96cf9760185 224 samples the emg1 (of the leftBiceps)
s1600907 0:c96cf9760185 225 samples the emg2 (of the Upper leg)
s1600907 0:c96cf9760185 226 filter the singals
s1600907 0:c96cf9760185 227 sends it to HIDScope
s1600907 0:c96cf9760185 228 */
s1600907 0:c96cf9760185 229
s1600907 0:c96cf9760185 230 // Rechts Biceps
s1600907 0:c96cf9760185 231 double inRechts = emg0.read(); // EMG signal
s1600907 0:c96cf9760185 232 double FilterRechts = bqc.step(inRechts); // High pass + Notch (50 HZ)
s1600907 0:c96cf9760185 233 double RectifyRechts = fabs(FilterRechts); // Rectify
s1600907 0:c96cf9760185 234 double outRechts = bq3.step(RectifyRechts); // Low pass
s1600907 2:92593c9d6146 235
s1600907 0:c96cf9760185 236 // Links Biceps
s1600907 0:c96cf9760185 237 double inLinks = emg1.read(); // EMG signal
s1600907 0:c96cf9760185 238 double FilterLinks = bqc2.step(inLinks); // High pass + Notch (50 HZ)
s1600907 0:c96cf9760185 239 double RectifyLinks = fabs(FilterLinks); // Rectify
s1600907 0:c96cf9760185 240 double outLinks = bq6.step(RectifyLinks); // Low pass
s1600907 0:c96cf9760185 241
s1600907 0:c96cf9760185 242 // Upper leg
s1600907 0:c96cf9760185 243 double inBeen = emg2.read(); // EMG signal
s1600907 0:c96cf9760185 244 double FilterBeen = bqc3.step(inBeen); // High pass + Notch (50 HZ)
s1600907 0:c96cf9760185 245 double RectifyBeen = fabs(FilterBeen); // Rectify
s1600907 2:92593c9d6146 246 double outBeen = bq9.step(RectifyBeen); // Low pass
s1600907 0:c96cf9760185 247
s1600907 0:c96cf9760185 248
s1600907 0:c96cf9760185 249 /* EMG signal in channel 0 (the first channel)
s1600907 0:c96cf9760185 250 and the filtered EMG signal in channel 1 (the second channel)
s1600907 0:c96cf9760185 251 of the HIDscope */
s1600907 5:b4a0301ec8cc 252 /*scope.set(0,inRechts);
s1600907 0:c96cf9760185 253 scope.set(1,outRechts);
s1600907 2:92593c9d6146 254 scope.set(2,inLinks);
s1600907 0:c96cf9760185 255 scope.set(3,outLinks);
s1600907 0:c96cf9760185 256 scope.set(4,inBeen);
s1600907 0:c96cf9760185 257 scope.set(5,outBeen);
s1600907 5:b4a0301ec8cc 258 */
s1600907 0:c96cf9760185 259 // To indicate that the function is working, the LED is on
s1600907 1:e1267e72ade8 260 if (outRechts >= 0.04){
s1600907 0:c96cf9760185 261 BicepsRight = true;
sjoerdbarts 13:e8b8b035abbd 262 red = 1;
s1600907 0:c96cf9760185 263 }
s1600907 0:c96cf9760185 264 else{
s1600907 0:c96cf9760185 265 BicepsRight = false;
sjoerdbarts 13:e8b8b035abbd 266 red = 0;
s1600907 0:c96cf9760185 267 }
s1600907 2:92593c9d6146 268
s1600907 0:c96cf9760185 269 // If Biceps links is actuated then:
s1600907 1:e1267e72ade8 270 if (outLinks >= 0.04){
s1600907 0:c96cf9760185 271 BicepsLeft = true;
sjoerdbarts 13:e8b8b035abbd 272 blue = 1;
s1600907 0:c96cf9760185 273 }
s1600907 0:c96cf9760185 274 else{
s1600907 0:c96cf9760185 275 BicepsLeft = false;
sjoerdbarts 13:e8b8b035abbd 276 blue = 0;
s1600907 0:c96cf9760185 277 }
s1600907 0:c96cf9760185 278 // If upper leg is actuated then:
s1600907 0:c96cf9760185 279 if (outBeen >= 0.01){
s1600907 0:c96cf9760185 280 Leg = true;
sjoerdbarts 13:e8b8b035abbd 281 green = 1;
s1600907 0:c96cf9760185 282 }
s1600907 0:c96cf9760185 283 else{
s1600907 0:c96cf9760185 284 Leg = false;
sjoerdbarts 13:e8b8b035abbd 285 green = 0;
s1600907 0:c96cf9760185 286 }
s1600907 0:c96cf9760185 287 }
s1600907 0:c96cf9760185 288
sjoerdbarts 7:bafc32b576c4 289 ///////////////////// functions for "motorhoekberekenen" //////////////////////////
sjoerdbarts 7:bafc32b576c4 290 // save previous x
s1600907 0:c96cf9760185 291 double Calc_Prev_x () {
s1600907 0:c96cf9760185 292 double Prev_x = x;
s1600907 0:c96cf9760185 293 //pc.printf("prev x = %f\r\n", Prev_x);
s1600907 0:c96cf9760185 294 return Prev_x;
s1600907 0:c96cf9760185 295 }
s1600907 0:c96cf9760185 296
sjoerdbarts 7:bafc32b576c4 297 // save previous y
s1600907 0:c96cf9760185 298 double Calc_Prev_y () {
s1600907 0:c96cf9760185 299 double Prev_y = y;
s1600907 0:c96cf9760185 300 //pc.printf("prev y = %f\r\n", Prev_y);
s1600907 0:c96cf9760185 301 return Prev_y;
s1600907 0:c96cf9760185 302 }
s1600907 0:c96cf9760185 303
sjoerdbarts 7:bafc32b576c4 304 // save previous Theta1Gear
s1600907 4:05c5da1c8b08 305 double Calc_Prev_Theta1_Gear () {
s1600907 4:05c5da1c8b08 306 double Prev_Theta1_Gear = Theta1Gear;
s1600907 4:05c5da1c8b08 307 return Prev_Theta1_Gear;
s1600907 4:05c5da1c8b08 308 }
s1600907 4:05c5da1c8b08 309
sjoerdbarts 7:bafc32b576c4 310 // save previous Theta2Gear
s1600907 4:05c5da1c8b08 311 double Calc_Prev_Theta2_Gear () {
s1600907 4:05c5da1c8b08 312 double Prev_Theta2_Gear = Theta2Gear;
s1600907 4:05c5da1c8b08 313 return Prev_Theta2_Gear;
s1600907 4:05c5da1c8b08 314 }
s1600907 4:05c5da1c8b08 315
sjoerdbarts 8:676646c50aeb 316 void CalcXY ()
sjoerdbarts 7:bafc32b576c4 317 {
sjoerdbarts 8:676646c50aeb 318 // calc steps in mm
sjoerdbarts 8:676646c50aeb 319 double Step = Speed/CALC_F ; //10 mm per seconde afleggen
s1600907 0:c96cf9760185 320
s1600907 0:c96cf9760185 321 if (BicepsLeft==true && BicepsRight==true && Leg==true && Stepper_State==false) {
sjoerdbarts 11:417193f23342 322 Stepper_On();
s1600907 0:c96cf9760185 323 }
s1600907 0:c96cf9760185 324 else if (BicepsLeft==true && BicepsRight==false && Leg==false && Stepper_State==false) {
s1600907 0:c96cf9760185 325 x = x - Step;
s1600907 0:c96cf9760185 326 }
s1600907 0:c96cf9760185 327 else if (BicepsLeft==false && BicepsRight==true && Leg==false && Stepper_State==false) {
s1600907 0:c96cf9760185 328 x = x + Step; // naar Right bewegen
s1600907 0:c96cf9760185 329 }
s1600907 0:c96cf9760185 330 else if (BicepsLeft==true && BicepsRight==true && Leg==false && Stepper_State==false) {
s1600907 0:c96cf9760185 331 y = y + Step; // naar voren bewegen
s1600907 0:c96cf9760185 332 }
s1600907 0:c96cf9760185 333 else if (BicepsLeft==false && BicepsRight==true && Leg==true && Stepper_State==false) {
s1600907 0:c96cf9760185 334 y = y - Step; // naar achter bewegen
s1600907 0:c96cf9760185 335 }
s1600907 0:c96cf9760185 336 else if (BicepsLeft==false && BicepsRight==false && Leg==false || Stepper_State==true) {
s1600907 0:c96cf9760185 337 }
s1600907 0:c96cf9760185 338
s1600907 0:c96cf9760185 339 // Grenswaardes LET OP: ARMEN MISSCHIEN GEBLOKKEERD DOOR BALK AAN DE BINNENKANT
s1600907 0:c96cf9760185 340 if (x > 200) {
s1600907 0:c96cf9760185 341 x = 200;
s1600907 0:c96cf9760185 342 }
s1600907 0:c96cf9760185 343 else if (x < -200) {
s1600907 0:c96cf9760185 344 x = -200;
s1600907 0:c96cf9760185 345 }
s1600907 0:c96cf9760185 346 if (y > 306) {
s1600907 0:c96cf9760185 347 y = 306;
s1600907 0:c96cf9760185 348 }
s1600907 0:c96cf9760185 349 else if (y < 50) {
s1600907 0:c96cf9760185 350 y = 50; // GOKJE, UITPROBEREN
s1600907 0:c96cf9760185 351 }
s1600907 5:b4a0301ec8cc 352 //pc.printf("x = %f, y = %f\r\n", x, y);
s1600907 1:e1267e72ade8 353
s1600907 2:92593c9d6146 354 //scope.set(2,x);
s1600907 2:92593c9d6146 355 //scope.set(3,y);
s1600907 0:c96cf9760185 356 }
s1600907 0:c96cf9760185 357
s1600907 0:c96cf9760185 358 // diagonaal berekenen voor linker arm
s1600907 0:c96cf9760185 359 double CalcDia1 (double x, double y) {
s1600907 0:c96cf9760185 360 double a = 50.0; // de afstand van gekozen assenstelsel tot de armas (assenstelsel precies in het midden) KEERTJE NAMETEN
s1600907 0:c96cf9760185 361 double BV1 = sqrt(pow((a+x),2) + pow(y,2)); // diagonaal (afstand van armas tot locatie) berekenen
s1600907 0:c96cf9760185 362 double Dia1 = pow(BV1,2)/(2*BV1); // berekenen van de afstand oorsprong tot diagonaal
s1600907 0:c96cf9760185 363
s1600907 0:c96cf9760185 364 //pc.printf("dia = %f, x = %f, y= %f\r\n", Dia1, x, y);
s1600907 0:c96cf9760185 365 return Dia1;
s1600907 0:c96cf9760185 366 }
s1600907 0:c96cf9760185 367
s1600907 0:c96cf9760185 368 // diagonaal berekenen voor rechter arm
s1600907 0:c96cf9760185 369 double CalcDia2 (double x, double y) {
s1600907 0:c96cf9760185 370 double a = 50.0;
s1600907 0:c96cf9760185 371 double BV2 = sqrt(pow((x-a),2) + pow(y,2)); // zelfde nog een keer doen maar nu voor de rechter arm
s1600907 0:c96cf9760185 372 double Dia2 = pow(BV2,2)/(2*BV2);
s1600907 0:c96cf9760185 373
s1600907 0:c96cf9760185 374 //pc.printf("dia = %f, x = %f, y= %f\r\n", Dia2, x, y);
s1600907 0:c96cf9760185 375 return Dia2;
s1600907 0:c96cf9760185 376 }
s1600907 0:c96cf9760185 377
s1600907 0:c96cf9760185 378 // calculate Theta1
s1600907 4:05c5da1c8b08 379 void CalcTheta1 (double Dia1) {
s1600907 0:c96cf9760185 380 double a = 50.0;
s1600907 0:c96cf9760185 381 double Bar = 200.0; // lengte van de armen
s1600907 0:c96cf9760185 382
s1600907 0:c96cf9760185 383 // Hoek berekenen van het grote tandwiel (gear)
s1600907 0:c96cf9760185 384 if (x > -a) {
s1600907 0:c96cf9760185 385 Theta1Gear = pi - atan(y/(x+a)) - acos(Dia1/Bar);
s1600907 0:c96cf9760185 386 }
s1600907 0:c96cf9760185 387 else if (x > -a) {
s1600907 0:c96cf9760185 388 Theta1Gear = pi - (pi + atan(y/(x+a))) - acos(Dia1/Bar);
s1600907 0:c96cf9760185 389 }
s1600907 0:c96cf9760185 390 else { // als x=-a
s1600907 0:c96cf9760185 391 Theta1Gear = 0.5*pi - acos(Dia1/Bar);
s1600907 0:c96cf9760185 392 }
s1600907 3:c524afedf863 393 Theta1Gear = Theta1Gear*180.0/pi; // veranderen van radialen naar graden
s1600907 0:c96cf9760185 394
s1600907 0:c96cf9760185 395 // omrekenen van grote tandwiel naar motortandwiel
s1600907 0:c96cf9760185 396 Theta1 = Theta1Gear*42.0/12.0; // grote tandwiel heeft 42 tanden. Motortandwiel heeft er 12.
s1600907 0:c96cf9760185 397
s1600907 5:b4a0301ec8cc 398 pc.printf("thetaMotor = %f, thetaGear = %f\r\n", Theta1, Theta1Gear);
s1600907 0:c96cf9760185 399 }
s1600907 0:c96cf9760185 400
s1600907 4:05c5da1c8b08 401 void CalcTheta2 (double Dia2) {
s1600907 0:c96cf9760185 402 double a = 50.0;
s1600907 0:c96cf9760185 403 double Bar = 200.0; // lengte van de armen
s1600907 0:c96cf9760185 404 double Prev_Theta2_Gear = Theta2Gear;
s1600907 4:05c5da1c8b08 405
s1600907 0:c96cf9760185 406 // Hoek berekenen van het grote tandwiel (gear)
s1600907 0:c96cf9760185 407 if (x < a) {
s1600907 0:c96cf9760185 408 Theta2Gear = pi + atan(y/(x-a)) - acos(Dia2/Bar);
s1600907 0:c96cf9760185 409 }
s1600907 0:c96cf9760185 410 else if (x > a) {
s1600907 0:c96cf9760185 411 Theta2Gear = pi - (pi - atan(y/(x-a))) - acos(Dia2/Bar);
s1600907 0:c96cf9760185 412 }
s1600907 0:c96cf9760185 413 else { // als x=a
s1600907 0:c96cf9760185 414 Theta2Gear = 0.5*pi - acos(Dia2/Bar);
s1600907 0:c96cf9760185 415 }
s1600907 3:c524afedf863 416 Theta2Gear = Theta2Gear*180/pi; // veranderen van radialen naar graden
s1600907 0:c96cf9760185 417
s1600907 4:05c5da1c8b08 418 // omrekenen van grote tandwiel naar motortandwiel
s1600907 4:05c5da1c8b08 419 Theta2 = Theta2Gear*42.0/12.0; // grote tandwiel heeft 42 tanden. Motortandwiel heeft er 12.
s1600907 4:05c5da1c8b08 420
s1600907 5:b4a0301ec8cc 421 pc.printf("thetaMotor = %f, thetaGear = %f\r\n", Theta2, Theta2Gear);
s1600907 4:05c5da1c8b08 422 }
s1600907 4:05c5da1c8b08 423
s1600907 4:05c5da1c8b08 424 // als een van de hoeken te groot wordt, zet dan alles terug naar de vorige positie
s1600907 4:05c5da1c8b08 425 void AngleLimits (double Prev_Theta1_Gear, double Prev_Theta2_Gear, double Prev_x, double Prev_y) {
s1600907 4:05c5da1c8b08 426 double MaxThetaGear = 100.0; // de hoek voordat arm het opstakel raakt (max hoek is 107.62 tussen arm en opstakel, maken er 100 van voor veiligheid)
s1600907 4:05c5da1c8b08 427
s1600907 4:05c5da1c8b08 428 if (Theta1Gear >= MaxThetaGear || Theta2Gear >= MaxThetaGear) {
s1600907 4:05c5da1c8b08 429 Theta1Gear = Prev_Theta1_Gear;
s1600907 0:c96cf9760185 430 Theta2Gear = Prev_Theta2_Gear;
s1600907 0:c96cf9760185 431 x = Prev_x;
s1600907 0:c96cf9760185 432 y = Prev_y;
s1600907 4:05c5da1c8b08 433
s1600907 4:05c5da1c8b08 434 Theta1 = Theta1Gear*42.0/12.0;
s1600907 4:05c5da1c8b08 435 Theta2 = Theta2Gear*42.0/12.0;
s1600907 0:c96cf9760185 436 }
s1600907 5:b4a0301ec8cc 437 pc.printf("thetaMotor = %f, thetaGear = %f\r\n", Theta2, Theta2Gear);
s1600907 0:c96cf9760185 438 }
s1600907 0:c96cf9760185 439
s1600907 0:c96cf9760185 440 void CalculationsForTheta () {
sjoerdbarts 12:9b0451105991 441 sample();
s1600907 0:c96cf9760185 442 double Prev_x = Calc_Prev_x ();
s1600907 0:c96cf9760185 443 double Prev_y = Calc_Prev_y ();
sjoerdbarts 8:676646c50aeb 444 double Prev_Theta1_Gear = Calc_Prev_Theta1_Gear ();
sjoerdbarts 8:676646c50aeb 445 double Prev_Theta2_Gear = Calc_Prev_Theta2_Gear ();
sjoerdbarts 8:676646c50aeb 446 CalcXY();
s1600907 0:c96cf9760185 447 double Dia1 = CalcDia1 (x, y);
s1600907 0:c96cf9760185 448 double Dia2 = CalcDia2 (x, y);
s1600907 4:05c5da1c8b08 449 CalcTheta1 (Dia1);
sjoerdbarts 8:676646c50aeb 450 CalcTheta2 (Dia2);
sjoerdbarts 8:676646c50aeb 451 AngleLimits (Prev_Theta1_Gear, Prev_Theta2_Gear, Prev_x, Prev_y); // laatste check
s1600907 0:c96cf9760185 452 }
s1600907 0:c96cf9760185 453
sjoerdbarts 8:676646c50aeb 454 ////////////////////////// Code for control /////////////////////////////////////
sjoerdbarts 8:676646c50aeb 455
sjoerdbarts 8:676646c50aeb 456 double m1_GetPosition()
sjoerdbarts 8:676646c50aeb 457 {
sjoerdbarts 8:676646c50aeb 458 int countsCW = m1_EncoderCW.getPulses();
sjoerdbarts 8:676646c50aeb 459 int countsCCW= m1_EncoderCCW.getPulses();
sjoerdbarts 8:676646c50aeb 460 int net_counts=countsCW-countsCCW;
sjoerdbarts 8:676646c50aeb 461 double Position=(net_counts*360.0)/COUNTS_PER_REV;
sjoerdbarts 8:676646c50aeb 462 return Position;
sjoerdbarts 8:676646c50aeb 463 }
sjoerdbarts 8:676646c50aeb 464
sjoerdbarts 8:676646c50aeb 465 double m2_GetPosition()
sjoerdbarts 8:676646c50aeb 466 {
sjoerdbarts 8:676646c50aeb 467 int countsCW = m2_EncoderCW.getPulses();
sjoerdbarts 8:676646c50aeb 468 int countsCCW= m2_EncoderCCW.getPulses();
sjoerdbarts 8:676646c50aeb 469 int net_counts=countsCW-countsCCW;
sjoerdbarts 8:676646c50aeb 470 double Position=(net_counts*360.0)/COUNTS_PER_REV;
sjoerdbarts 8:676646c50aeb 471 return Position;
sjoerdbarts 8:676646c50aeb 472 }
sjoerdbarts 8:676646c50aeb 473
sjoerdbarts 8:676646c50aeb 474 // Position control when calibrating
sjoerdbarts 8:676646c50aeb 475 double m1_GetPosition_cal()
sjoerdbarts 8:676646c50aeb 476 {
sjoerdbarts 8:676646c50aeb 477 int countsCW = m1_EncoderCW.getPulses();
sjoerdbarts 8:676646c50aeb 478 int countsCCW= m1_EncoderCCW.getPulses();
sjoerdbarts 8:676646c50aeb 479 int net_counts=countsCW-countsCCW;
sjoerdbarts 8:676646c50aeb 480 double Position=(net_counts*360.0)/COUNTS_PER_REV+210.0f; // calibrated position is 210 degrees
sjoerdbarts 8:676646c50aeb 481 return Position;
sjoerdbarts 8:676646c50aeb 482 }
sjoerdbarts 8:676646c50aeb 483
sjoerdbarts 8:676646c50aeb 484 // Position control when calibrating
sjoerdbarts 8:676646c50aeb 485 double m2_GetPosition_cal()
sjoerdbarts 8:676646c50aeb 486 {
sjoerdbarts 8:676646c50aeb 487 int countsCW = m2_EncoderCW.getPulses();
sjoerdbarts 8:676646c50aeb 488 int countsCCW= m2_EncoderCCW.getPulses();
sjoerdbarts 8:676646c50aeb 489 int net_counts=countsCW-countsCCW;
sjoerdbarts 8:676646c50aeb 490 double Position=(net_counts*360.0)/COUNTS_PER_REV+210.0f; // calibrated position is 210 degrees
sjoerdbarts 8:676646c50aeb 491 return Position;
sjoerdbarts 8:676646c50aeb 492 }
sjoerdbarts 8:676646c50aeb 493 double m1_PID(double error, const double Kp, const double Ki, const double Kd, const double Ts, const double N, double &m1_v1, double &m1_v2)
sjoerdbarts 8:676646c50aeb 494 {
sjoerdbarts 8:676646c50aeb 495 double a1 = -4/(N*Ts+2),
sjoerdbarts 8:676646c50aeb 496 a2 = -1*(N*Ts - 2)/(N*Ts+2),
sjoerdbarts 8:676646c50aeb 497 b0 = (4*Kp + 4*Kd*N + 2*Ki*Ts + 2*Kp*N*Ts + Ki*N*pow(Ts,2))/(2*N*Ts + 4),
sjoerdbarts 8:676646c50aeb 498 b1 = (Ki*N*pow(Ts,2) - 4*Kp - 4*Kd*N)/(N*Ts + 2),
sjoerdbarts 8:676646c50aeb 499 b2 = (4*Kp + 4*Kd*N - 2*Ki*Ts - 2*Kp*N*Ts + Ki*N*pow(Ts,2))/(2*N*Ts + 4);
sjoerdbarts 8:676646c50aeb 500
sjoerdbarts 8:676646c50aeb 501 double v = error - a1*m1_v1 - a2*m1_v2;
sjoerdbarts 8:676646c50aeb 502 double u = b0*v + b1*m1_v1 + b2*m1_v2;
sjoerdbarts 8:676646c50aeb 503 m1_v2 = m1_v1; m1_v1 = v;
sjoerdbarts 8:676646c50aeb 504 return u;
sjoerdbarts 8:676646c50aeb 505 }
sjoerdbarts 8:676646c50aeb 506
sjoerdbarts 8:676646c50aeb 507 double m2_PID(double error, const double Kp, const double Ki, const double Kd, const double Ts, const double N, double &m2_v1, double &m2_v2)
sjoerdbarts 8:676646c50aeb 508 {
sjoerdbarts 8:676646c50aeb 509 double a1 = -4/(N*Ts+2),
sjoerdbarts 8:676646c50aeb 510 a2 = -1*(N*Ts - 2)/(N*Ts+2),
sjoerdbarts 8:676646c50aeb 511 b0 = (4*Kp + 4*Kd*N + 2*Ki*Ts + 2*Kp*N*Ts + Ki*N*pow(Ts,2))/(2*N*Ts + 4),
sjoerdbarts 8:676646c50aeb 512 b1 = (Ki*N*pow(Ts,2) - 4*Kp - 4*Kd*N)/(N*Ts + 2),
sjoerdbarts 8:676646c50aeb 513 b2 = (4*Kp + 4*Kd*N - 2*Ki*Ts - 2*Kp*N*Ts + Ki*N*pow(Ts,2))/(2*N*Ts + 4);
sjoerdbarts 8:676646c50aeb 514
sjoerdbarts 8:676646c50aeb 515 double v = error - a1*m1_v1 - a2*m1_v2;
sjoerdbarts 8:676646c50aeb 516 double u = b0*v + b1*m1_v1 + b2*m1_v2;
sjoerdbarts 8:676646c50aeb 517 m1_v2 = m1_v1; m1_v1 = v;
sjoerdbarts 8:676646c50aeb 518 return u;
sjoerdbarts 8:676646c50aeb 519 }
sjoerdbarts 8:676646c50aeb 520
sjoerdbarts 8:676646c50aeb 521
s1600907 0:c96cf9760185 522
sjoerdbarts 8:676646c50aeb 523 void SetMotor(int motor_number, double MotorValue)
sjoerdbarts 8:676646c50aeb 524 {
sjoerdbarts 8:676646c50aeb 525 // Given -1<=motorValue<=1, this sets the PWM and direction
sjoerdbarts 8:676646c50aeb 526 // bits for motor 1. Positive value makes motor rotating
sjoerdbarts 8:676646c50aeb 527 // clockwise. motorValues outside range are truncated to
sjoerdbarts 8:676646c50aeb 528 // within range
sjoerdbarts 8:676646c50aeb 529 if (motor_number == 1)
sjoerdbarts 8:676646c50aeb 530 {
sjoerdbarts 8:676646c50aeb 531 if (MotorValue >=0)
sjoerdbarts 8:676646c50aeb 532 {
sjoerdbarts 8:676646c50aeb 533 motor1_dir=0;
sjoerdbarts 8:676646c50aeb 534 }
sjoerdbarts 8:676646c50aeb 535 else
sjoerdbarts 8:676646c50aeb 536 {
sjoerdbarts 8:676646c50aeb 537 motor1_dir=1;
sjoerdbarts 8:676646c50aeb 538 }
sjoerdbarts 8:676646c50aeb 539 if (fabs(MotorValue)>1){
sjoerdbarts 8:676646c50aeb 540 motor1_pwm.write(1);
sjoerdbarts 8:676646c50aeb 541 }
sjoerdbarts 8:676646c50aeb 542 else
sjoerdbarts 8:676646c50aeb 543 {
sjoerdbarts 8:676646c50aeb 544 motor1_pwm.write(abs(MotorValue));
sjoerdbarts 8:676646c50aeb 545 }
sjoerdbarts 8:676646c50aeb 546 }
sjoerdbarts 8:676646c50aeb 547 else
sjoerdbarts 8:676646c50aeb 548 {
sjoerdbarts 8:676646c50aeb 549 if (MotorValue >=0)
sjoerdbarts 8:676646c50aeb 550 {
sjoerdbarts 8:676646c50aeb 551 motor2_dir=0;
sjoerdbarts 8:676646c50aeb 552 }
sjoerdbarts 8:676646c50aeb 553 else
sjoerdbarts 8:676646c50aeb 554 {
sjoerdbarts 8:676646c50aeb 555 motor2_dir=1;
sjoerdbarts 8:676646c50aeb 556 }
sjoerdbarts 8:676646c50aeb 557 if (fabs(MotorValue)>1){
sjoerdbarts 8:676646c50aeb 558 motor2_pwm.write(1);
sjoerdbarts 8:676646c50aeb 559 }
sjoerdbarts 8:676646c50aeb 560 else
sjoerdbarts 8:676646c50aeb 561 {
sjoerdbarts 8:676646c50aeb 562 motor2_pwm.write(abs(MotorValue));
sjoerdbarts 8:676646c50aeb 563 }
sjoerdbarts 8:676646c50aeb 564 }
sjoerdbarts 8:676646c50aeb 565 }
sjoerdbarts 8:676646c50aeb 566
sjoerdbarts 8:676646c50aeb 567 void BlinkLed(){
sjoerdbarts 8:676646c50aeb 568 led = not led;
sjoerdbarts 8:676646c50aeb 569 }
sjoerdbarts 8:676646c50aeb 570
sjoerdbarts 8:676646c50aeb 571 void Controller_motor()
sjoerdbarts 8:676646c50aeb 572 {
sjoerdbarts 8:676646c50aeb 573 // get the actual position
sjoerdbarts 8:676646c50aeb 574 double m1_Position = m1_GetPosition_cal();
sjoerdbarts 8:676646c50aeb 575 double m2_Position = m2_GetPosition_cal();
sjoerdbarts 8:676646c50aeb 576 // Set position scopes
sjoerdbarts 8:676646c50aeb 577 scope.set(0,x);
sjoerdbarts 8:676646c50aeb 578 scope.set(1,y);
sjoerdbarts 8:676646c50aeb 579 scope.set(2,Theta1);
sjoerdbarts 8:676646c50aeb 580 scope.set(3,Theta2);
sjoerdbarts 8:676646c50aeb 581 /*
sjoerdbarts 8:676646c50aeb 582 scope.set(0,Theta1);
sjoerdbarts 8:676646c50aeb 583 scope.set(1,m1_Position);
sjoerdbarts 8:676646c50aeb 584 scope.set(3,Theta2);
sjoerdbarts 8:676646c50aeb 585 scope.set(4,m2_Position);
sjoerdbarts 8:676646c50aeb 586 */
sjoerdbarts 8:676646c50aeb 587 //scope.set(2,m1_Position);
sjoerdbarts 8:676646c50aeb 588 //scope.set(4,m2_Position);
sjoerdbarts 8:676646c50aeb 589 // calc the error
sjoerdbarts 8:676646c50aeb 590 double m1_error = Theta1 - m1_Position;
sjoerdbarts 8:676646c50aeb 591 double m2_error = Theta2 - m2_Position;
sjoerdbarts 8:676646c50aeb 592 //scope.set(2,m1_error);
sjoerdbarts 8:676646c50aeb 593 //scope.set(6,m2_error);
sjoerdbarts 8:676646c50aeb 594 // calc motorvalues for controller;
sjoerdbarts 8:676646c50aeb 595 double m1_MotorValue = m1_PID(m1_error, Kp, Ki, Kd, Ts, N, m1_v1, m1_v2);
sjoerdbarts 8:676646c50aeb 596 double m2_MotorValue = m2_PID(m2_error, Kp, Ki, Kd, Ts, N, m2_v1, m2_v2);
sjoerdbarts 8:676646c50aeb 597 scope.set(4,m1_MotorValue);
sjoerdbarts 8:676646c50aeb 598 scope.set(5,m2_MotorValue);
sjoerdbarts 8:676646c50aeb 599 // Set the motorvalues
sjoerdbarts 10:4bd8ec9e79ff 600 // SetMotor(1, m1_MotorValue);
sjoerdbarts 10:4bd8ec9e79ff 601 // SetMotor(2, m2_MotorValue);
sjoerdbarts 8:676646c50aeb 602 // Set motorvalues for scope
sjoerdbarts 8:676646c50aeb 603 // Send data to HIDScope
sjoerdbarts 8:676646c50aeb 604 scope.send();
sjoerdbarts 8:676646c50aeb 605 }
sjoerdbarts 8:676646c50aeb 606
sjoerdbarts 8:676646c50aeb 607 void PotControl()
sjoerdbarts 8:676646c50aeb 608 {
sjoerdbarts 8:676646c50aeb 609 double Motor1_Value = (pot1.read() - 0.5f)/2.0f;
sjoerdbarts 8:676646c50aeb 610 double Motor2_Value = (pot2.read() - 0.5f)/2.0f;
sjoerdbarts 8:676646c50aeb 611 //pc.printf("\r\n Motor value 1: %f \r\n",Motor1_Value);
sjoerdbarts 8:676646c50aeb 612 //pc.printf("\r\n Motor value 2: %f \r\n",Motor2_Value);
sjoerdbarts 8:676646c50aeb 613 double m1_Position = m1_GetPosition();
sjoerdbarts 8:676646c50aeb 614 double m2_Position = m2_GetPosition();
sjoerdbarts 8:676646c50aeb 615 scope.set(0, Motor1_Value);
sjoerdbarts 8:676646c50aeb 616 scope.set(1, m1_Position);
sjoerdbarts 8:676646c50aeb 617 scope.set(2, Motor2_Value);
sjoerdbarts 8:676646c50aeb 618 scope.set(3, m2_Position);
sjoerdbarts 8:676646c50aeb 619 scope.send();
sjoerdbarts 8:676646c50aeb 620 // Write the motors
sjoerdbarts 8:676646c50aeb 621 SetMotor(1, Motor1_Value);
sjoerdbarts 8:676646c50aeb 622 SetMotor(2, Motor2_Value);
sjoerdbarts 8:676646c50aeb 623 }
sjoerdbarts 8:676646c50aeb 624
sjoerdbarts 8:676646c50aeb 625 void ResetEncoders()
sjoerdbarts 8:676646c50aeb 626 {
sjoerdbarts 8:676646c50aeb 627 m1_EncoderCW.reset();
sjoerdbarts 8:676646c50aeb 628 m1_EncoderCCW.reset();
sjoerdbarts 8:676646c50aeb 629 m2_EncoderCW.reset();
sjoerdbarts 8:676646c50aeb 630 m2_EncoderCCW.reset();
sjoerdbarts 8:676646c50aeb 631 }
sjoerdbarts 8:676646c50aeb 632
sjoerdbarts 8:676646c50aeb 633 void Button1Switch()
sjoerdbarts 8:676646c50aeb 634 {
sjoerdbarts 8:676646c50aeb 635 button1_value = not button1_value;
sjoerdbarts 8:676646c50aeb 636 }
sjoerdbarts 8:676646c50aeb 637
sjoerdbarts 8:676646c50aeb 638 void Button2Switch()
sjoerdbarts 8:676646c50aeb 639 {
sjoerdbarts 8:676646c50aeb 640 button2_value = not button2_value;
s1600907 1:e1267e72ade8 641 }
s1600907 0:c96cf9760185 642
sjoerdbarts 13:e8b8b035abbd 643 void PANIC()
sjoerdbarts 13:e8b8b035abbd 644 {
sjoerdbarts 13:e8b8b035abbd 645 CalculationsTicker.detach();
sjoerdbarts 13:e8b8b035abbd 646 PIDControlTicker.detach();
sjoerdbarts 13:e8b8b035abbd 647 SetMotor(1,0.0);
sjoerdbarts 13:e8b8b035abbd 648 SetMotor(2,0.0);
sjoerdbarts 13:e8b8b035abbd 649 pc.printf("\r\n PANIC BUTTON PRESSED \r\n");
sjoerdbarts 13:e8b8b035abbd 650 pc.printf("\r\n TERMINATING ALL PROCESSES \r\n");
sjoerdbarts 13:e8b8b035abbd 651 }
sjoerdbarts 13:e8b8b035abbd 652
s1600907 0:c96cf9760185 653 ////////////////////////// main loop ////////////////////////////////////////////
s1600907 0:c96cf9760185 654 int main()
sjoerdbarts 8:676646c50aeb 655 {
sjoerdbarts 8:676646c50aeb 656 // Setup
sjoerdbarts 8:676646c50aeb 657 // Set baud connection with PC
s1600907 0:c96cf9760185 658 pc.baud(SERIAL_BAUD);
sjoerdbarts 8:676646c50aeb 659 pc.printf("\r\n ***THERMONUCLEAR WARFARE COMMENCES*** \r\n");
s1600907 0:c96cf9760185 660
s1600907 0:c96cf9760185 661 /* making the biquad chain for filtering the emg
s1600907 0:c96cf9760185 662 notch and high pass */
s1600907 0:c96cf9760185 663 bqc.add( &bq1 ).add( &bq2 );
s1600907 0:c96cf9760185 664 bqc2.add( &bq4 ).add( &bq5 );
s1600907 0:c96cf9760185 665 bqc3.add( &bq7 ).add( &bq8 );
sjoerdbarts 13:e8b8b035abbd 666
sjoerdbarts 8:676646c50aeb 667 // Setup Blinking LED to blink every 0.5 sec
sjoerdbarts 8:676646c50aeb 668 led = 1;
sjoerdbarts 8:676646c50aeb 669 BlinkLedTicker.attach(BlinkLed,0.5);
sjoerdbarts 8:676646c50aeb 670
sjoerdbarts 8:676646c50aeb 671 // Setup motor PWM speeds
sjoerdbarts 8:676646c50aeb 672 motor1_pwm.period(1.0/1000);
sjoerdbarts 8:676646c50aeb 673 motor2_pwm.period(1.0/1000);
sjoerdbarts 7:bafc32b576c4 674
sjoerdbarts 8:676646c50aeb 675 // Setup Interruptin.fall
sjoerdbarts 8:676646c50aeb 676 button1.fall(Button1Switch);
sjoerdbarts 13:e8b8b035abbd 677 button2.fall(PANIC);
sjoerdbarts 13:e8b8b035abbd 678 button3.fall(Stepper_On);
sjoerdbarts 8:676646c50aeb 679 //button4.fall(xxx);
s1600907 0:c96cf9760185 680
sjoerdbarts 8:676646c50aeb 681 // Actual code starts here
sjoerdbarts 8:676646c50aeb 682 // Start positioning the arms
sjoerdbarts 8:676646c50aeb 683 pc.printf("\r\n ***************** \r\n");
sjoerdbarts 8:676646c50aeb 684 pc.printf("\r\n Press Button 1 to start positioning the arms using PotControl\r\n");
sjoerdbarts 8:676646c50aeb 685 pc.printf("\r\n Make sure both potentiometers are positioned halfway! \r\n");
sjoerdbarts 8:676646c50aeb 686 pc.printf("\r\n ***************** \r\n");
sjoerdbarts 8:676646c50aeb 687 while (button1_value == false){}
sjoerdbarts 8:676646c50aeb 688 PotControlTicker.attach(&PotControl,CONTROLLER_TS);
s1600907 0:c96cf9760185 689
sjoerdbarts 8:676646c50aeb 690 pc.printf("\r\n ***************** \r\n");
sjoerdbarts 8:676646c50aeb 691 pc.printf("\r\n When done positioning, press Button 1 to detach Potcontrol");
sjoerdbarts 8:676646c50aeb 692 pc.printf("\r\n ***************** \r\n");
sjoerdbarts 8:676646c50aeb 693 while (button1_value == true){}
sjoerdbarts 8:676646c50aeb 694
sjoerdbarts 8:676646c50aeb 695 // Detach potcontrol
sjoerdbarts 8:676646c50aeb 696 PotControlTicker.detach();
sjoerdbarts 8:676646c50aeb 697
sjoerdbarts 8:676646c50aeb 698 // Set motors to 0
sjoerdbarts 8:676646c50aeb 699 SetMotor(1,0.0);
sjoerdbarts 8:676646c50aeb 700 SetMotor(2,0.0);
sjoerdbarts 8:676646c50aeb 701 // Wait a bit to let the movement stop
sjoerdbarts 8:676646c50aeb 702 wait(0.5);
sjoerdbarts 8:676646c50aeb 703 // Reset the encoders to set the 0 position
sjoerdbarts 8:676646c50aeb 704 ResetEncoders();
sjoerdbarts 8:676646c50aeb 705
sjoerdbarts 8:676646c50aeb 706 // PID control starts
sjoerdbarts 8:676646c50aeb 707 pc.printf("\r\n ***************** \r\n");
sjoerdbarts 8:676646c50aeb 708 pc.printf("\r\n When done positioning, press button SW3 to start potmeter PID control");
sjoerdbarts 8:676646c50aeb 709 pc.printf("\r\n Make sure both potentiometers are positioned halfway!!! \r\n");
sjoerdbarts 8:676646c50aeb 710 pc.printf("\r\n ***************** \r\n");
sjoerdbarts 8:676646c50aeb 711 while (button1_value == false){}
sjoerdbarts 8:676646c50aeb 712
sjoerdbarts 8:676646c50aeb 713 // Attach sample, calc and control tickers
sjoerdbarts 8:676646c50aeb 714 CalculationsTicker.attach(&CalculationsForTheta,CALC_TS);
sjoerdbarts 12:9b0451105991 715 PIDControlTicker.attach(&Controller_motor, CONTROLLER_TS);
sjoerdbarts 8:676646c50aeb 716 while(true){}
s1600907 0:c96cf9760185 717 }