SKU:RB-13K004 路虎5尋線避障履帶機(jī)器人
來(lái)自ALSROBOT WiKi
目錄 |
產(chǎn)品概述
2014最新推出Arduino路虎5越野履帶機(jī)器人根據(jù)歷年大學(xué)生電子大賽控制專題所設(shè)計(jì),支撐板基板外形汲取了變形金剛擎天圖案特色,采用2.5mm厚黑色亮光壓克力材料加工,重量輕、不易碎、不導(dǎo)電、美觀大方等優(yōu)點(diǎn)。下層基板可以安裝雙H橋直流電機(jī)驅(qū)動(dòng)板、Mini紅外避障傳感器、RB URF v1.1超聲波傳感器、GP2D12紅外測(cè)距傳感器、火焰?zhèn)鞲衅鳌⒐饩€傳感器、RB-421二自由度云臺(tái)、MG995單自由度云臺(tái)、AS-5DOF鋁合金機(jī)械臂與電子積木等,并設(shè)計(jì)了電源開關(guān)與充電接口固定孔,可不用取出充電電池就可完成充電,方便玩友調(diào)試機(jī)器人。上層基板可以安裝Arduino UNO控制器、Arduino mega1280控制器、Robotboard v1.2 51單片機(jī)控制器,若要搭載更多電子設(shè)備可以再增加基板,真正實(shí)現(xiàn)人性化設(shè)計(jì)理念。
產(chǎn)品參數(shù)
- 產(chǎn)品名稱:路虎5尋線避障履帶機(jī)器人
- 產(chǎn)品類型:履帶型移動(dòng)平臺(tái)
- 產(chǎn)品貨號(hào):RB - 13K004
- 編程軟件:Arduino IDE
- 基礎(chǔ)模塊:路虎5履帶平臺(tái)、Mini 紅外尋線傳感器、Mini 紅外避障傳感器、尋線避障傳感器固定支架
- 尋線探測(cè)距離:1cm - 4cm 可調(diào)
- 避障探測(cè)距離:3cm - 35cm 可調(diào)
- 控制方式:自主編程
- 重量:1.395kg
配件技術(shù)參數(shù)
路虎 5 底盤參數(shù)
- 電機(jī)電壓:7.2 V
- 工作電流:300 mA–2.5 A
- 電機(jī)輸出最大扭矩:10 Kg*cm
- 減速比例:86.8:1
- 爬坡能力:> 30°
- 行駛速度:1 Km/hr
- 尺寸:245 mm×225 mm×74 mm
- 上層基板尺寸:146 mm×194 mm
- 下層基板尺寸:130 mm×96 mm
- 基板厚度:2.5 mm
- 路虎 5 底盤資料
注:路虎 5 履帶機(jī)器人底盤均由廠家裝配好,此部分無(wú)須客戶自己組裝,上、下基板需要客戶自行根據(jù)搭載設(shè)備安裝。詳情請(qǐng)參考我們淘寶店里 Arduino 越野履帶機(jī)器人平臺(tái)路虎5底盤電子大賽推薦。
支撐板尺寸
產(chǎn)品清單
RB - 13K004 路虎5尋線避障履帶機(jī)器人 | |||
序號(hào) | 產(chǎn)品名稱 | 產(chǎn)品貨號(hào) | 數(shù)量 |
1 | 路虎5履帶底盤(無(wú)碼盤) | RB - 13K001 | 1 |
2 | 底盤支撐板套件 | RB - 13K040 | 1 |
3 | 電源充電接口開關(guān)套件 | RB - 06L012 | 1 |
4 | Starduino UNO R3 控制器 | RB - 01C076A | 1 |
5 | Arduino 傳感器擴(kuò)展板 V5.0 | RB - 01C015B | 1 |
6 | 雙 H 橋直流電機(jī)驅(qū)動(dòng)板 | RB - 01C025 | 1 |
7 | Mini 紅外尋線傳感器 | RB - 02S002A | 3 |
8 | Mini 紅外避障傳感器 | RB - 02S003A | 3 |
9 | 光電傳感器固定支架套件 | RB - 09M110 | 1 |
10 | 3P通用傳感器連接線 | RB - 06L003 | 2 |
11 | 單頭防插反3P連接線 | RB - 12C229 | 6 |
12 | M3 * 6 + 10 銅柱 | RB - 12C072 | 7 |
13 | M3 * 6 + 40 銅柱 | RB - 12C078 | 4 |
14 | M3 * 6 + 50 銅柱 | RB - 12C079 | 2 |
15 | 十字槽螺絲 M3 * 6 | RB - 12C081 | 7 |
16 | 六角螺母 M3 | RB - 12C089 | 7 |
17 | Arduino 供電線 | 贈(zèng)送 | 2 |
18 | 抗干擾 USB 連接線 | RB - 06L020 | 1 |
安裝步驟
步驟1:充電接口撥動(dòng)開關(guān)連接線制作
步驟2:雙H橋驅(qū)動(dòng)板安裝
步驟3:充電接口、撥動(dòng)開關(guān)安裝
步驟4:避障傳感器安裝
步驟5:傳感器支撐板安裝
步驟6:尋線傳感器安裝
步驟7:Carduino UNO 控制器安裝
步驟8:V5.0傳感器擴(kuò)展板安裝
步驟9:支撐板中板安裝
步驟10:支撐板上板安裝
安裝完成效果
例子程序
硬件接線
- 右側(cè)尋線傳感器接Carduino UNO控制器D2引腳
- 中間尋線傳感器接Carduino UNO控制器D3引腳
- 左側(cè)尋線傳感器接Carduino UNO控制器D4引腳
- 右側(cè)避障傳感器接Carduino UNO控制器A1引腳
- 中間避障傳感器接Carduino UNO控制器D11引腳
- 左側(cè)避障傳感器接Carduino UNO控制器D12引腳
- 雙H橋驅(qū)動(dòng)板EA接Carduino UNO控制器D10引腳
- 雙H橋驅(qū)動(dòng)板EB接Carduino UNO控制器D5引腳
- 雙H橋驅(qū)動(dòng)板I2接Carduino UNO控制器D9引腳
- 雙H橋驅(qū)動(dòng)板I1接Carduino UNO控制器D8引腳
- 雙H橋驅(qū)動(dòng)板I3接Carduino UNO控制器D7引腳
- 雙H橋驅(qū)動(dòng)板I4接Carduino UNO控制器D6引腳
程序代碼
void setup() { pinMode(8,OUTPUT);//定義輸入、輸出接口 pinMode(9,OUTPUT); pinMode(10,OUTPUT); pinMode(5,OUTPUT); pinMode(6,OUTPUT); pinMode(7,OUTPUT); pinMode(11,INPUT); pinMode(12,INPUT); pinMode(14,INPUT); pinMode(2,INPUT); pinMode(3,INPUT); pinMode(4,INPUT); } void qianjin()//前進(jìn) { digitalWrite(10,300);//輸入數(shù)字量進(jìn)行設(shè)定速度 digitalWrite(5,300); digitalWrite(9,HIGH);//使直流電機(jī)(右)順時(shí)針轉(zhuǎn) digitalWrite(8,LOW); digitalWrite(7,HIGH);//使直流電機(jī)(左)逆時(shí)針轉(zhuǎn) digitalWrite(6,LOW); } void youzhuan()//右轉(zhuǎn) { digitalWrite(10,100);//輸入數(shù)字量進(jìn)行設(shè)定速度 digitalWrite(5,100); digitalWrite(6,LOW);//使直流電機(jī)(右)逆時(shí)針轉(zhuǎn) digitalWrite(7,HIGH); digitalWrite(8,HIGH);//使直流電機(jī)(左)逆時(shí)針轉(zhuǎn) digitalWrite(9,LOW); } void zuozhuan()//左轉(zhuǎn) { digitalWrite(10,100);//輸入數(shù)字量進(jìn)行設(shè)定速度 digitalWrite(5,100); digitalWrite(6,HIGH);//使直流電機(jī)(右)順時(shí)針轉(zhuǎn) digitalWrite(7,LOW); digitalWrite(8,LOW);//使直流電機(jī)(左)順時(shí)針轉(zhuǎn) digitalWrite(9,HIGH); } void tingzhi()//停止 { digitalWrite(6,HIGH);//使直流電機(jī)(右)制動(dòng) digitalWrite(7,HIGH); digitalWrite(8,HIGH);//使直流電機(jī)(左)制動(dòng) digitalWrite(9,HIGH); } void houtui(int a) { analogWrite(10,a);//輸入模擬值進(jìn)行設(shè)定速度 analogWrite(5,a); digitalWrite(6,HIGH);//使直流電機(jī)(右)逆時(shí)針轉(zhuǎn) digitalWrite(7,LOW); digitalWrite(9,LOW);//使直流電機(jī)(左)順時(shí)針轉(zhuǎn) digitalWrite(8,HIGH); } void loop() { int r,m,l;//定義尋線傳感器接口 r=digitalRead(2);//定義右側(cè)尋線接口 m=digitalRead(3);//定義中間尋線接口 l=digitalRead(4);//定義左側(cè)尋線接口 int r1,m1,l1;//定義避障傳感器接口 r1=digitalRead(14);//定義右側(cè)避障接口 m1=digitalRead(12);//定義中間避障接口 l1=digitalRead(11);//定義左側(cè)避障接口 if(l==LOW || m==LOW || r==LOW)//判斷是否有黑線 有則繼續(xù) { if(l==LOW && m==LOW && r==LOW) qianjin(); if(l==HIGH && m==LOW && r==HIGH) qianjin(); if(l==HIGH && m==LOW && r==LOW) { youzhuan(); delay(400); tingzhi(); delay(80); } if(l==LOW && m==LOW && r==HIGH) { zuozhuan(); delay(400); tingzhi(); delay(80); } if(l==HIGH && m==HIGH && r==LOW) { youzhuan(); delay(400); tingzhi(); delay(80); } if(l==LOW && m==HIGH && r==HIGH) { zuozhuan(); delay(400); tingzhi(); delay(80); } } if(l==HIGH && m==HIGH && r==HIGH)//判斷是否有障礙 有則繼續(xù) { if(l1==HIGH && m1==HIGH && r1==HIGH) qianjin(); if(l1==HIGH && m1==LOW && r1==HIGH) { houtui(200); delay(400); zuozhuan(); delay(300); } if(l1==HIGH && m1==HIGH && r1==LOW) zuozhuan(); if(l1==LOW && m1==HIGH && r1==HIGH) youzhuan(); if(l1==HIGH && m1==LOW && r1==LOW) zuozhuan(); if(l1==LOW && m1==LOW && r1==HIGH) youzhuan(); if(l1==LOW && m1==LOW && r1==LOW) { houtui(200); delay(400); zuozhuan(); delay(300); } } }
視頻演示
相關(guān)資料
- 產(chǎn)品資料
下載鏈接:https://pan.baidu.com/s/1zNZGGpsX-P3gkcqJi6GZ7w 提取碼:ri9m
- 產(chǎn)品購(gòu)買鏈接: