1. 功能說明
在小型云臺機(jī)械手附近設(shè)置一個工作臺,并安裝一個顏色識別傳感器。將紅色、藍(lán)色工件分別放置在傳感器上,如果檢測的物料的顏色為紅色,機(jī)械臂將物體放在機(jī)械臂的左側(cè),如果檢測的物料的顏色為藍(lán)色,機(jī)械臂將物體放在機(jī)械臂的右側(cè),否則,機(jī)械臂不動作。
2. 使用樣機(jī)
本實驗使用的樣機(jī)是用探索者兼容零件制作的。
3. 功能實現(xiàn)
3.1 電子硬件
在這個示例中,采用了以下硬件,請大家參考:
將夾爪、腕關(guān)節(jié)、底座關(guān)節(jié)的舵機(jī)分別接在擴(kuò)展板的D4、D7以及D11舵機(jī)接口上,顏色傳感器接在A0、A4、A3口上。
3.2 編寫程序
編寫并燒錄以下程序(Color_Sorting_Robot.ino),該程序?qū)崿F(xiàn)演示視頻中的動作。
/******************************************************************************************* 版權(quán)說明:Copyright 2022 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ī)器譜 2022-12-21 https://www.robotway.com/ --------------------------------------------------------------------------------------- 實驗需求: 用顏色傳感器實現(xiàn)顏色識別。 實現(xiàn)思路: 程序的整體思路為:在機(jī)械臂前方安裝顏色傳感器,如果檢測的物料的顏色為紅色,機(jī)械臂將 物體放在機(jī)械臂的左側(cè),如果檢測的物料的顏色為藍(lán)色,機(jī)械臂將物體放在機(jī)械臂的右側(cè), 否則,機(jī)械臂不動作。 實驗接線: 最上端的機(jī)械爪舵機(jī)接D4; 中間的機(jī)械身軀舵機(jī)接D7; 最下端的機(jī)械底座舵機(jī)接D11; 顏色傳感器的接線為 S1 S2 5V GND S3 S2 5V GND OUT LED 5V GND | | | | | | | | | | | | A0 A1 5V GND A5 A4 5V GND D2 A3 5V GND ********************************************************************************************/ //顏色傳感器原理 /*首先進(jìn)行白平衡,把一個白色物體放置在TCS3200顏色傳感器之下,兩者相距10mm左右,點(diǎn)亮傳感器上的 4個白光LED燈,用Arduino控制器的定時器設(shè)置一固定時間1s,然后選通三種顏色的濾波器,讓被測物體反 射光中紅、綠、藍(lán)三色光分別通過濾波器,計算1s時間內(nèi)三色光分別對應(yīng)的TCS3200的輸出脈沖數(shù),再通過 算式得到白色物體RGB值255與三色光脈沖數(shù)的比例因子。有了白平衡后,得到的RGB比例因子,則其他顏色 物體反射光中紅、綠、藍(lán)三色光對應(yīng)的1s內(nèi)TCS3200輸出信號脈沖數(shù)乘以R、G、B比例因子,就可換算出被測 物體的RGB標(biāo)準(zhǔn)值。*/ #include "TimerOne.h" //顏色傳感器需要用到的定時函數(shù)庫 #include //舵機(jī)驅(qū)動需要的函數(shù)庫 ServoTimer2 myservo[3]; //舵機(jī)聲明 #define servo_num 3 //舵機(jī)數(shù)量 #define Servo_Speed 20 //舵機(jī)速度 #define Upward_servo_close 66 //機(jī)械爪閉合的角度值 #define Upward_servo_open 115 //機(jī)械爪張開的角度值 #define Middle_servo_down 105 //機(jī)械臂的初始角 #define Middle_servo_init 85 //機(jī)械臂的初始角 #define Middle_servo_left 10 //機(jī)械臂向左偏的角度 #define Middle_servo_left1 50 //機(jī)械臂向左偏的角度 #define Down_servo_middle 75 //機(jī)械底座初始角度值 #define Down_servo_left 5 //機(jī)械底座向左偏的角度值 #define Down_servo_right 145 //機(jī)械底座向右偏的角度值 int servo_pin[3]={4,7,11}; //定義舵機(jī)引腳號 float value_init[3]={Upward_servo_open, Middle_servo_left, Down_servo_middle};//舵機(jī)初始角度 int f=20; //舵機(jī)從角度A轉(zhuǎn)到角度B分的分?jǐn)?shù) //把TCS3200顏色傳感器各控制引腳連到Arduino數(shù)字端口 #define S0 A0 //物體表面的反射光越強(qiáng),TCS3002D的內(nèi)置振蕩器產(chǎn)生的方波頻率越高, #define S1 A1 //S0和S1的組合決定輸出信號頻率比率因子,比例因子為2% //比率因子為TCS3200傳感器OUT引腳輸出信號頻率與其內(nèi)置振蕩器頻率之比 #define S2 A4 //S2和S3的組合決定讓紅、綠、藍(lán),哪種光線通過濾波器 #define S3 A5 #define OUT 2 //TCS3200顏色傳感器輸出信號輸入到Arduino中斷0引腳,并引發(fā)脈沖信號中斷 //在中斷函數(shù)中記錄TCS3200輸出信號的脈沖個數(shù) #define LED A3 //控制TCS3200顏色傳感器是否點(diǎn)亮 int g_count = 0; // 計算與反射光強(qiáng)相對應(yīng)TCS3200顏色傳感器輸出信號的脈沖數(shù) // 數(shù)組存儲在1s內(nèi)TCS3200輸出信號的脈沖數(shù),它乘以RGB比例因子就是RGB標(biāo)準(zhǔn)值 int g_array[3]; int g_flag = 0; //濾波器模式選擇順序標(biāo)志 float g_SF[3]; // 存儲從TCS3200輸出信號的脈沖數(shù)轉(zhuǎn)換為RGB標(biāo)準(zhǔn)值的RGB比例因子 // 初始化TSC3200各控制引腳的輸入輸出模式 //設(shè)置TCS3002D的內(nèi)置振蕩器方波頻率與其輸出信號頻率的比例因子為2% void TSC_Init() { pinMode(S0, OUTPUT); pinMode(S1, OUTPUT); pinMode(S2, OUTPUT); pinMode(S3, OUTPUT); pinMode(OUT, INPUT); pinMode(LED, OUTPUT); digitalWrite(S0, LOW); digitalWrite(S1, HIGH); } //選擇濾波器模式,決定讓紅、綠、藍(lán),哪種光線通過濾波器 void TSC_FilterColor(int Level01, int Level02) { if(Level01 != LOW) Level01 = HIGH; if(Level02 != LOW) Level02 = HIGH; digitalWrite(S2, Level01); digitalWrite(S3, Level02); } //中斷函數(shù),計算TCS3200輸出信號的脈沖數(shù) void TSC_Count() { g_count ++ ; } //定時器中斷函數(shù),每1s中斷后,把該時間內(nèi)的紅、綠、藍(lán)三種光線通過濾波器時, //TCS3200輸出信號脈沖個數(shù)分別存儲到數(shù)組g_array[3]的相應(yīng)元素變量中 void TSC_Callback() { switch(g_flag) { case 0: TSC_WB(LOW, LOW); //選擇讓紅色光線通過濾波器的模式 break; case 1: g_array[0] = g_count; //存儲1s內(nèi)的紅光通過濾波器時,TCS3200輸出的脈沖個數(shù) TSC_WB(HIGH, HIGH); //選擇讓綠色光線通過濾波器的模式 break; case 2: g_array[1] = g_count; //存儲1s內(nèi)的綠光通過濾波器時,TCS3200輸出的脈沖個數(shù) TSC_WB(LOW, HIGH); //選擇讓藍(lán)色光線通過濾波器的模式 break; case 3: g_array[2] = g_count; //存儲1s內(nèi)的藍(lán)光通過濾波器時,TCS3200輸出的脈沖個數(shù) TSC_WB(HIGH, LOW); //選擇無濾波器的模式 break; default: g_count = 0; //計數(shù)值清零 break; } } //設(shè)置反射光中紅、綠、藍(lán)三色光分別通過濾波器時如何處理數(shù)據(jù)的標(biāo)志 //該函數(shù)被TSC_Callback( )調(diào)用 void TSC_WB(int Level0, int Level1) { g_count = 0; //計數(shù)值清零 g_flag ++; //輸出信號計數(shù)標(biāo)志 TSC_FilterColor(Level0, Level1); //濾波器模式 Timer1.setPeriod(100000); //設(shè)置輸出信號脈沖計數(shù)時長1s } //初始化 void setup() { TSC_Init(); Serial.begin(9600); //啟動串行通信 Timer1.initialize(100000); // defaulte is 1s Timer1.attachInterrupt(TSC_Callback); //設(shè)置定時器1的中斷,中斷調(diào)用函數(shù)為TSC_Callback() //設(shè)置TCS3200輸出信號的上跳沿觸發(fā)中斷,中斷調(diào)用函數(shù)為TSC_Count() attachInterrupt(0, TSC_Count, RISING); digitalWrite(LED, HIGH);//點(diǎn)亮LED燈 // delay(1500); //延時4s,以等待被測物體紅、綠、藍(lán)三色在1s內(nèi)的TCS3200輸出信號脈沖計數(shù) //通過白平衡測試,計算得到白色物體RGB值255與1s內(nèi)三色光脈沖數(shù)的RGB比例因子 g_SF[0] = 0.53; //紅色光比例因子 g_SF[1] = 0.65; //綠色光比例因子 g_SF[2] = 0.54; //藍(lán)色光比例因子 //紅、綠、藍(lán)三色光對應(yīng)的1s內(nèi)TCS3200輸出脈沖數(shù)乘以相應(yīng)的比例因子就是RGB標(biāo)準(zhǔn)值 reset(); } //主程序 int Now_Color = 0; //存儲上一次顏色傳感器檢測的數(shù)值 int Last_Color = 0; //存儲當(dāng)前顏色傳感器檢測的數(shù)值 void loop() { Last_Color = Color_Detection(); Now_Color = Color_Detection(); if( Last_Color == Now_Color) //如果兩次檢測的數(shù)值相同 //(這里是為了防止顏色傳感器檢測出錯,所以檢測了兩次) { switch(Now_Color) { case 1: Serial.print("Red"); //如果檢測到的物料為紅色,將物料放到機(jī)械臂的左側(cè) Servo_Left(); Now_Color = 0; Last_Color = 0; break; case 2: Serial.print("Blue");//如果檢測到的物料為藍(lán)色,將物料放到機(jī)械臂的右側(cè) Servo_Right(); Now_Color = 0; Last_Color = 0; break; case 3: Serial.print("NONE");//否則,機(jī)械臂不動作; Serial.println(); Now_Color = 0; Last_Color = 0; break; } } } int Color_Detection() //顏色檢測函數(shù) { int color[3]; g_flag = 0; for(int i=0; i<3; i++) { color[i] = g_array[i] * g_SF[i]; } Serial.println((String)(color[0]) + '+' + (String)(color[1]) + '+' + (String)(color[2]) + '+'); delay(500); if( (color[0] > color[1]) && (color[0] >color[2]) && ( (color[1]+color[2]) return 1; //如果檢測到的顏色為紅色,返回1; } else if( (color[2] > color[1]) && (color[2] >color[0]) ){ return 2; //如果檢測到的顏色為藍(lán)色,返回2; } else { return 3; } //否則,機(jī)械臂不動作; } void reset() //舵機(jī)角度初始化 { for(int i=0;i { myservo[i].attach(servo_pin[i]); myservo[i].write(map(value_init[i],0,180,500,2500)); } } void servo_move(float value0, float value1, float value2) //舵機(jī)轉(zhuǎn)動 { float value_arguments[3] = {value0, value1, value2}; float value_delta[servo_num]; for(int i=0;i { value_delta[i] = (value_arguments[i] - value_init[i]) / f; } for(int i=0;i { for(int k=0;k { value_init[k] = value_delta[k] == 0 ? value_arguments[k] : value_init[k] + value_delta[k]; } for(int j=0;j { myservo[j].write(map(value_init[j],0,180,500,2500)); delay(Servo_Speed); } } } void Servo_Left() //將物料放到機(jī)械臂的左側(cè) { servo_move(Upward_servo_open, Middle_servo_left, Down_servo_middle);//初始化動作 servo_move(Upward_servo_open, Middle_servo_init, Down_servo_middle);//機(jī)械臂下降 servo_move(Upward_servo_close, Middle_servo_init, Down_servo_middle);//機(jī)械爪閉合(抓取貨物) servo_move(Upward_servo_close, Middle_servo_left1, Down_servo_middle);//機(jī)械臂上抬 servo_move(Upward_servo_close, Middle_servo_down, Down_servo_left); //機(jī)械臂下降,機(jī)械底座向左轉(zhuǎn) servo_move(Upward_servo_open, Middle_servo_down, Down_servo_left); //機(jī)械爪張開(釋放貨物) servo_move(Upward_servo_open, Middle_servo_left, Down_servo_middle);//機(jī)械臂回復(fù)到初始角度 } void Servo_Right() //將物料放到機(jī)械臂的右側(cè) { servo_move(Upward_servo_open, Middle_servo_left, Down_servo_middle);//初始化動作 servo_move(Upward_servo_open, Middle_servo_init, Down_servo_middle); servo_move(Upward_servo_close, Middle_servo_init, Down_servo_middle); servo_move(Upward_servo_close, Middle_servo_left1, Down_servo_middle); servo_move(Upward_servo_close, Middle_servo_down, Down_servo_right); servo_move(Upward_servo_open, Middle_servo_down, Down_servo_right); servo_move(Upward_servo_open, Middle_servo_left, Down_servo_middle); } |
審核編輯黃昊宇
-
機(jī)器人
+關(guān)注
關(guān)注
211文章
28476瀏覽量
207396 -
機(jī)械手
+關(guān)注
關(guān)注
7文章
335瀏覽量
29671
發(fā)布評論請先 登錄
相關(guān)推薦
評論