Paralel Robot Yazılım konusunda İleri kinematik denklemi matlabta yazılmış ve test edilmiştir kod aşağıdadır. Bu kodu elektronik devrede pic içinede yazılmış ve kullanılmıştır. Pic osilatör frekansı 4Mhz olduğu durumda çözümü yaklaşık 10-20sn arasında sürmektedir. Bu yüzden yüksek hızlı pic’ ler seçilmesini öneririm.
Aşağıdaki kodda dikkat edilmesi gereken öenmli nokta “robot geometri” kısmıdır. Yapılan robotun geometrisi çizim porgramlarında hassas olarak belirlenip programa girilmelidir. Aksi halde aldığınız sonuçlar doğru olmaz. Daha sonra açı değerlerini girip end-effectorun xyz konumunu alabilirsiniz.
Ters kinematik koddada xyz değerlerini girip açı değerlerini hesaplatabilirsiniz. MATLAB ta GUI kullanarak açı değerlerini veya xyz değerlerini çeşitli kontroller ile girilmesini sağlaabilir ve hesaplanan sonuçları yine seri porttan robotun elektroniğine gönderip robot kontrol edilebilir. Ben kontrol için iki farklı yöntem yaptım. İlki ters kinematik ve ileri kinematik denklemi pic in içine gömerek butonlarla kontrolü sağladım. İkinci olarak aynı kodu kullanarak visual c# programında göresel program yazarak bir çok farklı şekilde robotun kontrolü sağladım. Visual c# programını aşağıdaki koddan sonra bulabilirsiniz.
MATLAB KODU
Forward Kinematics Equation (İleri Kinematik Denklem)
% forward kinemeatics solution from mzavatsky in website % http://forums.trossenrobotics.com/tutorials/introduction-129/delta-robot-kinematics-3276/ % marmara üniversity engineering faculty mechanical engineering % remzi şahinoğlu % 18.04.2011 clear all %clc % robot geometry % (look at pics above for explanation) e = 109.12; % end effector f = 346.41; % base re = 323.59; % rod length rf = 133.09; % arm length % trigonometric constants sqrt3 = sqrt(3.0); pi = 3.141592653; sin120 = sqrt3/2.0; cos120 = -0.5; tan60 = sqrt3; sin30 = 0.5; tan30 = 1/sqrt3; % forward kinematics: (theta1, theta2, theta3) -> (x0, y0, z0) % returned status: 0=OK, -1=non-existing position t = (f-e)*tan30/2; dtr = pi/180.0; %************** açı değerlerini girin ******************* theta1 = -8.7723*pi/180.0; theta2 = -8.7723*pi/180.0; theta3 = -8.7723*pi/180.0; %************** açı değerlerini girin ******************* y1 = -(t + rf*cos(theta1)); z1 = -rf*sin(theta1); y2 = (t + rf*cos(theta2))*sin30; x2 = y2*tan60; z2 = -rf*sin(theta2); y3 = (t + rf*cos(theta3))*sin30; x3 = -y3*tan60; z3 = -rf*sin(theta3); dnm = (y2-y1)*x3-(y3-y1)*x2; w1 = y1*y1 + z1*z1; w2 = x2*x2 + y2*y2 + z2*z2; w3 = x3*x3 + y3*y3 + z3*z3; % x = (a1*z + b1)/dnm a1 = (z2-z1)*(y3-y1)-(z3-z1)*(y2-y1); b1 = -((w2-w1)*(y3-y1)-(w3-w1)*(y2-y1))/2.0; % y = (a2*z + b2)/dnm; a2 = -(z2-z1)*x3+(z3-z1)*x2; b2 = ((w2-w1)*x3 - (w3-w1)*x2)/2.0; % a*z^2 + b*z + c = 0 a = a1*a1 + a2*a2 + dnm*dnm; b = 2*(a1*b1 + a2*(b2-y1*dnm) - z1*dnm*dnm); c = (b2-y1*dnm)*(b2-y1*dnm) + b1*b1 + dnm*dnm*(z1*z1 - re*re); % discriminant d = b*b - 4.0*a*c; if (d > 0) z0 = -0.5*(b+sqrt(d))/a y0 = (a2*z0 + b2)/dnm x0 = (a1*z0 + b1)/dnm else disp = 'non-existing point' end
Reverse Kinematics Equation (Ters Kinematik Denklem)
% reverse kinemeatics solution from mzavatsky in website % http://forums.trossenrobotics.com/tutorials/introduction-129/delta-robot-kinematics-3276/ % marmara üniversity engineering faculty mechanical engineering % remzi şahinoğlu % 18.04.2011 clear all clc % robot geometry % (look at pics above for explanation) e = 109.11920088; % base triangle side length f = 143.76021703; % end effector triangle side length re = 323.59252155; % rod length rf = 133.09395178; % arm length % trigonometric constants sqrt3 = sqrt(3.0); pi = 3.141592653; sin120 = sqrt3/2.0; cos120 = -0.5; tan60 = sqrt3; sin30 = 0.5; tan30 = 1/sqrt3; %*************** x y z bilgilerini buraya giriniz *************** x0 = 0; y0 = 0; z0 = -270.69926935; % değer eksi olmalıdır çünkü z ekseni yukarı yönde pozitiftir %*************** x y z bilgilerini buraya giriniz *************** %********** theta 2 % inverse kinematics % helper functions, calculates angle theta1 (for YZ-pane) %int delta_calcAngleYZ(float x0, float y0, float z0, float &theta) y1 = -0.5 * 0.57735 * f; % f/2 * tg 30 y01 = y0 -0.5 * 0.57735 * e; % shift center to edge % z = a + b*y a = (x0*x0 + y01*y01 + z0*z0 +rf*rf - re*re - y1*y1)/(2*z0); b = (y1-y01)/z0; % discriminant d = -(a+b*y1)*(a+b*y1)+rf*(b*b*rf+rf); if (d > 0) yj = (y1 - a*b - sqrt(d))/(b*b + 1); % choosing outer point zj = a + b*yj; theta_1 = 180.0*atan(-zj/(y1 - yj))/pi; % + ((yj>y1)?180.0:0.0); yj, y1 den küçükse 180 degilse 0 değerini çıkarır if (yj>y1) theta_2 = 180; else theta_2 = 0; end theta1 = theta_1 + theta_2 else disp= 'non-existing point' end %********** theta 2 x02 = x0*cos120 + y0*sin120; y02 = y0*cos120 - x0*sin120; z02 = z0; %y1 = cos(120)*(-0.5 * 0.57735 * f); y1 = -0.5 * 0.57735 * f; % f/2 * tg 30 y02 = y02 -0.5 * 0.57735 * e; % shift center to edge % z = a + b*y a = (x02*x02 + y02*y02 + z02*z02 +rf*rf - re*re - y1*y1)/(2*z02); b = (y1-y02)/z02; % discriminant d = -(a+b*y1)*(a+b*y1)+rf*(b*b*rf+rf); if (d > 0) yj = (y1 - a*b - sqrt(d))/(b*b + 1); % choosing outer point zj = a + b*yj; theta_1 = 180.0*atan(-zj/(y1 - yj))/pi; % + ((yj>y1)?180.0:0.0); yj, y1 den küçükse 180 degilse 0 değerini çıkarır if (yj>y1) theta_2 = 180; else theta_2 = 0; end theta2 = theta_1 + theta_2 else disp= 'non-existing point' end %************theta3 x03 = x0*cos120 - y0*sin120; y03 = y0*cos120 + x0*sin120; z03 = z0; y1 = -0.5 * 0.57735 * f; % f/2 * tg 30 y03 = y03 -0.5 * 0.57735 * e; % shift center to edge % z = a + b*y a = (x03*x03 + y03*y03 + z03*z03 +rf*rf - re*re - y1*y1)/(2*z03); b = (y1-y03)/z03; % discriminant d = -(a+b*y1)*(a+b*y1)+rf*(b*b*rf+rf); if (d > 0) yj = (y1 - a*b - sqrt(d))/(b*b + 1); % choosing outer point zj = a + b*yj; theta_1 = 180.0*atan(-zj/(y1 - yj))/pi; % + ((yj>y1)?180.0:0.0); yj, y1 den küçükse 180 degilse 0 değerini çıkarır if (yj>y1) theta_2 = 180; else theta_2 = 0; end theta3 = theta_1 + theta_2 else disp= 'non-existing point' end
Visual C#: Paralel Robot Yazılım
Bu kod tarafımdan yazılmıştır. Amacı delta robotun bilgisayar ile kontrolünü sağlamaktır. 6 farklı şekilde robot kontrolü sağlamaya izin verir. Mavi ekran robotun bilgisayar faresi ile kontrol edilmesi sağlar. Bilgisayar faresi mavi ekranın sınırları içerisine girdiğinde farenin ekranda bulunduğu xy posizyonu program tarafından okunup o an ki z ekseni değerine göre anlık olarak kinematik denklemden geçirilerek hesaplanan açı değerleri seri porttan gönderilir. Fare konumu her değiştiğinde bu işlem yapılır. Bu şekilde gerçek zamanlı olarak hareket ettirilebilr. Farenin sol tuşu ile robotun z ekseni +10mm sağ tuşu ile -10mm olarak hareket ettirilebilir. Farnin tekerlek tuşunada basılarak kıskaç açılıp kapanabilir.
Sağ üst köşedeki scrollbar lar ise kollar kinematik denklemden ve birbirinden bağımsız olarak hareket ettimeye yarar. Saü alt taraftaki xyz butonları 100mm kadar robotu hareket ettirir. Onun yanındaki nokta kontrol bloguna girelen xyz değerleri git tuşuna basılınca robot o konuma gider.
Ortadaki programlama blogu ise robotun hareketlerini kıskacın durumunu kaydet tuşuna basarak hafızaya alır. Birden fazla nokta berlileyip hafızaya alındıktan sonra çalış tuşuna basarak ilk noktadan en son noktaya doğru robotun otomatik kontrolünü yapabilirsiniz.
Önemli not olarak bu programda robot geometri kısmındaki değişkenleri kendi robotunuzun geometrisine göre değiştirmeniz gereklidir. Aynı şekilde 3d programında robotunuzun sıfır pozisyonundaki end-effectorun xyz konumu hassas olarak ölçülüp robot geometri bölümün altındaki sıfır posizyon bölümüne değerler girilmelidir.
using System; using System.Collections.Generic; using System.ComponentModel; using System.Data; using System.Drawing; using System.IO.Ports; using System.Linq; using System.Text; using System.Windows.Forms; namespace delta_robot_v1 { public partial class Form1 : Form { byte servo1,servo2,servo3,kiskac; float e, f, re, rf, x0, y0, z0, x02, x03, y1, y01, y02, y03, z02, z03, theta1, theta2, theta3, a, b, d, yj, zj; float t, dtr, y001, z1, z2, y2, x2, y3, x3, z3, dnm, w1, w2, w3, a1, b1, a2, b2, a0, b0, c0, d0; float pi=3.1415927F; string kiskac_txt; byte[] servo_pwm = new byte[200]; // 50 point veya işlem yapılabilir int i = 0, dongu; public Form1() { InitializeComponent(); comboBox1.Items.Add("COM1"); comboBox1.Items.Add("COM2"); comboBox1.Items.Add("COM3"); comboBox1.Items.Add("COM4"); comboBox1.Items.Add("COM5"); comboBox1.Items.Add("COM6"); comboBox1.Text = "COM1"; timer1.Enabled = false; if (serialPort1.IsOpen == true) // program başladıgında port acıksa kapat { serialPort1.Close(); } x_pos.Enabled = false; // port kapalı ise kontrol butonlarını pasifle x_neg.Enabled = false; y_pos.Enabled = false; y_neg.Enabled = false; z_pos.Enabled = false; z_neg.Enabled = false; Kaydet_btn.Enabled = false; Sil_btn.Enabled = false; Calis_btn.Enabled = false; Dur_btn.Enabled = false; listBox1.Enabled = false; textBox_in_x.Enabled = false; textBox_in_y.Enabled = false; textBox_in_z.Enabled = false; checkBox_mouse.Enabled = false; kiskac_ac_btn.Enabled = false; sifir_poz_btn.Enabled = false; btn_git.Enabled = false; vScrollBar_1.Enabled = false; vScrollBar_2.Enabled = false; vScrollBar_3.Enabled = false; hScrollBar1_Timer.Enabled = false; // robot geometrisi için değişkenlerin atanması e = 109.12F; // end-effectorun üçgeninin kenar uzunluğu f = 346.41F; // base üçgeninin kenar uzunluğu rf = 133.09F; // arm uzunluğu re = 323.59F; // rod uzunluğu // robot ilk çalışmada sıfır posizyonuna gitmesi için x0 = 0; y0 = 0; z0 = -253.125F; hesapla_aci(); // ilk açılışta göstergelerin robotun sıfır pozisyonundaki hesapla_pwm(); // değerlerini alması için hesaplaması gerekir veriyi_gonder(); } //**************************************************************************************// //************* GİRİLEN XYZ POZİSYON BİLGİSİNE GÖRE AÇI DEĞERLERİNİ HESAPLA ************// private void hesapla_aci() { //********** theta 1 ******************************************************// y1 = -0.5F * 0.57735F * f; // f/2 * tg 30 y01 = y0 - 0.5F * 0.57735F * e; // shift center to edge // z = a + b*y a = (x0 * x0 + y01 * y01 + z0 * z0 + rf * rf - re * re - y1 * y1) / (2 * z0); b = (y1 - y01) / z0; // discriminant d = -(a + b * y1) * (a + b * y1) + rf * (b * b * rf + rf); if (d > 0) { yj = (y1 - a * b - (float)Math.Sqrt(d) / (b * b + 1)); // choosing outer point zj = a + b * yj; theta1 = 180.0F * (float)Math.Atan(-zj / (y1 - yj)) / pi + ((yj > y1) ? 180.0F : 0.0F); // yj, y1 den küçükse 180; degilse 0 değerini çıkarır } else { no_point(); } //********** theta 2 ******************************************************// x02 = x0 * (float)Math.Cos(120 * pi / 180) + y0 * (float)Math.Sin(120 * pi / 180); y02 = y0 * (float)Math.Cos(120 * pi / 180) - x0 * (float)Math.Sin(120 * pi / 180); z02 = z0; //y1 = cos(120)*(-0.5 * 0.57735 * f); y1 = -0.5F * 0.57735F * f; // f/2 * tg 30 y02 = y02 - 0.5F * 0.57735F * e; // shift center to edge // z = a + b*y a = (x02 * x02 + y02 * y02 + z02 * z02 + rf * rf - re * re - y1 * y1) / (2 * z02); b = (y1 - y02) / z02; // discriminant d = -(a + b * y1) * (a + b * y1) + rf * (b * b * rf + rf); if (d > 0) { yj = (y1 - a * b - (float)Math.Sqrt(d)) / (b * b + 1); // choosing outer point zj = a + b * yj; theta2 = 180.0F * (float)Math.Atan(-zj / (y1 - yj)) / pi + ((yj > y1) ? 180.0F : 0.0F); //yj, y1 den küçükse 180; degilse 0 değerini çıkarır } else { no_point(); } //********** theta 3 ******************************************************// x03 = x0 * (float)Math.Cos(120 * pi / 180) - y0 * (float)Math.Sin(120 * pi / 180); y03 = y0 * (float)Math.Cos(120 * pi / 180) + x0 * (float)Math.Sin(120 * pi / 180); z03 = z0; y1 = -0.5F * 0.57735F * f; // f/2 * tg 30 y03 = y03 - 0.5F * 0.57735F * e; // shift center to edge // z = a + b*y a = (x03 * x03 + y03 * y03 + z03 * z03 + rf * rf - re * re - y1 * y1) / (2 * z03); b = (y1 - y03) / z03; // discriminant d = -(a + b * y1) * (a + b * y1) + rf * (b * b * rf + rf); if (d > 0) { yj = (y1 - a * b - (float)Math.Sqrt(d)) / (b * b + 1); // choosing outer point zj = a + b * yj; theta3 = 180.0F * (float)Math.Atan(-zj / (y1 - yj)) / pi + ((yj > y1) ? 180.0F : 0.0F); //yj, y1 den küçükse 180; degilse 0 değerini çıkarır } else { no_point(); } } //******************* ÇALIŞMA UZAYINI DIŞINDA BİR NOKTA TANIMLANDIĞINDA ****************// private void no_point() { MessageBox.Show("Hata: Çalışma alanı dışında bir nokta tanımlanmış"); } //**************************************************************************************// //*************** GİRİLEN AÇI BİLGİSİNDEN POSİZYON BİLGİSİNİ HESAPLAMA *****************// private void hesapla_pozisyon() // hata var çözüm henüz bulunamadı { // theta değerleri radyan olarak girilmelidir //theta1 = theta1 * pi / 180; //theta2 = theta2 * pi / 180; //theta3 = theta3 * pi / 180; t = (f - e) * (float)Math.Tan(30) / 2; dtr = pi / 180; y001 = -(t + rf * (float)Math.Cos(theta1)); z1 = -rf * (float)Math.Sin(theta1); y2 = (t + rf * (float)Math.Cos(theta2)) * (float)Math.Sin(30); x2 = y2 * (float)Math.Tan(60); z2 = -rf * (float)Math.Sin(theta2); y3 = (t + rf * (float)Math.Cos(theta3)) * (float)Math.Sin(30); x3 = -y3 * (float)Math.Tan(60); z3 = -rf * (float)Math.Sin(theta3); dnm = (y2 - y001) * x3 - (y3 - y001) * x2; w1 = y001 * y001 + z1 * z1; w2 = x2 * x2 + y2 * y2 + z2 * z2; w3 = x3 * x3 + y3 * y3 + z3 * z3; // x = (a1*z + b1)/dnm a1 = (z2 - z1) * (y3 - y001) - (z3 - z1) * (y2 - y001); b1 = -((w2 - w1) * (y3 - y001) - (w3 - w1) * (y2 - y001)) / 2; // y = (a2*z + b2)/dnm; a2 = -(z2 - z1) * x3 + (z3 - z1) * x2; b2 = ((w2 - w1) * x3 - (w3 - w1) * x2) / 2; // a*z^2 + b*z + c = 0 a0 = a1 * a1 + a2 * a2 + dnm * dnm; b0 = 2 * (a1 * b1 + a2 * (b2 - y1 * dnm) - z1 * dnm * dnm); c0 = (b2 - y001 * dnm) * (b2 - y001 * dnm) + b1 * b1 + dnm * dnm * (z1 * z1 - re * re); // discriminant d0 = b0 * b0 - 4 * a0 * c0; if (d0 > 0) { z0 = -0.5F * (b + (float)Math.Sqrt(d)) / a0; y0 = (a2 * z0 + b2) / dnm; x0 = (a1 * z0 + b1) / dnm; } else { no_point(); } } //**************************************************************************************// //************ HESAPLANAN AÇI DEĞERLERİNE GÖRE PWM DUTY SÜRELERİNİ HESAPLA *************// private void hesapla_pwm() { if (143.333F + 1.0833 * theta1 < 230) servo1 = Convert.ToByte(143.333F + 1.0833 * theta1); else servo1 = 230; if (143.333F + 1.0833 * theta2 < 230) servo2 = Convert.ToByte(143.333F + 1.0833 * theta2); else servo2 = 230; if (143.333F + 1.0833 * theta3 < 230) servo3 = Convert.ToByte(143.333F + 1.0833 * theta3); else servo3 = 230; } //**************************************************************************************// //*************** HESAPLANAN AÇI ve POZİSYON BİLGİLERİNİ GÖSTERGEYE YAZ ****************// private void gostergeye_yaz() { // pozisyon bilgilerini göstergeye yaz label_xpos.Text = Convert.ToString(x0); label_ypos.Text = Convert.ToString(y0); label_zpos.Text = Convert.ToString(z0); // açı bilgilerini açı bilgisi göstergesine yaz label16.Text = Convert.ToString(theta1); label17.Text = Convert.ToString(theta2); label18.Text = Convert.ToString(theta3); // pwm duty sürelerini göstergeye yaz label20.Text = servo1.ToString(); label21.Text = servo2.ToString(); label22.Text = servo3.ToString(); } //**************************************************************************************// //**************************** BİLGİYİ SERİ PORTTAN GÖNDER *****************************// private void veriyi_gonder() { if (serialPort1.IsOpen == true) { serialPort1.Write(new byte[] { servo1, servo2, servo3, kiskac }, 0, 4); } } //**************************************************************************************// //************************ SERİ PORTU AÇ 9600 BAUD RATE HIZI ***************************// private void baglan_Click(object sender, EventArgs e) { if (serialPort1.IsOpen == false) { comboBox1.Enabled = false; serialPort1.Open(); // port aç baglan.Text = "Bağlantıyı Kes"; baglan.BackColor = Color.Green; x_pos.Enabled = true; // port kapalı ise kontrol butonlarını aktif et x_neg.Enabled = true; y_pos.Enabled = true; y_neg.Enabled = true; z_pos.Enabled = true; z_neg.Enabled = true; Kaydet_btn.Enabled = true; Sil_btn.Enabled = true; Calis_btn.Enabled = true; Dur_btn.Enabled = true; listBox1.Enabled = true; textBox_in_x.Enabled = true; textBox_in_y.Enabled = true; textBox_in_z.Enabled = true; checkBox_mouse.Enabled = true; kiskac_ac_btn.Enabled = true; sifir_poz_btn.Enabled = true; btn_git.Enabled = true; vScrollBar_1.Enabled = true; vScrollBar_2.Enabled = true; vScrollBar_3.Enabled = true; hScrollBar1_Timer.Enabled = true; } else { comboBox1.Enabled = true; serialPort1.Close(); // port kapa baglan.Text = "Bağlan"; baglan.BackColor = Color.Red; x_pos.Enabled = false; // port kapalı ise kontrol butonlarını pasifle x_neg.Enabled = false; y_pos.Enabled = false; y_neg.Enabled = false; z_pos.Enabled = false; z_neg.Enabled = false; Kaydet_btn.Enabled = false; Sil_btn.Enabled = false; Calis_btn.Enabled = false; Dur_btn.Enabled = false; listBox1.Enabled = false; textBox_in_x.Enabled = false; textBox_in_y.Enabled = false; textBox_in_z.Enabled = false; checkBox_mouse.Enabled = false; kiskac_ac_btn.Enabled = false; sifir_poz_btn.Enabled = false; btn_git.Enabled = false; vScrollBar_1.Enabled = false; vScrollBar_2.Enabled = false; vScrollBar_3.Enabled = false; hScrollBar1_Timer.Enabled = false; } } //**************************************************************************************// //********************* EKSEN KONTROL BUTONLARI X-Y-Z ve KISKAC ************************// private void x_pos_Click(object sender, EventArgs e) { x0 = x0 + 10; hesapla_aci(); hesapla_pwm(); gostergeye_yaz(); veriyi_gonder(); } private void x_neg_Click(object sender, EventArgs e) { x0 = x0 - 10; hesapla_aci(); hesapla_pwm(); gostergeye_yaz(); veriyi_gonder(); } private void y_pos_Click(object sender, EventArgs e) { y0 = y0 + 10; hesapla_aci(); hesapla_pwm(); gostergeye_yaz(); veriyi_gonder(); } private void y_neg_Click(object sender, EventArgs e) { y0 = y0 - 10; hesapla_aci(); hesapla_pwm(); gostergeye_yaz(); veriyi_gonder(); } private void z_pos_Click(object sender, EventArgs e) { z0 = z0 + 10; hesapla_aci(); hesapla_pwm(); gostergeye_yaz(); veriyi_gonder(); } private void z_neg_Click(object sender, EventArgs e) { z0 = z0 - 10; hesapla_aci(); hesapla_pwm(); gostergeye_yaz(); veriyi_gonder(); } //********************************* KISKACI AC KAPAT ***********************************// private void kiskac_ac_btn_Click(object sender, EventArgs e) { if (kiskac_ac_btn.Text == "Kıskaç aç") { kiskac_ac_btn.Text = "Kıskaç kapat"; kiskac = 151; veriyi_gonder(); } else { kiskac_ac_btn.Text = "Kıskaç aç"; kiskac = 150; veriyi_gonder(); } } //**************************************************************************************// //*************************** ROBOTU SIFIR POZİSYONUNA GETİR ***************************// private void sifir_poz_btn_Click(object sender, EventArgs e) { kiskac_ac_btn.Text = "Kıskaç kapalı"; vScrollBar_1.Value = 150; vScrollBar_2.Value = 150; vScrollBar_3.Value = 150; kiskac = 150; x0 = 0; y0 = 0; z0 = -253.125F; hesapla_aci(); hesapla_pwm(); gostergeye_yaz(); veriyi_gonder(); } //**************************************************************************************// //****************** MOUSE İLE KONTROLÜ MODU - SÜRÜKLEME *******************************// private void pictureBox1_MouseMove(object sender, MouseEventArgs e) { Point nokta = Cursor.Position; if (checkBox_mouse.Checked == true) { x0 = (nokta.X - 208); y0 = (nokta.Y - 234); hesapla_aci(); hesapla_pwm(); veriyi_gonder(); gostergeye_yaz(); } } //**************************************************************************************// //****************** MOUSE İLE KONTROLÜ MODU - BUTON TIKLAMA ***************************// private void pictureBox1_MouseClick(object sender, MouseEventArgs e) { if (checkBox_mouse.Checked == true) { if (e.Button == MouseButtons.Left) //label_zpos.Text = "L"; z0 = z0 + 10; else if (e.Button == MouseButtons.Right) z0 = z0 - 10; else if (e.Button == MouseButtons.Middle) if (kiskac == 150) // tekerleğe tıklanınca kıskac açıksa kapat, kapalı ise aç { kiskac = 151; } else { kiskac = 150; } } } //**************************************************************************************// //********************** SERVO MOTOR KONTROL SCROLL BARLARI ****************************// private void vScrollBar_1_Scroll(object sender, ScrollEventArgs e) { label16.Text = Convert.ToString(132.31 - (0.9231 * vScrollBar_1.Value)); //hesapla_pozisyon(); // hatalı hesaplama yapıyor //gostergeye_yaz(); servo1 = Convert.ToByte(vScrollBar_1.Value); serialPort1.Write(new byte[] { servo1, servo2, servo3, kiskac }, 0, 4); } private void vScrollBar_2_Scroll(object sender, ScrollEventArgs e) { label17.Text = Convert.ToString(132.31 - (0.9231 * vScrollBar_2.Value)); servo2 = Convert.ToByte(vScrollBar_2.Value); // veriyi buradan gönder serialPort1.Write(new byte[] { servo1, servo2, servo3, kiskac }, 0, 4); } private void vScrollBar_3_Scroll(object sender, ScrollEventArgs e) { label18.Text = Convert.ToString(132.31 - (0.9231 * vScrollBar_3.Value)); servo3 = Convert.ToByte(vScrollBar_3.Value); // veriyi buradan gönder serialPort1.Write(new byte[] { servo1, servo2, servo3, kiskac }, 0, 4); } //**************************************************************************************// //********************** GİRİLEN XYZ BİLGİSİNE GİT BUTONU */****************************// private void btn_git_Click(object sender, EventArgs e) { x0 = Convert.ToInt16(textBox_in_x.Text); y0 = Convert.ToInt16(textBox_in_y.Text); z0 = Convert.ToInt16(textBox_in_z.Text); hesapla_aci(); hesapla_pwm(); gostergeye_yaz(); veriyi_gonder(); } //*************************** PROGRAMLAMA KONTROL **************************************// private void Kaydet_btn_Click(object sender, EventArgs e) { if (kiskac == 151) { kiskac_txt = "açık"; } else { kiskac_txt = "kapalı"; } listBox1.Items.Add("X:" + Convert.ToString(x0) + ", Y:" + Convert.ToString(y0) + ", Z:" + Convert.ToString(z0) + ", K:" + kiskac_txt); // servo pwm bilgilerini kaydet i = i + 1; servo_pwm[i] = servo1; i = i + 1; servo_pwm[i] = servo2; i = i + 1; servo_pwm[i] = servo3; i = i + 1; servo_pwm[i] = kiskac; } private void Sil_btn_Click(object sender, EventArgs e) { listBox1.Items.Remove(listBox1.SelectedItem); if (i > 0) { servo_pwm[i] = 0; i = i - 1; servo_pwm[i] = 0; i = i - 1; servo_pwm[i] = 0; i = i - 1; servo_pwm[i] = 0; i = i - 1; } else { i = 0; } } private void Calis_btn_Click(object sender, EventArgs e) { Kaydet_btn.Enabled = false; Sil_btn.Enabled = false; timer1.Enabled = true; dongu = i; i = 0; } private void timer1_Tick(object sender, EventArgs e) { if (i < dongu) { i = i + 1; servo1 = servo_pwm[i]; i = i + 1; servo2 = servo_pwm[i]; i = i + 1; servo3 = servo_pwm[i]; i = i + 1; kiskac = servo_pwm[i]; gostergeye_yaz(); veriyi_gonder(); } else { timer1.Enabled = false; Kaydet_btn.Enabled = true; Sil_btn.Enabled = true; } } private void Dur_btn_Click(object sender, EventArgs e) { timer1.Enabled = false; Kaydet_btn.Enabled = true; Sil_btn.Enabled = true; } private void hScrollBar1_Timer_Scroll(object sender, ScrollEventArgs e) { timer1.Interval = hScrollBar1_Timer.Value; } private void Form1_FormClosed(object sender, FormClosedEventArgs e) { timer1.Enabled = false; if (serialPort1.IsOpen == true) // program kapatıldıgında port acıksa kapat { serialPort1.Close(); } } private void comboBox1_SelectedIndexChanged(object sender, EventArgs e) { serialPort1.PortName = comboBox1.Text; } } }
Bir sonraki uygulamamızda Parelel robotumuzu step motor ile nasıl tahrik edilir öğreneceğiz.
0 yorum