Code for the Poolinator

Dependencies:   mbed QEI HIDScope Pulse biquadFilter MODSERIAL FastPWM

Committer:
sjoerd1999
Date:
Sat Nov 02 19:21:44 2019 +0000
Revision:
15:47d949e2de1a
Parent:
14:6a82804c88d6
more comments

Who changed what in which revision?

UserRevisionLine numberNew contents of line
sjoerd1999 4:8113394bed1b 1 /*
sjoerd1999 4:8113394bed1b 2 The Poolinator - A pool playing robot for people with DMD
sjoerd1999 4:8113394bed1b 3
sjoerd1999 4:8113394bed1b 4 GROUP 10
sjoerd1999 4:8113394bed1b 5 Sjoerd de Jong - s1949950
sjoerd1999 4:8113394bed1b 6 Joost Loohuis - s1969633
sjoerd1999 4:8113394bed1b 7 Viktor Edlund - s2430878
sjoerd1999 4:8113394bed1b 8 Giuseppina Pinky Diatmiko - s1898841
sjoerd1999 4:8113394bed1b 9 Daan v.d Veen - s2003171
sjoerd1999 4:8113394bed1b 10 */
sjoerd1999 4:8113394bed1b 11
RobertoO 0:67c50348f842 12 #include "mbed.h"
sjoerd1999 3:d319bc2b19f1 13 #include "HIDScope.h"
sjoerd1999 2:f8e0a7b5c90a 14 #include "QEI.h"
RobertoO 1:b862262a9d14 15 #include "MODSERIAL.h"
sjoerd1999 2:f8e0a7b5c90a 16 #include "BiQuad.h"
sjoerd1999 2:f8e0a7b5c90a 17 #include "FastPWM.h"
sjoerd1999 9:913a59894698 18 #include <Pulse.h>
sjoerd1999 3:d319bc2b19f1 19
sjoerd1999 8:1733338758d3 20 #define PI 3.14159265358979323846
sjoerd1999 8:1733338758d3 21
RobertoO 1:b862262a9d14 22 MODSERIAL pc(USBTX, USBRX);
RobertoO 0:67c50348f842 23
sjoerd1999 13:74f2e8d3e04e 24 bool demo = false;
sjoerd1999 14:6a82804c88d6 25 enum State {CALIBRATE, INIT_0, IDLE, INIT_1, PHASE_1, INIT_2, PHASE_2, INIT_3, PHASE_3, PHASE_1EMG};
sjoerd1999 13:74f2e8d3e04e 26 State currentState = CALIBRATE;
sjoerd1999 8:1733338758d3 27
sjoerd1999 15:47d949e2de1a 28 struct vec { // 3D vector(x,y,z) to store positions
sjoerd1999 8:1733338758d3 29 double x,y,z;
sjoerd1999 8:1733338758d3 30 };
sjoerd1999 8:1733338758d3 31
sjoerd1999 13:74f2e8d3e04e 32 vec endPos{0,55,20};
sjoerd1999 9:913a59894698 33 vec ballPos{10,50,10};
sjoerd1999 9:913a59894698 34
sjoerd1999 14:6a82804c88d6 35 // EMG CONTROLS
sjoerd1999 15:47d949e2de1a 36 DigitalIn EMG_D(D15); // LDR connected, used to indicate which arm is sending atm, (left arm/right arm)
sjoerd1999 15:47d949e2de1a 37 AnalogIn EMG_A(A5); // LDR connected, used to indicate what that arm is doing, (idle/move left/move right)
sjoerd1999 13:74f2e8d3e04e 38 void moveWithEMG()
sjoerd1999 13:74f2e8d3e04e 39 {
sjoerd1999 15:47d949e2de1a 40 int whichEMG = EMG_D.read(); // 0 or 1, left arm or right arm
sjoerd1999 14:6a82804c88d6 41 float EMGvalue = EMG_A.read();
sjoerd1999 15:47d949e2de1a 42 int EMGstate = (EMGvalue < 0.29) ? 0 : (EMGvalue < 0.7) ? 1 : 2; // 0 if the led is off, 1 if it's half brightness, 2 if it's on completely
sjoerd1999 15:47d949e2de1a 43 float delta = 0.08; // How much to move in the xz direction
sjoerd1999 14:6a82804c88d6 44 if(whichEMG == 0) {
sjoerd1999 15:47d949e2de1a 45 if(EMGstate == 1) endPos.x -= delta; // Move the end position a bit to the left
sjoerd1999 15:47d949e2de1a 46 if(EMGstate == 2) endPos.x += delta; // ... to the right
sjoerd1999 14:6a82804c88d6 47 } else {
sjoerd1999 15:47d949e2de1a 48 if(EMGstate == 1) endPos.z -= delta; // ... away
sjoerd1999 15:47d949e2de1a 49 if(EMGstate == 2) endPos.z += delta; // ... towards us
sjoerd1999 13:74f2e8d3e04e 50 }
sjoerd1999 13:74f2e8d3e04e 51 }
sjoerd1999 9:913a59894698 52
sjoerd1999 9:913a59894698 53 // JOYSTICK CONTROL //
sjoerd1999 9:913a59894698 54 AnalogIn joyX(A2), joyY(A1), slider(A0);
sjoerd1999 9:913a59894698 55 DigitalIn joyButton(PTB20);
sjoerd1999 15:47d949e2de1a 56 void moveWithJoystick() // Move the endpositon based on joystick input.
sjoerd1999 9:913a59894698 57 {
sjoerd1999 9:913a59894698 58 float delta = 0.04;
sjoerd1999 9:913a59894698 59 if(joyX.read() < 0.2) endPos.x += delta;
sjoerd1999 9:913a59894698 60 else if(joyX.read() > 0.8) endPos.x -= delta;
sjoerd1999 9:913a59894698 61 if(joyY.read() < 0.2) endPos.z += delta;
sjoerd1999 9:913a59894698 62 else if(joyY.read() > 0.8) endPos.z -= delta;
sjoerd1999 9:913a59894698 63 if(slider.read() < 0.2) endPos.y += delta;
sjoerd1999 9:913a59894698 64 else if(slider.read() > 0.9) endPos.y -= delta;
sjoerd1999 9:913a59894698 65 }
sjoerd1999 3:d319bc2b19f1 66
sjoerd1999 8:1733338758d3 67 // DC MOTORS //
sjoerd1999 9:913a59894698 68 QEI encoder1(D10,D11,NC,32), encoder2(PTC5,PTC7, NC, 32), encoder3(D12,D13,NC,32);
sjoerd1999 8:1733338758d3 69 PwmOut motor1_pwm(D5), motor3_pwm(D6);
sjoerd1999 8:1733338758d3 70 DigitalOut motor1_dir(D4), motor3_dir(D7), motor2_A(D2), motor2_B(D3);
sjoerd1999 7:bfcb74384f46 71
sjoerd1999 8:1733338758d3 72 float motor1_cur = 0, motor2_cur = 0, motor3_cur = 0;
sjoerd1999 8:1733338758d3 73 float motor1_tar = 0, motor2_tar = 0, motor3_tar = 0;
sjoerd1999 2:f8e0a7b5c90a 74
sjoerd1999 15:47d949e2de1a 75 void setMotor(int motor, float motor_spd) // Set the motor speed (between -1 and 1) of a motor (1, 2, or 3)
sjoerd1999 2:f8e0a7b5c90a 76 {
sjoerd1999 2:f8e0a7b5c90a 77 int motor_dir = (motor_spd >= 0) ? 0 : 1;
sjoerd1999 2:f8e0a7b5c90a 78 motor_spd = fabs(motor_spd);
sjoerd1999 2:f8e0a7b5c90a 79
sjoerd1999 2:f8e0a7b5c90a 80 if(motor == 1) {
sjoerd1999 9:913a59894698 81 motor1_dir.write(1 - motor_dir);
sjoerd1999 2:f8e0a7b5c90a 82 motor1_pwm.write(motor_spd);
sjoerd1999 8:1733338758d3 83 } else if(motor == 3) {
sjoerd1999 8:1733338758d3 84 motor3_dir.write(motor_dir);
sjoerd1999 8:1733338758d3 85 motor3_pwm.write(motor_spd);
sjoerd1999 2:f8e0a7b5c90a 86 } else if(motor == 2) {
sjoerd1999 15:47d949e2de1a 87 motor2_A.write((motor_dir == 0) ? 0 : int(motor_spd)); // Motor 2 has digital pins so no PWM, always fully on or fully off
sjoerd1999 8:1733338758d3 88 motor2_B.write((motor_dir == 0) ? int(motor_spd) : 0);
sjoerd1999 2:f8e0a7b5c90a 89 }
sjoerd1999 2:f8e0a7b5c90a 90 }
sjoerd1999 2:f8e0a7b5c90a 91
sjoerd1999 8:1733338758d3 92 void getMotorPositions() // Calculate current motor positions (M1:angle, M2/M3:length) based on encoder pulses
sjoerd1999 8:1733338758d3 93 {
sjoerd1999 9:913a59894698 94 motor1_cur = 244 - float(encoder1.getPulses()) / 18530.00 * 360;
sjoerd1999 9:913a59894698 95 if(motor1_cur > 360) motor1_cur -= 360;
sjoerd1999 9:913a59894698 96 if(motor1_cur < 0) motor1_cur += 360;
sjoerd1999 9:913a59894698 97 motor2_cur = float(encoder2.getPulses()) / 41920.00 + 14.3;
sjoerd1999 9:913a59894698 98 motor3_cur = float(encoder3.getPulses()) / 41920.00 + 57.8;
sjoerd1999 8:1733338758d3 99 }
sjoerd1999 8:1733338758d3 100
sjoerd1999 15:47d949e2de1a 101 void moveToTargets() // Move to the target positions. No PID. If the error(the fabs(.....)) is smaller than some threshold, then the motors are off, otherwise they are fully on for motor 2/3, and 0.08 speed for motor 1.
sjoerd1999 8:1733338758d3 102 {
sjoerd1999 14:6a82804c88d6 103 setMotor(1, (fabs(motor1_cur - motor1_tar) < 0.5) ? 0 : (motor1_cur < motor1_tar) ? 0.08 : -0.08);
sjoerd1999 14:6a82804c88d6 104 setMotor(2, (fabs(motor2_cur - motor2_tar) < 0.04) ? 0 : (motor2_cur < motor2_tar) ? 1 : -1);
sjoerd1999 14:6a82804c88d6 105 setMotor(3, (fabs(motor3_cur - motor3_tar) < 0.04) ? 0 : (motor3_cur < motor3_tar) ? 1: -1);
sjoerd1999 8:1733338758d3 106 }
sjoerd1999 8:1733338758d3 107
sjoerd1999 15:47d949e2de1a 108 // KINEMATICS // (NOT USED ANYMORE, USED THE NEXT FUNCTION, WHICH TAKES THE SERVO POSITION AS ENDPOINT)
sjoerd1999 15:47d949e2de1a 109 //void calculateKinematics(float x, float y, float z) // y is up
sjoerd1999 15:47d949e2de1a 110 //{
sjoerd1999 15:47d949e2de1a 111 // float angle1 = fmod(2*PI - atan2(z, x), 2*PI) * (360 / (2*PI));
sjoerd1999 15:47d949e2de1a 112 // float angle2 = acos(sqrt(x*x + y*y + z*z) / 100.00) + atan2(sqrt(x*x + z*z), y);
sjoerd1999 15:47d949e2de1a 113 // float angle3 = 2 * asin(sqrt(x*x + y*y + z*z) / 100.00);
sjoerd1999 15:47d949e2de1a 114 //
sjoerd1999 15:47d949e2de1a 115 // motor1_tar = angle1;
sjoerd1999 15:47d949e2de1a 116 // motor2_tar = sqrt(200 - 200 * cos(angle2)); // a^2 = b^2 + c^2 - 2bc * cos(angle) (b = c = 10cm)
sjoerd1999 15:47d949e2de1a 117 // motor3_tar = sqrt(2600 - 1000 * cos(PI - angle3)); // a^2 = b^2 + c^2 - 2bc * cos(angle) (b = 10cm, c = 50cm)
sjoerd1999 15:47d949e2de1a 118 //}
sjoerd1999 8:1733338758d3 119
sjoerd1999 15:47d949e2de1a 120 void calculateKinematicsHand(float x, float y, float z) // y is up, calculate target positions of the motors using the kinematics
sjoerd1999 9:913a59894698 121 {
sjoerd1999 15:47d949e2de1a 122 float angle1 = fmod(2*PI - atan2(z, x), 2*PI) * (360 / (2*PI)); // Make sure the angle is between 0-360 degrees
sjoerd1999 15:47d949e2de1a 123 float xz = sqrt(x*x + z*z) - 15; // Offset 15cm because servo is 15cm away from endaffector in the 2D plane
sjoerd1999 15:47d949e2de1a 124 y -= 9; // Offset y with 9 cm because the servo is 9 cm below endaffector
sjoerd1999 9:913a59894698 125 float angle2 = acos(sqrt(xz*xz + y*y) / 100.00) + atan2(xz, y);
sjoerd1999 9:913a59894698 126 float angle3 = 2 * asin(sqrt(xz*xz +y*y) / 100.00);
sjoerd1999 9:913a59894698 127
sjoerd1999 9:913a59894698 128 motor1_tar = angle1;
sjoerd1999 8:1733338758d3 129 motor2_tar = sqrt(200 - 200 * cos(angle2)); // a^2 = b^2 + c^2 - 2bc * cos(angle) (b = c = 10cm)
sjoerd1999 8:1733338758d3 130 motor3_tar = sqrt(2600 - 1000 * cos(PI - angle3)); // a^2 = b^2 + c^2 - 2bc * cos(angle) (b = 10cm, c = 50cm)
sjoerd1999 8:1733338758d3 131 }
sjoerd1999 8:1733338758d3 132
sjoerd1999 15:47d949e2de1a 133 // STEPPER MOTOR //
sjoerd1999 2:f8e0a7b5c90a 134 DigitalOut STEPPER_IN1(PTB18), STEPPER_IN2(PTB19), STEPPER_IN3(PTC1), STEPPER_IN4(PTC8);
sjoerd1999 2:f8e0a7b5c90a 135
sjoerd1999 2:f8e0a7b5c90a 136 int stepper_steps = 0;
sjoerd1999 8:1733338758d3 137 float stepper_angle = 0, stepper_target = 0;
sjoerd1999 2:f8e0a7b5c90a 138
sjoerd1999 8:1733338758d3 139 void stepper_step(int direction_) // Requires ~1.5ms wait time between each step, 4096 steps is one rotation
sjoerd1999 15:47d949e2de1a 140 { // Stepper motor has electromagnets inside, depending on which are on/off, the motor will move to a different position, this code does that.
sjoerd1999 3:d319bc2b19f1 141 STEPPER_IN1 = (stepper_steps == 5 || stepper_steps == 6 || stepper_steps == 7);
sjoerd1999 2:f8e0a7b5c90a 142 STEPPER_IN2 = (stepper_steps == 3 || stepper_steps == 4 || stepper_steps == 5);
sjoerd1999 2:f8e0a7b5c90a 143 STEPPER_IN3 = (stepper_steps == 1 || stepper_steps == 2 || stepper_steps == 3);
sjoerd1999 2:f8e0a7b5c90a 144 STEPPER_IN4 = (stepper_steps == 7 || stepper_steps == 0 || stepper_steps == 1);
sjoerd1999 2:f8e0a7b5c90a 145 stepper_steps += (direction_ == 0) ? - 1 : 1;
sjoerd1999 2:f8e0a7b5c90a 146 stepper_steps = (stepper_steps + 8) % 8;
sjoerd1999 9:913a59894698 147 stepper_angle -= ((direction_ == 0) ? -1 : 1) * (360.00 / 4096.00);
sjoerd1999 2:f8e0a7b5c90a 148 }
sjoerd1999 2:f8e0a7b5c90a 149
sjoerd1999 8:1733338758d3 150 Ticker stepper_moveToAngle;
sjoerd1999 8:1733338758d3 151 void stepper_move() // Move toward desired angle with threshold. In Ticker function because requires wait otherwise
sjoerd1999 8:1733338758d3 152 {
sjoerd1999 9:913a59894698 153 if(fabs(stepper_angle - stepper_target) > 1) stepper_step((stepper_angle < stepper_target) ? 0 : 1);
sjoerd1999 8:1733338758d3 154 }
sjoerd1999 8:1733338758d3 155
sjoerd1999 8:1733338758d3 156 // SERVO //
sjoerd1999 9:913a59894698 157 AnalogOut servo(DAC0_OUT); // Write analog value to the Arduino
sjoerd1999 13:74f2e8d3e04e 158 void setServo(float i) // Set servo to specified angle(0-180 degrees) signal measured by Arduino and decoded there.
sjoerd1999 5:33133ebe37fd 159 {
sjoerd1999 9:913a59894698 160 servo = i / 180.00;
sjoerd1999 5:33133ebe37fd 161 }
sjoerd1999 3:d319bc2b19f1 162
sjoerd1999 8:1733338758d3 163 // AIMING //
sjoerd1999 13:74f2e8d3e04e 164 float aimAngle, aimTilt = 45;
sjoerd1999 12:c3fd0712f43d 165 float cueLength = 15;
sjoerd1999 9:913a59894698 166 void aim(float angle, float tilt) // Moves both stepper and servo so the end affector points towards desired angle
sjoerd1999 8:1733338758d3 167 {
sjoerd1999 9:913a59894698 168 setServo(tilt + 90);
sjoerd1999 9:913a59894698 169
sjoerd1999 9:913a59894698 170 // SPHERICAL TO CARTESIAN:
sjoerd1999 9:913a59894698 171 float handX = ballPos.x + cueLength * sin(tilt / 180 * PI) * cos(angle / 180 * PI);
sjoerd1999 9:913a59894698 172 float handY = ballPos.y - cueLength * cos(tilt / 180 * PI);
sjoerd1999 9:913a59894698 173 float handZ = ballPos.z - cueLength * sin(tilt / 180 * PI) * sin(angle / 180 * PI);
sjoerd1999 9:913a59894698 174 endPos.x = handX;
sjoerd1999 9:913a59894698 175 endPos.y = handY;
sjoerd1999 9:913a59894698 176 endPos.z = handZ;
sjoerd1999 9:913a59894698 177
sjoerd1999 15:47d949e2de1a 178 float stepperAngle = angle - fmod(2*PI - atan2(handZ, handX), 2*PI) * (180 / PI); // Make sure it stays between 0-360 degrees
sjoerd1999 9:913a59894698 179 if(stepperAngle < 0) stepperAngle += 360;
sjoerd1999 9:913a59894698 180 stepper_target = stepperAngle;
sjoerd1999 8:1733338758d3 181 }
sjoerd1999 8:1733338758d3 182
sjoerd1999 8:1733338758d3 183 // SOLENOID //
sjoerd1999 5:33133ebe37fd 184 DigitalOut solenoidA(PTC0), solenoidB(PTC9);
sjoerd1999 8:1733338758d3 185 void setSolenoid(int dir) // 1 is out, 0 is in
sjoerd1999 3:d319bc2b19f1 186 {
sjoerd1999 15:47d949e2de1a 187 solenoidA = (dir == 0) ? 0 : 1; // IMPOSSIBLE TO CREATE SHORT CIRCUIT THIS WAY, A is always inverse of B!!
sjoerd1999 9:913a59894698 188 solenoidB = (dir == 0) ? 1 : 0;
sjoerd1999 7:bfcb74384f46 189 }
sjoerd1999 7:bfcb74384f46 190
sjoerd1999 8:1733338758d3 191 // LASER //
sjoerd1999 7:bfcb74384f46 192 DigitalOut laserPin(D8);
sjoerd1999 7:bfcb74384f46 193 void setLaser(bool on)
sjoerd1999 7:bfcb74384f46 194 {
sjoerd1999 7:bfcb74384f46 195 if(on) laserPin.write(1);
sjoerd1999 7:bfcb74384f46 196 else laserPin.write(0);
sjoerd1999 7:bfcb74384f46 197 }
sjoerd1999 7:bfcb74384f46 198
sjoerd1999 9:913a59894698 199 // CALIBRATION // a3 a4 A5
sjoerd1999 14:6a82804c88d6 200 AnalogIn switch1(A3), switch2(A4);
sjoerd1999 14:6a82804c88d6 201 DigitalIn switch3(D14);
sjoerd1999 8:1733338758d3 202 void calibrate() // Calibrates all 3 motors simultaniously
sjoerd1999 7:bfcb74384f46 203 {
sjoerd1999 14:6a82804c88d6 204 setMotor(1,0.1); // Set all motors to move towards the switches
sjoerd1999 7:bfcb74384f46 205 setMotor(2,1);
sjoerd1999 7:bfcb74384f46 206 setMotor(3,1);
sjoerd1999 7:bfcb74384f46 207
sjoerd1999 9:913a59894698 208 while(!(switch1.read() < 0.5 && switch2.read() > 0.5 && switch3.read() > 0.5)) { // When all switches have been pushed in, stop
sjoerd1999 15:47d949e2de1a 209 if(switch1.read() < 0.5) setMotor(1,0); // When one of the switches has been pushed in, stop that motor
sjoerd1999 7:bfcb74384f46 210 if(switch2.read() > 0.5) setMotor(2,0);
sjoerd1999 7:bfcb74384f46 211 if(switch3.read() > 0.5) setMotor(3,0);
sjoerd1999 9:913a59894698 212 wait_ms(30);
sjoerd1999 7:bfcb74384f46 213 }
sjoerd1999 8:1733338758d3 214 for(int i = 1; i <= 3; i++) setMotor(i,0); // Make sure they've all stopped
sjoerd1999 8:1733338758d3 215
sjoerd1999 8:1733338758d3 216 encoder1.reset(); // Reset encoder positions
sjoerd1999 7:bfcb74384f46 217 encoder2.reset();
sjoerd1999 7:bfcb74384f46 218 encoder3.reset();
sjoerd1999 3:d319bc2b19f1 219 }
sjoerd1999 3:d319bc2b19f1 220
sjoerd1999 3:d319bc2b19f1 221
RobertoO 0:67c50348f842 222 int main()
RobertoO 0:67c50348f842 223 {
RobertoO 0:67c50348f842 224 pc.baud(115200);
RobertoO 1:b862262a9d14 225 pc.printf("\r\nStarting...\r\n\r\n");
sjoerd1999 12:c3fd0712f43d 226 motor1_pwm.period(0.020);
sjoerd1999 12:c3fd0712f43d 227 motor3_pwm.period(0.020);
sjoerd1999 9:913a59894698 228 stepper_moveToAngle.attach(&stepper_move, 0.0015);
sjoerd1999 14:6a82804c88d6 229
RobertoO 0:67c50348f842 230 while (true) {
sjoerd1999 9:913a59894698 231 switch(currentState) {
sjoerd1999 13:74f2e8d3e04e 232 case CALIBRATE: // Calibrate the hand
sjoerd1999 13:74f2e8d3e04e 233 setSolenoid(0);
sjoerd1999 9:913a59894698 234 calibrate();
sjoerd1999 9:913a59894698 235 setServo(90);
sjoerd1999 15:47d949e2de1a 236 currentState = INIT_0; // Go to next state after calibration
sjoerd1999 13:74f2e8d3e04e 237 break;
sjoerd1999 15:47d949e2de1a 238 case INIT_0: // Go to idle position (x=0, y=55, z=20);
sjoerd1999 13:74f2e8d3e04e 239 calculateKinematicsHand(endPos.x, endPos.y, endPos.z); // Calculate target positions
sjoerd1999 13:74f2e8d3e04e 240 getMotorPositions(); // Calculate current positions
sjoerd1999 13:74f2e8d3e04e 241 moveToTargets(); // Set the motors speeds accordingly
sjoerd1999 13:74f2e8d3e04e 242 wait_ms(40);
sjoerd1999 15:47d949e2de1a 243 if(fabs(motor1_cur - motor1_tar) < 0.6 && fabs(motor2_cur - motor2_tar) < 0.05 && fabs(motor3_cur - motor3_tar) < 0.05) currentState = IDLE; // if idle position reached, go to next state
sjoerd1999 13:74f2e8d3e04e 244 break;
sjoerd1999 15:47d949e2de1a 245 case IDLE: // Wait for button press, stop all motors
sjoerd1999 14:6a82804c88d6 246 setMotor(1,0);
sjoerd1999 14:6a82804c88d6 247 setMotor(2,0);
sjoerd1999 14:6a82804c88d6 248 setMotor(3,0);
sjoerd1999 14:6a82804c88d6 249 wait_ms(40);
sjoerd1999 13:74f2e8d3e04e 250 if(joyButton.read() == 0) {
sjoerd1999 14:6a82804c88d6 251 if(demo) currentState = PHASE_1;
sjoerd1999 14:6a82804c88d6 252 else currentState = PHASE_1EMG;
sjoerd1999 13:74f2e8d3e04e 253 setLaser(1);
sjoerd1999 15:47d949e2de1a 254 wait_ms(1000); // Wait a second after the button has been pressed so the button check in the next phase doesn't trigger
sjoerd1999 13:74f2e8d3e04e 255 }
sjoerd1999 9:913a59894698 256 break;
sjoerd1999 15:47d949e2de1a 257 case PHASE_1EMG: // Move endaffector with EMG
sjoerd1999 14:6a82804c88d6 258 moveWithEMG();
sjoerd1999 14:6a82804c88d6 259 setServo(80);
sjoerd1999 14:6a82804c88d6 260 calculateKinematicsHand(endPos.x, endPos.y, endPos.z); // Calculate target positions
sjoerd1999 14:6a82804c88d6 261 getMotorPositions(); // Calculate current positions
sjoerd1999 14:6a82804c88d6 262 moveToTargets(); // Set the motors speeds accordingly
sjoerd1999 14:6a82804c88d6 263 if(joyButton.read() == 0) {
sjoerd1999 14:6a82804c88d6 264 currentState = PHASE_1;
sjoerd1999 14:6a82804c88d6 265 wait_ms(1000);
sjoerd1999 14:6a82804c88d6 266 }
sjoerd1999 14:6a82804c88d6 267 wait_ms(40);
sjoerd1999 14:6a82804c88d6 268 break;
sjoerd1999 15:47d949e2de1a 269 case PHASE_1: // MOVE endaffector with joystick
sjoerd1999 14:6a82804c88d6 270 moveWithJoystick();
sjoerd1999 14:6a82804c88d6 271 setServo(80);
sjoerd1999 9:913a59894698 272 calculateKinematicsHand(endPos.x, endPos.y, endPos.z); // Calculate target positions
sjoerd1999 9:913a59894698 273 getMotorPositions(); // Calculate current positions
sjoerd1999 9:913a59894698 274 moveToTargets(); // Set the motors speeds accordingly
sjoerd1999 9:913a59894698 275 if(joyButton.read() == 0) {
sjoerd1999 9:913a59894698 276 currentState = PHASE_2;
sjoerd1999 9:913a59894698 277 wait_ms(1000);
sjoerd1999 9:913a59894698 278 ballPos.x = endPos.x;
sjoerd1999 12:c3fd0712f43d 279 ballPos.y = 75;
sjoerd1999 9:913a59894698 280 ballPos.z = endPos.z;
sjoerd1999 12:c3fd0712f43d 281 setLaser(0);
sjoerd1999 9:913a59894698 282 }
sjoerd1999 9:913a59894698 283 wait_ms(40);
sjoerd1999 9:913a59894698 284 break;
sjoerd1999 9:913a59894698 285
sjoerd1999 15:47d949e2de1a 286 case PHASE_2: // Control angle/tilt of the cue with joystick/slider
sjoerd1999 13:74f2e8d3e04e 287 if(slider.read() > 0.9) aimTilt += 0.25;
sjoerd1999 13:74f2e8d3e04e 288 else if(slider.read() < 0.1) aimTilt -= 0.25;
sjoerd1999 13:74f2e8d3e04e 289 aimTilt = (aimTilt < 0) ? 0 : (aimTilt > 90) ? 90 : aimTilt;
sjoerd1999 9:913a59894698 290
sjoerd1999 14:6a82804c88d6 291 if(joyX.read() < 0.2) aimAngle -= 0.3;
sjoerd1999 14:6a82804c88d6 292 else if(joyX.read() > 0.8) aimAngle += 0.3;
sjoerd1999 13:74f2e8d3e04e 293 aimAngle = (aimAngle < 0) ? 360 : (aimAngle > 360) ? 0 : aimAngle;
sjoerd1999 9:913a59894698 294
sjoerd1999 9:913a59894698 295 aim(aimAngle, aimTilt);
sjoerd1999 9:913a59894698 296
sjoerd1999 9:913a59894698 297 calculateKinematicsHand(endPos.x, endPos.y, endPos.z); // Calculate target positions
sjoerd1999 9:913a59894698 298 getMotorPositions(); // Calculate current positions
sjoerd1999 9:913a59894698 299 moveToTargets(); // Set the motors speeds accordingly
sjoerd1999 9:913a59894698 300 wait_ms(40);
sjoerd1999 13:74f2e8d3e04e 301
sjoerd1999 13:74f2e8d3e04e 302 if(joyButton.read() == 0) {
sjoerd1999 13:74f2e8d3e04e 303 currentState = PHASE_3;
sjoerd1999 12:c3fd0712f43d 304 }
sjoerd1999 9:913a59894698 305 break;
sjoerd1999 15:47d949e2de1a 306 case PHASE_3: // Shoot, then reset position and go to idle
sjoerd1999 13:74f2e8d3e04e 307 setSolenoid(1);
sjoerd1999 13:74f2e8d3e04e 308 wait_ms(500);
sjoerd1999 13:74f2e8d3e04e 309 setSolenoid(0);
sjoerd1999 13:74f2e8d3e04e 310 currentState = INIT_0;
sjoerd1999 13:74f2e8d3e04e 311 endPos.x = 0;
sjoerd1999 13:74f2e8d3e04e 312 endPos.y = 55;
sjoerd1999 13:74f2e8d3e04e 313 endPos.z = 20;
sjoerd1999 13:74f2e8d3e04e 314 aimTilt = 45;
sjoerd1999 13:74f2e8d3e04e 315 aimAngle = 0;
sjoerd1999 13:74f2e8d3e04e 316 stepper_target = 0;
sjoerd1999 13:74f2e8d3e04e 317 break;
sjoerd1999 9:913a59894698 318 }
sjoerd1999 4:8113394bed1b 319 /*
sjoerd1999 4:8113394bed1b 320 SOME EXAPLE CODE
sjoerd1999 5:33133ebe37fd 321
sjoerd1999 4:8113394bed1b 322 * MOTOR
sjoerd1999 8:1733338758d3 323 setMotor(..., ...) // which motor (1,2,3), and speed (-1.0, +1.0)
sjoerd1999 5:33133ebe37fd 324
sjoerd1999 8:1733338758d3 325 * KINEMATICS (this should be done every ~30 ms)
sjoerd1999 8:1733338758d3 326 calculateKinematics(x, y, z); // Calculate target positions
sjoerd1999 8:1733338758d3 327 getMotorPositions(); // Calculate current positions
sjoerd1999 8:1733338758d3 328 moveToTargets(); // Set the motors speeds accordingly
sjoerd1999 3:d319bc2b19f1 329
sjoerd1999 4:8113394bed1b 330 * STEPPER
sjoerd1999 8:1733338758d3 331 stepper_target = ...; // angle (between 0.0 and 180.0)
sjoerd1999 4:8113394bed1b 332
sjoerd1999 4:8113394bed1b 333 * SERVO
sjoerd1999 7:bfcb74384f46 334 setServo(...) // value between 0.0 and 180.0 (= 0 and 180 degrees)
sjoerd1999 5:33133ebe37fd 335
sjoerd1999 5:33133ebe37fd 336 * SOLENOID
sjoerd1999 8:1733338758d3 337 setSolenoid(...); // position, 0(in) or 1(out)
sjoerd1999 8:1733338758d3 338
sjoerd1999 8:1733338758d3 339 * LASER
sjoerd1999 8:1733338758d3 340 setLaser(...) // 0(off) or 1(on)
sjoerd1999 5:33133ebe37fd 341
sjoerd1999 4:8113394bed1b 342 */
RobertoO 0:67c50348f842 343 }
RobertoO 0:67c50348f842 344 }