Update 18 Februari 2017, PID laucnher dan Base sudah diperbarui

Dependencies:   Motor PID Joystick_OrdoV5 mbed millis

Fork of MainProgram_BaseBaru_otomatis-reloader by KRAI 2017

Committer:
gustavaditya
Date:
Mon Feb 13 12:03:37 2017 +0000
Revision:
31:d5cbda07fd95
Parent:
30:d69cc27ac644
Child:
32:581d4a2373f0
Program Sip 13 Gebruari 2017

Who changed what in which revision?

UserRevisionLine numberNew contents of line
rahmadirizki18 5:3aa203218306 1 /****************************************************************************/
rahmadirizki18 5:3aa203218306 2 /* PROGRAM UNTUK PID CLOSED LOOP */
rahmadirizki18 5:3aa203218306 3 /* */
gustavaditya 31:d5cbda07fd95 4 /* Last Update : 13 Februari 2017 */
gustavaditya 31:d5cbda07fd95 5 /* */
rahmadirizki18 5:3aa203218306 6 /* - Digunakan encoder autonics */
rahmadirizki18 5:3aa203218306 7 /* - Konfigurasi Motor dan Encoder sbb : */
MarchioKevin 22:4632f58461e0 8 /* ______________________ */
MarchioKevin 22:4632f58461e0 9 /* / \ Rode Depan Belakang: */
MarchioKevin 22:4632f58461e0 10 /* / 2 (Belakang) \ Omniwheel */
MarchioKevin 22:4632f58461e0 11 /* | | */
MarchioKevin 22:4632f58461e0 12 /* | 3 (Encoder) 4 | Roda Kiri Kanan: */
MarchioKevin 22:4632f58461e0 13 /* | | Fixed Wheel */
MarchioKevin 22:4632f58461e0 14 /* \ 1 (Depan) / */
MarchioKevin 22:4632f58461e0 15 /* \______________________/ Putaran berlawanan arah */
MarchioKevin 22:4632f58461e0 16 /* jarum jam positif */
rahmadirizki18 5:3aa203218306 17 /* SETTINGS (WAJIB!) : */
rahmadirizki18 5:3aa203218306 18 /* 1. Settings Pin Encoder, Resolusi, dan Tipe encoding di omniPos.h */
rahmadirizki18 5:3aa203218306 19 /* 2. Deklarasi penggunaan library omniPos pada bagian deklarasi encoder */
rahmadirizki18 5:3aa203218306 20 /* */
rahmadirizki18 5:3aa203218306 21 /****************************************************************************/
rahmadirizki18 6:68293bed71ea 22 /* */
MarchioKevin 20:54dc93e7b016 23 /* Joystick */
Sufa 30:d69cc27ac644 24 /* Kanan => */
Sufa 30:d69cc27ac644 25 /* Kiri => */
rahmadirizki18 6:68293bed71ea 26 /* */
Sufa 30:d69cc27ac644 27 /* Tombol silang => Power Screw Aktif */
Sufa 30:d69cc27ac644 28 /* Tombol segitiga => Aktif motor Launcher */
Sufa 30:d69cc27ac644 29 /* Tombol lingkaran => Aktif Pneumatik Launcher */
Sufa 30:d69cc27ac644 30 /* Tombol L1 => Pivot Kiri */
Sufa 30:d69cc27ac644 31 /* Tombol R1 => Pivot Kanan */
Sufa 30:d69cc27ac644 32 /* Tombol L3 => PWM Motor Belakang Dikurangi */
Sufa 30:d69cc27ac644 33 /* Tombol R3 => PWM Motor Belakang Ditambah */
Sufa 30:d69cc27ac644 34 /* Tombol L2 => PWM Motor Depan Dikurangi */
Sufa 30:d69cc27ac644 35 /* Tombol R2 => PWM Motor Depan Ditambah */
rahmadirizki18 13:8ab42383a2ca 36 /* */
calmantara186 16:90119f03c5d1 37 /* Bismillahirahmanirrahim */
MarchioKevin 20:54dc93e7b016 38 /* Jagalah Kebersihan Kodingan */
rahmadirizki18 6:68293bed71ea 39 /****************************************************************************/
rahmadirizki18 6:68293bed71ea 40
fanny868 0:9072e932503c 41 #include "mbed.h"
fanny868 0:9072e932503c 42 #include "JoystickPS3.h"
fanny868 0:9072e932503c 43 #include "Motor.h"
rahmadirizki18 6:68293bed71ea 44 #include "Servo.h"
rahmadirizki18 5:3aa203218306 45 #include "encoderKRAI.h"
be_bryan 26:256160a1a82d 46 #include "millis.h"
rahmadirizki18 5:3aa203218306 47
calmantara186 16:90119f03c5d1 48 /***********************************************/
calmantara186 16:90119f03c5d1 49 /* Konstanta dan Variabel */
calmantara186 16:90119f03c5d1 50 /***********************************************/
calmantara186 16:90119f03c5d1 51 #define PI 3.14159265
be_bryan 26:256160a1a82d 52 #define D_ENCODER 10 // Diameter Roda Encoder
be_bryan 26:256160a1a82d 53 #define D_ROBOT 80 // Diameter Roda Robot
rahmadirizki18 17:e4229d77a5ab 54 #define PERPINDAHAN 1 // Perpindahan ke kanan dan kiri
rahmadirizki18 5:3aa203218306 55
be_bryan 26:256160a1a82d 56 // Variable Atas
gustavaditya 31:d5cbda07fd95 57 double speed, speed2, maxSpeed = 0.8, minSpeed = 0;
be_bryan 26:256160a1a82d 58 double kpA=0.6757, kdA=0.6757, kiA=0.00006757;
be_bryan 26:256160a1a82d 59 double p,i,d;
be_bryan 27:68efb1622985 60 double p2,i2,d2;
be_bryan 26:256160a1a82d 61 double last_error = 0, current_error, sum_error = 0;
be_bryan 27:68efb1622985 62 double last_error2 = 0, current_error2, sum_error2 = 0;
gustavaditya 31:d5cbda07fd95 63 float rpm, target_rpm = 8.0;
gustavaditya 31:d5cbda07fd95 64 float rpm2, target_rpm2 = 8.0;
gustavaditya 31:d5cbda07fd95 65 float pwmPowerUp = 0.5;
gustavaditya 31:d5cbda07fd95 66 float pwmPowerDown = -0.5;
Sufa 30:d69cc27ac644 67 bool henti=false, hentis=false;
be_bryan 26:256160a1a82d 68
be_bryan 26:256160a1a82d 69 // Variable Bawah
Joshua23 25:054d3048dd03 70 float Vt;
gustavaditya 31:d5cbda07fd95 71 float keliling_enc = PI*D_ENCODER;
gustavaditya 31:d5cbda07fd95 72 float keliling_robot = PI*D_ROBOT;
gustavaditya 31:d5cbda07fd95 73 float speedT = 0.2;
gustavaditya 31:d5cbda07fd95 74 float vpid = 0;
gustavaditya 31:d5cbda07fd95 75 float PIVOT = 0.4; // PWM Pivot Kanan, Pivot Kiri
gustavaditya 31:d5cbda07fd95 76 float tuneDpn = 0.365; // Tunning PWM motor Depan
gustavaditya 31:d5cbda07fd95 77 float tuneBlk = 0.46; // Tunning PWM motor belakang
gustavaditya 31:d5cbda07fd95 78
gustavaditya 31:d5cbda07fd95 79 /* Variabel Encoder Bawah */
gustavaditya 31:d5cbda07fd95 80 float errTetha, Tetha; // Variabel yang didapatkan encoder
gustavaditya 31:d5cbda07fd95 81
gustavaditya 31:d5cbda07fd95 82 /* Deklarasi Variable Millis */
gustavaditya 31:d5cbda07fd95 83 unsigned long int previousMillis = 0;
gustavaditya 31:d5cbda07fd95 84 unsigned long int currentMillis;
gustavaditya 31:d5cbda07fd95 85 unsigned long int previousMillis2 = 0;
gustavaditya 31:d5cbda07fd95 86 unsigned long int currentMillis2;
gustavaditya 31:d5cbda07fd95 87 unsigned long int previousMillis3 = 0;
MarchioKevin 22:4632f58461e0 88
gustavaditya 31:d5cbda07fd95 89 /* Variabel Stick */
gustavaditya 31:d5cbda07fd95 90 //Logic untuk masuk aktuator
gustavaditya 31:d5cbda07fd95 91 int case_joy;
gustavaditya 31:d5cbda07fd95 92 bool isLauncher = false;
gustavaditya 31:d5cbda07fd95 93 bool isReload = false;
gustavaditya 31:d5cbda07fd95 94 int flagLauncher = 1;
gustavaditya 31:d5cbda07fd95 95 bool flag_Pneu = false;
gustavaditya 31:d5cbda07fd95 96
gustavaditya 31:d5cbda07fd95 97 /*****************************************************/
gustavaditya 31:d5cbda07fd95 98 /* Definisi Prosedur, Fungsi dan Setting Pinout */
gustavaditya 31:d5cbda07fd95 99 /*****************************************************/
gustavaditya 31:d5cbda07fd95 100
gustavaditya 31:d5cbda07fd95 101 /* Fungsi dan Procedur Encoder */
gustavaditya 31:d5cbda07fd95 102 void init_speed(); //
gustavaditya 31:d5cbda07fd95 103 void aktuator(); // Pergerakan aktuator berdasarkan case joystick
gustavaditya 31:d5cbda07fd95 104 int case_joystick(); // Mendapatkan case dari joystick
gustavaditya 31:d5cbda07fd95 105 //void speedKalibrasiMotor(); // Pertambahan target RPM motor atas melalui joystick
gustavaditya 31:d5cbda07fd95 106 void setCenter(); // Prosedur reset encoder, posisi saat itu diset jadi titik (0,0)
gustavaditya 31:d5cbda07fd95 107 float getTetha(); // Fungsi mendapatkan error Tetha
gustavaditya 31:d5cbda07fd95 108
gustavaditya 31:d5cbda07fd95 109 /* Inisialisasi Pin TX-RX Joystik dan PC */
gustavaditya 31:d5cbda07fd95 110 joysticknucleo joystick(PA_0,PA_1);
gustavaditya 31:d5cbda07fd95 111 Serial pc(USBTX,USBRX);
calmantara186 16:90119f03c5d1 112
be_bryan 26:256160a1a82d 113 /* Deklarasi Encoder Base */
gustavaditya 31:d5cbda07fd95 114 encoderKRAI encoderBase(PC_4, PB_15, 2000, encoderKRAI::X2_ENCODING); //inA, inB, pin Indeks (NC = tak ada), 2xresolusi, mode pembacaan
rahmadirizki18 15:98f0d56b14f0 115
be_bryan 26:256160a1a82d 116 /* Deklarasi Encoder Launcher */
gustavaditya 31:d5cbda07fd95 117 encoderKRAI encLauncherBlk( PC_10, PC_11, 28, encoderKRAI::X2_ENCODING);
gustavaditya 31:d5cbda07fd95 118 encoderKRAI encLauncherDpn( PD_2, PC_12, 28, encoderKRAI::X2_ENCODING);
be_bryan 26:256160a1a82d 119
calmantara186 16:90119f03c5d1 120 /* Deklarasi Motor Base */
gustavaditya 31:d5cbda07fd95 121 Motor motorDpn(PB_9, PA_12, PC_5); // pwm, fwd, rev
gustavaditya 31:d5cbda07fd95 122 Motor motorBlk(PB_6, PB_1, PB_12); // pwm, fwd, rev
fanny868 0:9072e932503c 123
calmantara186 16:90119f03c5d1 124 /* Deklarasi Motor Launcher */
gustavaditya 31:d5cbda07fd95 125 Motor launcherDpn(PA_8,PC_2,PC_1); // pwm ,fwd, rev
gustavaditya 31:d5cbda07fd95 126 Motor launcherBlk(PA_10, PC_3, PC_0); // pwm, fwd, rev
gustavaditya 31:d5cbda07fd95 127 Motor powerScrew(PB_7, PA_14, PA_15); // pwm, fwd, rev
rahmadirizki18 5:3aa203218306 128
be_bryan 26:256160a1a82d 129 /* Deklarasi Penumatik Launcher */
Sufa 29:7b372b0aaa61 130 DigitalOut pneumatik(PB_3, PullUp);
be_bryan 26:256160a1a82d 131
be_bryan 27:68efb1622985 132 /*Dekalrasi Limit Switch */
gustavaditya 31:d5cbda07fd95 133 DigitalIn limitAtas(PC_9, PullUp);
gustavaditya 31:d5cbda07fd95 134 DigitalIn limitTengah(PB_10, PullUp);
gustavaditya 31:d5cbda07fd95 135 DigitalIn limitBawah(PC_8, PullUp);
rahmadirizki18 5:3aa203218306 136
fanny868 0:9072e932503c 137
MarchioKevin 22:4632f58461e0 138 /****************************************************/
MarchioKevin 22:4632f58461e0 139 /* Deklarasi Fungsi dan Procedure */
MarchioKevin 22:4632f58461e0 140 /****************************************************/
gustavaditya 31:d5cbda07fd95 141 int case_joystick()
gustavaditya 31:d5cbda07fd95 142 {
gustavaditya 31:d5cbda07fd95 143 //---------------------------------------------------//
gustavaditya 31:d5cbda07fd95 144 // Gerak Motor Base //
gustavaditya 31:d5cbda07fd95 145 // Case 1 : Pivot kanan //
gustavaditya 31:d5cbda07fd95 146 // Case 2 : Pivot Kiri //
gustavaditya 31:d5cbda07fd95 147 // Case 3 : Kanan //
gustavaditya 31:d5cbda07fd95 148 // Case 4 : Kiri //
gustavaditya 31:d5cbda07fd95 149 // Case 5 : Break //
gustavaditya 31:d5cbda07fd95 150 //---------------------------------------------------//
gustavaditya 31:d5cbda07fd95 151
gustavaditya 31:d5cbda07fd95 152 int caseJoystick;
gustavaditya 31:d5cbda07fd95 153 if (!joystick.L1 && joystick.R1) {
gustavaditya 31:d5cbda07fd95 154 // Pivot Kanan
gustavaditya 31:d5cbda07fd95 155 caseJoystick = 1;
gustavaditya 31:d5cbda07fd95 156 }
gustavaditya 31:d5cbda07fd95 157 else if (!joystick.R1 && joystick.L1) {
gustavaditya 31:d5cbda07fd95 158 // Pivot Kiri
gustavaditya 31:d5cbda07fd95 159 caseJoystick = 2;
gustavaditya 31:d5cbda07fd95 160 }
gustavaditya 31:d5cbda07fd95 161 else if ((!joystick.R1)&&(!joystick.L1)&&(!joystick.atas)&&(!joystick.bawah)&&(joystick.kanan)&&(!joystick.kiri)) {
gustavaditya 31:d5cbda07fd95 162 // Kanan
gustavaditya 31:d5cbda07fd95 163 caseJoystick = 3;
gustavaditya 31:d5cbda07fd95 164 pc.printf("kanan");
gustavaditya 31:d5cbda07fd95 165 }
gustavaditya 31:d5cbda07fd95 166 else if ((!joystick.R1)&&(!joystick.L1)&&(!joystick.atas)&&(!joystick.bawah)&&(!joystick.kanan)&&(joystick.kiri)) {
gustavaditya 31:d5cbda07fd95 167 // Kiri
gustavaditya 31:d5cbda07fd95 168 caseJoystick = 4;
gustavaditya 31:d5cbda07fd95 169 pc.printf("kiri");
gustavaditya 31:d5cbda07fd95 170 }
gustavaditya 31:d5cbda07fd95 171 else if (joystick.segitiga_click && flagLauncher){
gustavaditya 31:d5cbda07fd95 172 // Motor Launcher
gustavaditya 31:d5cbda07fd95 173 caseJoystick = 5;
gustavaditya 31:d5cbda07fd95 174 }
gustavaditya 31:d5cbda07fd95 175 else if (joystick.R2_click && (target_rpm2 < 14)){
gustavaditya 31:d5cbda07fd95 176 // Target Pulse PID ++ Motor Depan
gustavaditya 31:d5cbda07fd95 177 caseJoystick = 6;
gustavaditya 31:d5cbda07fd95 178 }
gustavaditya 31:d5cbda07fd95 179 else if (joystick.L2_click && (target_rpm2 > 1)){
gustavaditya 31:d5cbda07fd95 180 // Target Pulse PID -- Motor Depan
gustavaditya 31:d5cbda07fd95 181 caseJoystick = 7;
gustavaditya 31:d5cbda07fd95 182 }
gustavaditya 31:d5cbda07fd95 183 else if (joystick.R3_click && (target_rpm < 14)){
gustavaditya 31:d5cbda07fd95 184 // Target Pulse PID ++ Motor Belakang
gustavaditya 31:d5cbda07fd95 185 caseJoystick = 8;
gustavaditya 31:d5cbda07fd95 186 }
gustavaditya 31:d5cbda07fd95 187 else if (joystick.L3_click && (target_rpm > 1)){
gustavaditya 31:d5cbda07fd95 188 // Target Pulse PID -- Motor Belakang
gustavaditya 31:d5cbda07fd95 189 caseJoystick = 9;
gustavaditya 31:d5cbda07fd95 190 }
gustavaditya 31:d5cbda07fd95 191 else if (joystick.silang_click){
gustavaditya 31:d5cbda07fd95 192 // Pnemuatik ON
gustavaditya 31:d5cbda07fd95 193 caseJoystick = 10;
gustavaditya 31:d5cbda07fd95 194 }
gustavaditya 31:d5cbda07fd95 195 else if ((joystick.atas)&&(!joystick.bawah)) {
gustavaditya 31:d5cbda07fd95 196 // Power Screw Up
gustavaditya 31:d5cbda07fd95 197 caseJoystick = 11;
gustavaditya 31:d5cbda07fd95 198 }
gustavaditya 31:d5cbda07fd95 199 else if ((!joystick.atas)&&(joystick.bawah)) {
gustavaditya 31:d5cbda07fd95 200 // Power Screw Down
gustavaditya 31:d5cbda07fd95 201 caseJoystick = 12;
gustavaditya 31:d5cbda07fd95 202 }
gustavaditya 31:d5cbda07fd95 203 else if ((!joystick.R1)&&(!joystick.L1)&&(!joystick.atas)&&(!joystick.bawah)&&(!joystick.kanan)&&(!joystick.kiri)) {
gustavaditya 31:d5cbda07fd95 204 // Break
gustavaditya 31:d5cbda07fd95 205 caseJoystick = 13;
gustavaditya 31:d5cbda07fd95 206 }
gustavaditya 31:d5cbda07fd95 207
gustavaditya 31:d5cbda07fd95 208 return(caseJoystick);
gustavaditya 31:d5cbda07fd95 209 }
gustavaditya 31:d5cbda07fd95 210
gustavaditya 31:d5cbda07fd95 211 float getTetha(){
gustavaditya 31:d5cbda07fd95 212 // Fungsi untuk mendapatkan nilai tetha
gustavaditya 31:d5cbda07fd95 213 float busur, tetha;
gustavaditya 31:d5cbda07fd95 214 busur = ((encoderBase.getPulses())/(float)(2000.0)*keliling_enc);
gustavaditya 31:d5cbda07fd95 215 tetha = busur/keliling_robot*360;
gustavaditya 31:d5cbda07fd95 216
gustavaditya 31:d5cbda07fd95 217 return -(tetha);
gustavaditya 31:d5cbda07fd95 218 }
gustavaditya 31:d5cbda07fd95 219
be_bryan 26:256160a1a82d 220 float pidBase(float Kp, float Ki, float Kd)
Joshua23 25:054d3048dd03 221 {
Joshua23 25:054d3048dd03 222 int errorP;
Joshua23 25:054d3048dd03 223 errorP = getTetha();
Joshua23 25:054d3048dd03 224 return (float)Kp*errorP;
Joshua23 25:054d3048dd03 225 }
Joshua23 25:054d3048dd03 226
gustavaditya 31:d5cbda07fd95 227 void init_speed (){
gustavaditya 31:d5cbda07fd95 228 if (speed>maxSpeed){
gustavaditya 31:d5cbda07fd95 229 speed = maxSpeed;
gustavaditya 31:d5cbda07fd95 230 }
gustavaditya 31:d5cbda07fd95 231 if (speed<minSpeed){
gustavaditya 31:d5cbda07fd95 232 speed = minSpeed;
calmantara186 16:90119f03c5d1 233 }
gustavaditya 31:d5cbda07fd95 234 if (speed2>maxSpeed){
gustavaditya 31:d5cbda07fd95 235 speed2 = maxSpeed;
gustavaditya 31:d5cbda07fd95 236 }
gustavaditya 31:d5cbda07fd95 237 if (speed2<minSpeed){
gustavaditya 31:d5cbda07fd95 238 speed2 = minSpeed;
gustavaditya 31:d5cbda07fd95 239 }
gustavaditya 31:d5cbda07fd95 240 }
gustavaditya 31:d5cbda07fd95 241
gustavaditya 31:d5cbda07fd95 242 void setCenter(){
gustavaditya 31:d5cbda07fd95 243 // Fungsi untuk menentukan center dari robot
gustavaditya 31:d5cbda07fd95 244 encoderBase.reset();
fanny868 0:9072e932503c 245 }
fanny868 0:9072e932503c 246
gustavaditya 31:d5cbda07fd95 247 void aktuator()
gustavaditya 31:d5cbda07fd95 248 {
gustavaditya 31:d5cbda07fd95 249 switch (case_joy) {
gustavaditya 31:d5cbda07fd95 250 case (1):
gustavaditya 31:d5cbda07fd95 251 {
gustavaditya 31:d5cbda07fd95 252 // Pivot Kanan
gustavaditya 31:d5cbda07fd95 253 motorDpn.speed(-PIVOT);
gustavaditya 31:d5cbda07fd95 254 motorBlk.speed(-PIVOT);
gustavaditya 31:d5cbda07fd95 255 setCenter();
gustavaditya 31:d5cbda07fd95 256 break;
gustavaditya 31:d5cbda07fd95 257 }
gustavaditya 31:d5cbda07fd95 258 case (2):
gustavaditya 31:d5cbda07fd95 259 {
gustavaditya 31:d5cbda07fd95 260 // Pivot Kiri
gustavaditya 31:d5cbda07fd95 261 motorDpn.speed(PIVOT);
gustavaditya 31:d5cbda07fd95 262 motorBlk.speed(PIVOT);
gustavaditya 31:d5cbda07fd95 263 setCenter();
gustavaditya 31:d5cbda07fd95 264 break;
gustavaditya 31:d5cbda07fd95 265 }
gustavaditya 31:d5cbda07fd95 266 case (3) :
gustavaditya 31:d5cbda07fd95 267 {
gustavaditya 31:d5cbda07fd95 268 // Kanan
gustavaditya 31:d5cbda07fd95 269 motorDpn.speed(-(tuneDpn) + pidBase(0.09,0,0));
gustavaditya 31:d5cbda07fd95 270 motorBlk.speed((tuneBlk) + pidBase(0.09,0,0));
gustavaditya 31:d5cbda07fd95 271 break;
gustavaditya 31:d5cbda07fd95 272 }
gustavaditya 31:d5cbda07fd95 273 case (4) :
gustavaditya 31:d5cbda07fd95 274 {
gustavaditya 31:d5cbda07fd95 275 // Kiri
gustavaditya 31:d5cbda07fd95 276 motorDpn.speed(tuneDpn + pidBase(0.09,0,0));
gustavaditya 31:d5cbda07fd95 277 motorBlk.speed(-tuneBlk + pidBase(0.09,0,0));
gustavaditya 31:d5cbda07fd95 278 break;
gustavaditya 31:d5cbda07fd95 279 }
gustavaditya 31:d5cbda07fd95 280 case (5) :
gustavaditya 31:d5cbda07fd95 281 {
gustavaditya 31:d5cbda07fd95 282 // Aktifkan motor atas
gustavaditya 31:d5cbda07fd95 283 isLauncher = !isLauncher;
gustavaditya 31:d5cbda07fd95 284 break;
Joshua23 8:0711dea61312 285 }
gustavaditya 31:d5cbda07fd95 286 case (6) :
gustavaditya 31:d5cbda07fd95 287 {
gustavaditya 31:d5cbda07fd95 288 // Target Pulse PID ++ Motor Depan
gustavaditya 31:d5cbda07fd95 289 target_rpm2 = target_rpm2++;
gustavaditya 31:d5cbda07fd95 290 break;
gustavaditya 31:d5cbda07fd95 291 }
gustavaditya 31:d5cbda07fd95 292 case (7) :
gustavaditya 31:d5cbda07fd95 293 {
gustavaditya 31:d5cbda07fd95 294 // Target Pulse PID -- Motor Depan
gustavaditya 31:d5cbda07fd95 295 target_rpm2 = target_rpm2--;
gustavaditya 31:d5cbda07fd95 296 break;
gustavaditya 31:d5cbda07fd95 297 }
gustavaditya 31:d5cbda07fd95 298 case (8) :
gustavaditya 31:d5cbda07fd95 299 {
gustavaditya 31:d5cbda07fd95 300 // Target Pulse PID ++ Motor Belakang
gustavaditya 31:d5cbda07fd95 301 target_rpm = target_rpm++;
gustavaditya 31:d5cbda07fd95 302 break;
gustavaditya 31:d5cbda07fd95 303 }
gustavaditya 31:d5cbda07fd95 304 case (9) :
be_bryan 27:68efb1622985 305 {
gustavaditya 31:d5cbda07fd95 306 // Target Pulse PID -- Motor Belakang
gustavaditya 31:d5cbda07fd95 307 target_rpm = target_rpm--;
gustavaditya 31:d5cbda07fd95 308 break;
gustavaditya 31:d5cbda07fd95 309 }
gustavaditya 31:d5cbda07fd95 310 case (10) :
gustavaditya 31:d5cbda07fd95 311 {
gustavaditya 31:d5cbda07fd95 312 // Pneumatik
gustavaditya 31:d5cbda07fd95 313 pneumatik = 0;
gustavaditya 31:d5cbda07fd95 314 previousMillis3 = millis();
gustavaditya 31:d5cbda07fd95 315 flag_Pneu = true;
gustavaditya 31:d5cbda07fd95 316 break;
gustavaditya 31:d5cbda07fd95 317 }
gustavaditya 31:d5cbda07fd95 318 case (11) :
gustavaditya 31:d5cbda07fd95 319 {
gustavaditya 31:d5cbda07fd95 320 // Power Screw Up
gustavaditya 31:d5cbda07fd95 321 powerScrew.speed(pwmPowerUp);
gustavaditya 31:d5cbda07fd95 322 break;
gustavaditya 31:d5cbda07fd95 323 }
gustavaditya 31:d5cbda07fd95 324 case (12) :
gustavaditya 31:d5cbda07fd95 325 {
gustavaditya 31:d5cbda07fd95 326 // Power Screw Down
gustavaditya 31:d5cbda07fd95 327 powerScrew.speed(pwmPowerDown);
gustavaditya 31:d5cbda07fd95 328 break;
gustavaditya 31:d5cbda07fd95 329 }
gustavaditya 31:d5cbda07fd95 330 default :
gustavaditya 31:d5cbda07fd95 331 {
gustavaditya 31:d5cbda07fd95 332 motorDpn.brake(1);
gustavaditya 31:d5cbda07fd95 333 motorBlk.brake(1);
gustavaditya 31:d5cbda07fd95 334 if (!limitAtas)
be_bryan 27:68efb1622985 335 {
gustavaditya 31:d5cbda07fd95 336 powerScrew.brake(1);
gustavaditya 31:d5cbda07fd95 337 }
gustavaditya 31:d5cbda07fd95 338 if (!limitTengah)
gustavaditya 31:d5cbda07fd95 339 {
gustavaditya 31:d5cbda07fd95 340 case_joy = 12;
gustavaditya 31:d5cbda07fd95 341 aktuator();
gustavaditya 31:d5cbda07fd95 342 }
gustavaditya 31:d5cbda07fd95 343 if (!limitBawah)
Sufa 30:d69cc27ac644 344 {
gustavaditya 31:d5cbda07fd95 345 case_joy = 11;
gustavaditya 31:d5cbda07fd95 346 aktuator();
be_bryan 27:68efb1622985 347 }
gustavaditya 31:d5cbda07fd95 348 }
gustavaditya 31:d5cbda07fd95 349 } // End Switch
gustavaditya 31:d5cbda07fd95 350 }
gustavaditya 31:d5cbda07fd95 351
gustavaditya 31:d5cbda07fd95 352 void launcher()
gustavaditya 31:d5cbda07fd95 353 {
gustavaditya 31:d5cbda07fd95 354 if (isLauncher)
Sufa 30:d69cc27ac644 355 {
be_bryan 26:256160a1a82d 356 startMillis();
be_bryan 28:2d0746dc2d7d 357 currentMillis = millis();
be_bryan 28:2d0746dc2d7d 358 currentMillis2 = millis();
be_bryan 28:2d0746dc2d7d 359
gustavaditya 31:d5cbda07fd95 360 // PID Launcher Depan
be_bryan 26:256160a1a82d 361 if (currentMillis-previousMillis>=10)
be_bryan 26:256160a1a82d 362 {
gustavaditya 31:d5cbda07fd95 363 rpm = (float)encLauncherBlk.getPulses();
be_bryan 26:256160a1a82d 364 current_error = target_rpm - rpm;
be_bryan 26:256160a1a82d 365 sum_error = sum_error + current_error;
be_bryan 26:256160a1a82d 366 p = current_error*kpA;
be_bryan 26:256160a1a82d 367 d = (current_error-last_error)*kdA/10.0;
be_bryan 26:256160a1a82d 368 i = sum_error*kiA*10.0;
be_bryan 26:256160a1a82d 369 speed = p + d + i;
be_bryan 26:256160a1a82d 370 init_speed();
gustavaditya 31:d5cbda07fd95 371 launcherBlk.speed(speed);
be_bryan 26:256160a1a82d 372 last_error = current_error;
gustavaditya 31:d5cbda07fd95 373 encLauncherBlk.reset();
be_bryan 26:256160a1a82d 374 //pc.printf("%.04lf\n",rpm);
be_bryan 26:256160a1a82d 375 previousMillis = currentMillis;
be_bryan 26:256160a1a82d 376 }
be_bryan 27:68efb1622985 377 if (currentMillis2-previousMillis2>=10)
be_bryan 27:68efb1622985 378 {
gustavaditya 31:d5cbda07fd95 379 rpm2 = (float)encLauncherDpn.getPulses();
be_bryan 27:68efb1622985 380 current_error2 = target_rpm2 - rpm2;
be_bryan 27:68efb1622985 381 sum_error2 = sum_error2 + current_error2;
be_bryan 27:68efb1622985 382 p2 = current_error2*kpA;
be_bryan 27:68efb1622985 383 d2 = (current_error2-last_error2)*kdA/10.0;
be_bryan 27:68efb1622985 384 i2 = sum_error2*kiA*10.0;
be_bryan 27:68efb1622985 385 speed2 = p2 + d2 + i2;
be_bryan 27:68efb1622985 386 init_speed();
gustavaditya 31:d5cbda07fd95 387 launcherDpn.speed(speed2);
be_bryan 27:68efb1622985 388 last_error2 = current_error2;
gustavaditya 31:d5cbda07fd95 389 encLauncherDpn.reset();
be_bryan 27:68efb1622985 390 previousMillis2 = currentMillis2;
be_bryan 27:68efb1622985 391 }
rahmadirizki18 6:68293bed71ea 392 }
Sufa 29:7b372b0aaa61 393 else
Sufa 29:7b372b0aaa61 394 {
gustavaditya 31:d5cbda07fd95 395 launcherDpn.brake(1);
gustavaditya 31:d5cbda07fd95 396 launcherBlk.brake(1);
gustavaditya 31:d5cbda07fd95 397 }
rahmadirizki18 5:3aa203218306 398 }
gustavaditya 31:d5cbda07fd95 399
MarchioKevin 22:4632f58461e0 400 /*********************************************************/
MarchioKevin 22:4632f58461e0 401 /* Main Function */
MarchioKevin 22:4632f58461e0 402 /*********************************************************/
calmantara186 16:90119f03c5d1 403
gustavaditya 31:d5cbda07fd95 404 int main (void)
gustavaditya 31:d5cbda07fd95 405 {
gustavaditya 31:d5cbda07fd95 406 // Set baud rate - 115200
fanny868 0:9072e932503c 407 joystick.setup();
rahmadirizki18 23:023b522977b2 408 pc.baud(115200);
rahmadirizki18 6:68293bed71ea 409 wait_ms(1000);
rahmadirizki18 5:3aa203218306 410 setCenter();
rahmadirizki18 5:3aa203218306 411 wait_ms(500);
rahmadirizki18 23:023b522977b2 412 pc.printf("ready....");
fanny868 0:9072e932503c 413 while(1)
fanny868 0:9072e932503c 414 {
fanny868 0:9072e932503c 415 // Interrupt Serial
calmantara186 16:90119f03c5d1 416 joystick.idle();
gustavaditya 31:d5cbda07fd95 417 if(joystick.readable())
gustavaditya 31:d5cbda07fd95 418 {
fanny868 0:9072e932503c 419 // Panggil fungsi pembacaan joystik
fanny868 0:9072e932503c 420 joystick.baca_data();
fanny868 0:9072e932503c 421 // Panggil fungsi pengolahan data joystik
fanny868 0:9072e932503c 422 joystick.olah_data();
gustavaditya 31:d5cbda07fd95 423 // Masuk ke case joystick
gustavaditya 31:d5cbda07fd95 424 case_joy = case_joystick();
rahmadirizki18 3:1287fccc11be 425 aktuator();
gustavaditya 31:d5cbda07fd95 426 launcher();
gustavaditya 31:d5cbda07fd95 427 if ((millis()-previousMillis3 >= 700)&&(flag_Pneu)){
be_bryan 26:256160a1a82d 428 pneumatik = 1;
gustavaditya 31:d5cbda07fd95 429 flag_Pneu = false;
be_bryan 26:256160a1a82d 430 }
be_bryan 26:256160a1a82d 431 }
gustavaditya 31:d5cbda07fd95 432 else
gustavaditya 31:d5cbda07fd95 433 {
gustavaditya 31:d5cbda07fd95 434 joystick.idle();
MarchioKevin 21:da2f3d04468f 435 }
fanny868 0:9072e932503c 436 }
be_bryan 28:2d0746dc2d7d 437 }