I. Tujuan
a. Mahasiswa dapat membangkitkan sinyal PWM dengan menggunakan fasilitas timer pada
mikrokontroler baik secara hardware
b. Mahasiswa dapat menggunakan timer pada mikrokontroler untuk men-sampling data rotary
encoder untuk membaca data kecepatan
c. Mahasiswa dapat menggunakan timer pada mikrokontroler untuk men-sampling
memmanggil fungsi kontrol
d. Mahasiswa dapat membuat program pengaturan kecepatan motor DC brushed dengan
metode PID
II. Pendahuluan
Motor DC brushed adalah salah satu jenis motor listrik yang memerlukan supply tegangan arus
searah pada kumparan rotor untuk diubah menjadi energi gerak mekanik. Motor DC yang digunakan
pada praktikum ini adalah jenis PMDC, yang menggunakan magnet permanen untuk membangkitkan
medan magnet pada bagian stator dari motor. Kontroler PID (Proportional–Integral–Derivative
controller) merupakan kontroler umpan balik yang banyakdigunakan pada sistem kontrol industri.
dengan nilai KP, KI, dan KD yang semuanya positif, yang merupakan koefisien (gain) untuk term
proporsional, integral, dan derivatif, secara berurutan (atau P, I, dan D). Pada model ini:
Kendali P bertanggung jawab terhadap nilai error aktual,. Contohnya, jika nilai kesalahan
besar dan positif, maka keluaran kontrol juga besar dan positif.
Kendali I bertanggung jawab terhadap nilai error sebelumnya (total error yang sudah
terjadi). Contoh, jika keluaran saat ini kurang besar, maka kesalahan akan terakumulasi terus
menerus, dan kontroler akan merespon dengan keluaran lebih tinggi.
Kendali D bertanggung jawab untuk kemungkinan nilai error yang akan datang, berdasarkan
pada rate perubahan error (laju error) terhadap waktu.
Driver
Setpoint PID Control Motor Output
Motor
Perhitungan Rotari
kecepatan Enkoder
Sampling
Modul kontroler yang digunakan pada percobaan ini menggunakan ADROIT-AVR, yaitu rangkaian
pengendali utama dari robot AdRoiT. Rangkaian ini akan mengendalikan gerakan robot melalui
modul aktuator yang ada. ADROIT-AVR dilengkapi dengan rangkaian regulator, 2 buah driver motor
DC dan beberapa sensor onboard. Selain itu bisa juga dihubungkan dengan sensor maupun aktuator
tambahan yang bisa dihubungkan melalui jalur komunikasi UART dan I2C.
3
5
4 6
7 10 11
9
13
Gambar 4. Modul Rangkaian AdRoiT AVR (tampak bawah)
Keterangan:
1. Konektor Motor DC 1 (motor penggerak kanan)
2. Konektor Motor DC 2 (motor penggerak kiri)
3. Driver motor DC (motor 1 dan 2)
4. Mikrokontroler ATMega128
5. Konektor UART Depan (UART 1)
6. Konektor I2C
7. MPU6050 (Accelerometer 3 axis + Gyroscope 3 axis )
8. HMC5883L (Magnetometer 3 axis)
9. Konektor UART Belakang (UART 1)
10. Regulator 3,3V
11. Tombol reset
12. Buzzer
13. Sekering
B. Skematik Rangkaian
a. Rangkaian LED
Modul ADROIT-AVR dilengkapi dengan empat buah LED untuk keperluan umum. LED tersebut
terhungung pada PORTC bit-4 sampai dengan bit-7. Sifat dari LED adalah active high, sehingga LED
akan menyala saat diberi logika 1. Bit-bit pada port ini harus difungsikan sebagai output.
Modul ADROIT-AVR dilengkapi dengan empat buah push button untuk keperluan umum. Push
button tersebut terhungung pada PORTC bit-0 sampai dengan bit-3. Sifat dari push button adalah
active low, sehingga push button akan menghasilkan logika 0 saat ditekan. Supaya logika ketika push
button tidak ditekan bisa menghasilkan logika 1, maka internal pull-up dari PORTC pada bit-0 sampai
dengan bit-3 harus diaktifkan. Selain itu bit-bit pada port tersebut harus diinisialisasi sebagai input.
c. Rangkaian Dipswitch
Modul ADROIT-AVR dilengkapi dengan empat bitdip-switch untuk keperluan umum. Dip-switch
tersebut terhungung pada PORTG bit-0, 1, 2 dan 4. Sifat dari dip-switch adalah active low, sehingga
ketika aktif (terhubung) akan menghasilkan logika 0. Supaya logika ketika tidak aktif bisa
menghasilkan logika 1, maka internal pull-up dari PORTG pada bit-0, 1,2, dan 4 harus diaktifkan.
Selain itu bit-bit pada port tersebut harus diinisialisasi sebagai input.
d. Rangkaian LCD
e. Rangkaian ADC
Modul ADROIT-AVR dilengkapi dengan 8 kanal ADC. Akan tetapi jumlah kanal ADC yang bisa
dihubungkan ke rangkaian luar hanya ada 7 kanal, karena salah satu kanal digunakan untuk
monitoring tegangan supply. Masing-masing bit bisa tetap dikonfigurasikan sebagai input untuk
interface dengan ADC.
Modul ADROIT-AVR dilengkapi dengan 8 kanal PWM generator, 3 diantaranya bisa dibangkitkan
dengan hardware PWM generator menggunakan timer 1 dengan resolusi 16 bit. Sedangkan 5 kanal
sisanya bisa dikendalikan dengan emulasi PWM dengan menggunakan interupsi timer. Bit-bit pada
masing-masing kanal harus dikonfigurasikan sebagai output supaya bisa menggunakannya untuk
melakukan interface ke motor Servo.
g. Rangkaian Buzzer
Modul ADROIT-AVR dilengkapi dengan dua buah driver motor yang dilengkapi juga dengan fasilitas
antarmuka untuk rotary encoder. Masing-masing enkoder bisa digunakan untuk melakukan
antarmuka dengan mode bidirectional encoder. Pengaturan kecepatan dari motor DC dilakukan
melalui timer 0, sedangkan rotary encoder dibaca dengan memanfaatkan ekternal interrupt 6 dan 7.
PORTE bit 2, 3, 4 dan 5 dikonfigurasikan sebagai output untuk men-drive motor. Sedangkan PORTB
0, 1 dan PORT E 6, 7 dikonfigurasikan sebagai input dengan pull-up aktif untuk keperluan interface
dengan rotary encoder.
Gambar 5. Motor DC Brushed yang dilengkapi dengan gearbox dan rotary enkoder
Modul ADROIT-AVR dilengkapi sebuah sensor IMU yang mengasilkan pembacaan data 3 axis
Gyroscope dan 3 axis Accelerometer. Sensor ini terhubung dengan mikrokontroler menggunakan
antarmuka I2C.
Modul ADROIT-AVR dilengkapi sebuah sensor magnetic compas yang bisa membaca medan
magnet sekitar dalam arah 3 axis. Sensor ini terhubung dengan mikrokontroler menggunakan
antarmuka I2C melalui IC IMU MPU6050.
Pilih OK
Pilih Yes
Pilih AT90… OK
Masuk ke Ports Port A, Set semua bit di Port A sebagai output (untuk interface ke LCD
text)
Pilih Ports Port F, tidak perlu dikonfigurasi karena digunakan untuk input ADC
(defaultnya sebagai input floating)
6. Lakukan setting untuk Buzzer dengan masuk pada tab Timers Timer 0
7. Lakukan setting untuk Motor Servo 7, 6, 8 dengan masuk pada tab Timers Timer 1
Timer satu juga digunakan untuk membangkitkan interupsi dengan periode 5ms untuk
mencacah pembangkitan pulsa PWM untuk motor servo yang mempunyai periode 20ms.
Selain itu interupsi juga digunakan untuk pewaktuan update perhitungan sinyal IMU
(digunakan pada praktikum selanjutnya)
Interupsi diaktifkan pada 2 kondisi, yaitu:
Timer1 Overflow Interrupt
Input Capture Interrupt
Mode CTC dengan Top dari nilai OCR2, dimana Frek. Interrup yang dihasilkan dapat dihitung
dengan Fint = Fclk/(Top+1) , dimana periode interupsinya adalah T int = 1/Fint
OCR2+1 = 250KHz/10000 = 250, maka OCR2=250-1=249d = F9h
9. Lakukan setting untuk PWM pada motor dengan masuk pada tab Timers Timer 3
Timer 3 menggunakan 2 buah kanal PWM dengan sifat inverted, karena driver motor nilai
PWMnya active low dengan frekwensi 20KHz. Selain itu timer ini juga digunakan untuk
membangkitkan frekwensi interupsi sebesar 40KHz untuk keperluan mengemulasi sinyal
10. Selanjutnya aktifkan mode external interrupt untuk interface pada rotary encoder yang
terhubung ke Ext IRQ 6 dan 7
12. Masuk ke seting ADC (optional, bisa di-skip Karena tidak dibutuhkan dalam percobaan ini)
Simpan file ke lokasi yang Anda pilih di computer, misal dengan nama MotorDC.
Ada 3 jenis file yang akan dihasilkan, yaitu:
a. File C Compiler (*.c)
b. File Project (*.prj)
c. File CodewizzardAVR Project (*.cwp)
Ketiganya bisa diberi nama yang sama untuk memudahkan kita dalam mengingat file-file
tersebut.
#define ON 1
#define OFF 0
2. Selanjutnya simpan file dengan dama Definisi.h melalui menu File Save As
3. Untuk bisa mengakses LCD, diperlukan proses inisialisasi dan beberapa fungsi yang lain.
Untuk itu fungsi-fungsi yang digunakan untuk mengakses LCD text sebaiknya diletakkan pada
file yang terpisah juga. Seperti langkah sebelumnya bisa ditambahkan file header yang
menyimpan fungsi-fungsi LCD dengan membuat file source baru melalui menu File New ,
pilih Source, dan OK
// Fungsi LCD
#include <delay.h>
#define DelayLCD 50 // nilai delay untuk penulisan atau penghapusan LCD
#pragma used+
// sub fungsi pengiriman command ke LCD
void LCD_Init_Cmd(unsigned char xData)
{ LCD_PORT = 0B00000100 | (xData & 0xF0);
delay_us(1); LCD_EN(0);
}
// fungi untuk menulis text yang disimpan ke ROM ke LCD baris ke(0=baris 1, 1=Baris 2)
void LCD_TulisF(unsigned char Baris, unsigned char flash *text)
{ LCD_GotoXY(0,Baris);LCD_TextF(text);
}
// fungsi untuk menghapus LCD pada baris ke (0=baris 1, 1=Baris 2) secara langsung
void LCD_HapusBaris(unsigned char Baris) // menghapus baris tanpa delay
{ unsigned char i;
LCD_GotoXY(0,Baris);
for(i=0;i<16;i++) LCD_Data(' ');
}
// fungsi untuk menghapus LCD pada baris ke (0=baris 1, 1=Baris 2) dari kiri layar
void LCD_HapusKiri(unsigned char Baris)
{ unsigned char i;
LCD_GotoXY(0,Baris);
for(i=0;i<16;i++) { LCD_Data(' '); delay_ms(DelayLCD);}
}
// fungsi untuk menghapus LCD pada baris ke (0=baris 1, 1=Baris 2) dari kanan layar
void LCD_HapusKanan(unsigned char Baris)
{ int8_t i,j;
j = 0x80 + 0x40*Baris;
for(i=15;i>-1;i--)
{ LCD_Perintah (j+i); LCD_Data(' '); delay_ms(DelayLCD);}
}
// menuliskan string (16 karakter)dari arah kiri dgn delay pada (0=baris 1, 1=Baris 2)
void LCD_TulisKiri(unsigned char Baris, unsigned char flash *text)
{ unsigned char i;
LCD_GotoXY(0,Baris);
for(i=0;i<16;i++)
{ LCD_Data(*(text+i)); delay_ms(DelayLCD);}
}
4. Selanjutnya simpan file tersebut dengan dama LCD.h melalui menu File Save As
5. Masukkan include #include "Definisi.h" dan #include "LCD.h" dibawah #include
<mega128.h>
6. Deklarasikan Variabel global dibawah file include di atas
#define SetGlobalInterrupt #asm("sei")
#define ClrGlobalInterrupt #asm("cli")
7. Tambahkan program berikut pada fungsi interupsi eksternal (dibawah deklarasi variable
global pada bagian yang sudah tersedia). Program ini adalah untuk membaca data rotary
encoder, baik data posisi maupun variable counter yang selanjutnya akan disampling untuk
mendapatkan data kecepatan, yaitu:
8. Kecepatan aktual dari motor didapatkan dengan cara melakukan sampling pada data sensor
rotary encoder dan dicari selisihnya dengan data sebelumnya. Semakin cepat putaran
motor, maka semakin besar pula jumlah pulsa dari encoder yang didapatkan setiap waktu
sampling.
9. Tambahkan program pada interupsi timer2 compare match (interupsi setiap 1 ms sekali).
Timer ini digunakan untuk melakukan proses perhitungan kecepatan motor dari rotary
encoder dan juga pemanggil fungsi kendali kecepatan motor dengan PID. Masing-masing
proses sebenarnya dilakukan secara bergiliran setiap 10ms sekali. Hal ini dilakukan supaya
program tidak terjebak terlalu lama pada program interupsi, sehingga dilakukan proses
pencacahan pada hitungan tertentu untuk setiap eksekusi prosesnya. Berikut kodenya:
// Timer2 output compare interrupt service routine
interrupt [TIM2_COMP] void timer2_comp_isr(void) // interupsi setiap 1 ms
{
// Place your code here
static unsigned char _dCounterKi=0, _dCounterKa=0, Timer2Tick=10;
SetGlobalInterrupt;
if(--Timer2Tick==0) Timer2Tick=10; // timer 1 ms dicacah 10 x
switch(Timer2Tick)
10. Tambahkan prototype fungsi perhitungan PID kecepatan motor kanan dan kiri yang nantinya
akan dipanggil oleh fungsi interupsi timer 2 compare match. Prototipe fungsi ini nantinya
akan kita isi dengan fungsi kendali PID untuk pengaturan kecepatan motor DC yang ada.
void HitungPIDmotorKa() // menghitung PID motor kanan (dihitung setiap 10ms sekali)
{
}
void HitungPIDmotorKi() // menghitung PID motor kiri (dihitung setiap 10ms sekali)
{
}
11. Lakukan editing program di dalam fungsi main, pada program sekitar looping while (1)
dengan kode:
// Tulis keterangan (label) pada LCD
PwmMKa(100); // 25% pengaturtan kecepatan dengan model open loop
PwmMKi(100); // 25% pengaturtan kecepatan dengan model open loop
LCD_TulisF(0,"Kecepatan.Ka:");
LCD_TulisF(1,"Kecepatan.Ki:");
while (1)
{
// Place your code here
// menampilkan data kecepatan aktual motor Kanan (pulsa/10ms)
LCD_GotoXY(13,0); LCD_Angka3(dSpeedKa); LCD_Data(' ');
// menampilkan data kecepatan aktual motor Kiri (pulsa/10ms)
LCD_GotoXY(13,1); LCD_Angka3(dSpeedKi); LCD_Data(' ');
}
12. Selanjutnya Build Project dengan menekan Ctrl+F9, atau melalui menu Project Build
void HitungPIDmotorKa() // menghitung PID motor kanan (dihitung setiap 10ms sekali)
{
signed char ErrorMKa, dErrorMKa;
signed short U;
static signed char iErrorMKa=0, lastErrorMKa=0;
// Menghitung PID Motor kanan
if(SpeedKa>0)
{ ErrorMKa = (signed char)SpeedKa-(signed char)dSpeedKa; // nilai error
iErrorMKa+=ErrorMKa; // integral error
if(iErrorMKa>40) iErrorMKa = 40; // pembatas nilai inegral error
else if(iErrorMKa<-40)iErrorMKa = -40; // +- 10% nilai aktuasi
dErrorMKa = lastErrorMKa - ErrorMKa; // nilai perubahan error
lastErrorMKa = ErrorMKa; // update nilai last Error
U = ErrorMKa * KPmKa; // Hitung kendali proporsional
U+= iErrorMKa * KImKa; // menambahkan kendali Integral
U+= dErrorMKa * KDmKa; // menambahkan kendali Differential
if (U>MaxPWM) // membatasi nilai aktuasi (maksimal PWM)
{ PwmMKa(MaxPWM);}
else if (U>0)
{ PwmMKa(U); }
else // nilai minimal PWM=0 (motor tidak dibalik arahnya)
{ PwmMKa(0); }
}
else {PwmMKa(0); iErrorMKa=0; lastErrorMKa=0;}
}
void HitungPIDmotorKi() // menghitung PID motor kiri (dihitung setiap 10ms sekali)
{
signed char ErrorMKi, dErrorMKi;
signed short U;
static signed char iErrorMKi=0, lastErrorMKi=0;
// Menghitung PID Motor kiri
if(SpeedKa>0)
{ ErrorMKi = (signed char)SpeedKi-(signed char)dSpeedKi; // nilai error
iErrorMKi+=ErrorMKi; // integral error
if(iErrorMKi>40) iErrorMKi = 40; // pembatas nilai inegral error
else if(iErrorMKi<-40)iErrorMKi = -40; // +- 10% nilai aktuasi
dErrorMKi = lastErrorMKi - ErrorMKi; // nilai perubahan error
lastErrorMKi = ErrorMKi; // update nilai last Error
U = ErrorMKi * KPmKi; // Hitung kendali proporsional
U+= iErrorMKi * KImKi; // menambahkan kendali Integral
U+= dErrorMKi * KDmKi; // menambahkan kendali Differential
if (U>MaxPWM) // membatasi nilai aktuasi (maksimal PWM)
{ PwmMKi(MaxPWM);}
else if (U>0)
{ PwmMKi(U); }
else // nilai minimal PWM=0 (motor tidak dibalik arahnya)
{ PwmMKi(0); }
}
else {PwmMKi(0); iErrorMKi=0; lastErrorMKi=0;}
}
3. Lakukan editing program di dalam fungsi main, pada program sekitar looping while (1)
dengan kode:
SpeedKa = 0; // nilai awal kecepatan motor kanan = 0
SpeedKi = 0; // nilai awal kecepatan motor kiri = 0
// inisialisasi LCD
LCD_Init();
while (1)
4. Ulangi seperti langkah 12 sampai dengan 16 dari percobaan B untuk mengupdate isi
program pada mikrokontroler.
5. Apabila program berjalan dengan baik, seharusnya motor berputar dengan kecepatan yang
sama, dan data kecepatan motor yang ditampilkan pada LCD mendekati/sama dengan nilai
setpointnya.
6. Kecepatan motor dapat diatur dengan mengubah setpoint kecepatan motor (variabel
SpeedKa dan variabel SpeedKi).
7. Konstanta gain dari masing-masing kontroler dapat diatur sesuai kebutuhan. Berikut perilaku
secara umum dari pengaruh PID gain terhadap respon system, yaitu:
KP gain ketika dinaikkan akan mempercepat respon motor terhadap nilai setpoint
yang diberikan atau perubahan terhadap perubahan beban. Akan tetapi apabila
nilainya dinaikkan, maka kemungkinan terjadi overshoot juga akan naik.
KI gain ketika diperbesar akan cepat mengurangi steady state error, dan bisa
mempercepat tercapainya setpoint selama perubahan setpoint mengarah ke arah
yang sama (berlanjut membesar atau mengecil dari nilai sebelumnya). Sehingga KI
gain yang besar cocok untuk aplikasi pengaturan kecepatan motor yang setpoint-nya
cenderung statis. Akan tetapi naiknya KI gain ini akan menaikkan kemungkinan
terjadinya osilasi dari respon kecepatan (biasanya frekwensi osilasi relatif rendah
jika osilasi tersebut disebabkan oleh nilai KI gain yang terlalu besar). Selain itu
naiknya nilai KI gain akan menyebabkan respon kendali kecepatan justru akan
melambat apabila nilai setpoint yang diberikann bersifat fluktuatif.
KD gain ketika dinaikkan akan mempercepat repon sistem terhadap perubahan
setpoint. Sehingga KD gain yang besar diperlukan pada pengaturan kecepatan motor
yang kecepatannya cenderung dinamis. Akan tetapi apabila nilainya terlalu besar
akan membuat kecepatan mortor mudah berosilasi. Biasanya frekwensi osilasi yang
dihasilkan relatif tinggi jika osilasi tersebut disebabkan oleh nilai KD gain yang terlalu
besar.
D. Tugas
/*********************************************************
Project : ADROIT AVR Rev.3
Version : 1
Date : 3/13/2014
Author : Eko Henfri Binugroho
Company : ER2C
Code : Buzzer access and tone generator
*********************************************************/
#ifndef _myBuzzer_
#define _myBuzzer_
#include <mega128.h>
#include <delay.h>
#define C5 523
#define CS5 554
#define D5 587
#define DS5 622
#define E5 659
#define F5 698
#define FS5 740
#define G5 783
#define GS5 830
#define A5 880
#define AS5 932
#define B5 987
#define C6 1046
#define C7 2093
#define CS7 2217
#define D7 2349
#define DS7 2489
#define E7 2639
#define F7 2793
#define FS7 2960
#define G7 3136
#define GS7 3322
#define A7 3520
#define AS7 3729
#define B7 3951
void BuzzerOff()
{ TCCR0=0x00; PORTB.4=0; ASSR=0x00; }
void Nada1(void)
{ Buzzer(1000,100);Buzzer(500,20);
Buzzer(3000,50);Buzzer(500,20);
Buzzer(3000,100);Buzzer(500,20);
Buzzer(2000,50);
}
void Nada2(void)
{ Buzzer(3000,100);Buzzer(500,20);
Buzzer(2500,150);Buzzer(500,20);
Buzzer(1000,50);Buzzer(500,20);
Buzzer(3000,50);
}
void Nada3(void)
{ Buzzer(3000,50);Buzzer(500,20);
Buzzer(1000,150);Buzzer(500,20);
Buzzer(3000,100);Buzzer(500,20);
Buzzer(2000,50);
}
#endif
Untuk bisa mengakses lagu, maka kedua data melodi dan tempo dari lagu perlu dideklarasikan pada
program main, yaitu: