Alle subfiles samengevoegd

Dependencies:   HIDScope biquadFilter mbed MODSERIAL FastPWM QEI

Committer:
sjoerdbarts
Date:
Mon Oct 31 12:44:23 2016 +0000
Revision:
10:4bd8ec9e79ff
Parent:
9:6cee14e0e323
Child:
11:417193f23342
Added stepper motor control

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