1、功能描述
R308樣機(jī)是一款擁有3自由度的串聯(lián)機(jī)械臂。本文提供的示例所實現(xiàn)的功能為:在3自由度串聯(lián)機(jī)械臂樣機(jī)上安裝電磁鐵,實現(xiàn)電磁鐵搬運(yùn)物品的功能。
2、電子硬件
在這個示例中,我們采用了以下硬件,請大家參考:
主控板 | Basra(兼容Arduino Uno) |
擴(kuò)展板 | Bigfish2.1 |
舵機(jī) | 270°伺服電機(jī) |
電池 | 7.4V鋰電池 |
其它 | 電磁鐵、USB線 |
電路連接說明:
注:
① 270°伺服電機(jī)連接在Bigfish擴(kuò)展板D4 . GND . VCC接口上
② 270°伺服電機(jī)連接在Bigfish擴(kuò)展板D7 . GND . VCC接口上
③ 270°伺服電機(jī)連接在Bigfish擴(kuò)展板D11 . GND . VCC接口上
電磁鐵連接在Bigfish擴(kuò)展板D9,D10接口上
3、運(yùn)動控制
上位機(jī):Controller 1.0
下位機(jī)編程環(huán)境:Arduino 1.8.19
3.1初始位置的設(shè)定
① 將Controller下位機(jī)程序servo_bigfish.ino直接下載到主控板。這段代碼供Controller上位機(jī)與主控板通信,并允許調(diào)試舵機(jī)。代碼如下:
/*------------------------------------------------------------------------------------ 版權(quán)說明:Copyright 2023 Robottime(Beijing) Technology Co., Ltd. All Rights Reserved. Distributed under MIT license.See file LICENSE for detail or copy at https://opensource.org/licenses/MIT by 機(jī)器譜 2023-01-31 https://www.robotway.com/ ------------------------------ /* * Bigfish擴(kuò)展板舵機(jī)口; 4, 7, 11, 3, 8, 12, 14, 15, 16, 17, 18, 19 * 使用軟件調(diào)節(jié)舵機(jī)時請拖拽對應(yīng)序號的控制塊 */ #include #define ANGLE_VALUE_MIN 0 #define ANGLE_VALUE_MAX 180 #define PWM_VALUE_MIN 500 #define PWM_VALUE_MAX 2500 #define SERVO_NUM 12 Servo myServo[SERVO_NUM]; int data_array[2] = {0,0}; //servo_pin: data_array[0], servo_value: data_array[1]; int servo_port[SERVO_NUM] = {4, 7, 11, 3, 8, 12, 14, 15, 16, 17, 18, 19}; int servo_value[SERVO_NUM] = {}; String data = ""; boolean dataComplete = false; void setup() { Serial.begin(9600); } void loop() { while(Serial.available()) { int B_flag, P_flag, T_flag; data = Serial.readStringUntil('n'); data.trim(); for(int i=0;i= ANGLE_VALUE_MIN && where <= ANGLE_VALUE_MAX) { myServo[which].write(where); } else if(where >= PWM_VALUE_MIN && where <= PWM_VALUE_MAX) { myServo[which].writeMicroseconds(where); } } int pin2index(int _pin){ int index; switch(_pin) { case 4: index = 0; break; case 7: index = 1; break; case 11: index = 2; break; case 3: index = 3; break; case 8: index = 4; break; case 12: index = 5; break; case 14: index = 6; break; case 15: index = 7; break; case 16: index = 8; break; case 17: index = 9; break; case 18: index = 10; break; case 19: index = 11; break; } return index; }
下載完成后,保持主控板和電腦的USB連接,以便利用上位機(jī)進(jìn)行調(diào)試。
② 雙擊打開Controller 1.0b.exe:
③ 界面左上角選擇:設(shè)置-面板設(shè)置,彈出需要顯示的調(diào)試塊,可通過勾選隱藏不需要調(diào)試的舵機(jī)塊:聯(lián)機(jī)-選擇主控板對應(yīng)端口號以及波特率。
④ 拖動進(jìn)度條,可以觀察相應(yīng)的舵機(jī)角度轉(zhuǎn)動。寫好對應(yīng)的舵機(jī)調(diào)試角度,勾選左下角添加-轉(zhuǎn)化,獲得舵機(jī)調(diào)試的數(shù)組:
⑤ 將該數(shù)組直接復(fù)制到相應(yīng)的Arduino程序中的get_coordinate()部分進(jìn)行使用。
3.2調(diào)試好角度后將電磁鐵搬運(yùn)例程(calculate_angle_test.ino)下載到主控板【程序源碼詳見 https://www.robotway.com/h-col-191.html】
/*------------------------------------------------------------------------------------ 版權(quán)說明:Copyright 2023 Robottime(Beijing) Technology Co., Ltd. All Rights Reserved. Distributed under MIT license.See file LICENSE for detail or copy at https://opensource.org/licenses/MIT by 機(jī)器譜 2023-01-31 https://www.robotway.com/ ------------------------------*/ #include #include #define SERVO_SPEED 3460 //定義舵機(jī)轉(zhuǎn)動快慢的時間 #define ACTION_DELAY 200 //定義所有舵機(jī)每個狀態(tài)時間間隔 #define L1 172 #define L2 160 #define L3 135 Servo myServo[6]; int f = 200; //定義舵機(jī)每個狀態(tài)間轉(zhuǎn)動的次數(shù),以此來確定每個舵機(jī)每次轉(zhuǎn)動的角度 int servo_port[6] = {4,7,11,3,8,12}; //定義舵機(jī)引腳 int servo_num = sizeof(servo_port) / sizeof(servo_port[0]); //定義舵機(jī)數(shù)量 float value_init[6] = {1500, 1500, 1500, 0, 0, 0}; //定義舵機(jī)初始角度 double theta[3] = {}; float value_pwm[6] = {}; float coordinate[3] = {}; int data_num; boolean dataComplete = false; void setup() { Serial.begin(9600); pinMode(9, OUTPUT); pinMode(10, OUTPUT); for(int i=0;i= 0){ theta[0] = theta0 * 180 / PI; } else { theta[0] = 180 + theta0 * 180 / PI; } theta[1] = 90 - theta1 * 180 / PI; theta[2] = theta2 * 180 / PI; // Serial.print("theta0 = "); // Serial.println(theta[0]); // Serial.print("theta1 = "); // Serial.println(theta[1]); // Serial.print("theta2 = "); // Serial.println(theta[2]); // Serial.println("-------------------------------------"); } void ServoStart(int which) { if(!myServo[which].attached())myServo[which].attach(servo_port[which]); pinMode(servo_port[which], OUTPUT); } void ServoStop(int which) { myServo[which].detach(); digitalWrite(servo_port[which],LOW); } void ServoGo(int which , int where) { if(where!=200) { if(where==201) ServoStop(which); else { ServoStart(which); myServo[which].writeMicroseconds(where); } } } void servo_move(float value0, float value1, float value2, float value3, float value4, float value5) { float value_arguments[] = {value0, value1, value2, value3, value4, value5}; float value_delta[servo_num]; for(int i=0;i
審核編輯黃宇
-
機(jī)器人
+關(guān)注
關(guān)注
211文章
28445瀏覽量
207230 -
Arduino
+關(guān)注
關(guān)注
188文章
6470瀏覽量
187181 -
機(jī)械臂
+關(guān)注
關(guān)注
12文章
515瀏覽量
24599
發(fā)布評論請先 登錄
相關(guān)推薦
評論