(RB-13K032)4WD越野移動小車平臺
來自ALSROBOT WiKi
目錄 |
產品概述
2014年最新推出的AS-4WD鋁合金超大越野輪式移動機器人平臺是哈爾濱奧松機器人科技有限公司汲取多款移動機器人平臺優(yōu)點于一體,并結合中國機器人大賽暨Robocup公開賽規(guī)則以及Arduino互動教學課程要求,自主研發(fā)的全鋁合金4輪驅動移動機器人平臺。此款平臺可搭載多款控制器、驅動器、傳感器和無線射頻模塊等,平臺上支撐板設有51單片機控制器、Arduino mega168控制器、Arduino mega328控制器、Arduino MEGA1280控制器、32路舵機控制器固定孔,二自由度舵機云臺固定槽、碰撞開關安裝孔,除此之外,前端板可安裝紅外避障傳感器、紅外測距傳感器、光線傳感器、超聲波傳感器、超亮發(fā)光燈等。平臺主體采用硬質鋁合金材料,此種材料具有重量輕、強度高、不變形等特點。再加上獨特的外形設計與色彩搭配,給人以炫酷的感覺。
由于近年來機器人比賽多為競技對抗類,所以多款顏色選擇,可讓您按顏色分隊,場地上方懸掛攝像頭,可以進行圖像識別與圖像追蹤應用。平臺動力輸出類型為四輪驅動,特設常用多款直流減速電機固定孔,可依據(jù)個人喜好更換電機與輪胎,使機器人輕松完成越障、爬坡等高性能測試。平臺輪胎采用超大越野彈性橡膠,具有減震、耐磨、抓地力強等優(yōu)點,能適應光滑路面和崎嶇路面。這款平臺非常適合Arduino愛好者、各大中小學開展機器人普及教育使用,更適合學生用其參加全國大學生電子大賽、智能車競賽、足球機器人等比賽。讓你輕松感受機器人DIY無限樂趣!
配件清單
規(guī)格參數(shù)
- 車輪直徑:120mm
- 車輪寬度:60mm
- 平臺長度:195mm(車身長度:270mm)
- 平臺寬度:142mm(車身寬度:280mm)
- 平臺高度:120mm
- 平臺重量:1280g
- 底盤距地面距離:26mm
- 電機額定電壓:12VDC
- 電機空載轉速:120轉/分
- 電機額定轉速:108轉/分
- 電機齒輪箱長度:19mm
- 電機額定電流:0.37A
- 電機額定轉矩:26.8mN.m
- 電機最大轉矩:55.3mN.m
應用例程
主要設備
- Arduino 控制器×1
- Arduino 傳感器擴展板V5.0×1
- RB-421 舵機×1
- 超聲波模塊×1
- 超聲波支架×1
- 雙H 橋驅動板×1
- 鋰電池×1
- 4WD越野移動小車平臺×1 套
接線說明
- 數(shù)字口2→接超聲波
- 數(shù)字口10→接RB-421 舵機
- 數(shù)字口5→接雙H 橋驅動板的EB
- 數(shù)字口6→接雙H 橋驅動板的I4
- 數(shù)字口7→接雙H 橋驅動板的I3
- 數(shù)字口8→接雙H 橋驅動板的I1
- 數(shù)字口9→接雙H 橋驅動板的I2
- 數(shù)字口11→接雙H 橋驅動板的EA
接線圖
示例程序
#include <Servo.h> Servo myservo; int duration; //定義變量duration 用來存儲脈沖 int distance; //定義變量distance 用來存儲距離值 int srfPin = 2; //定義srfPin 為數(shù)字口2 int z; //定義變量Z int val; //定義變量val int val1; //定義變量val1 int val2; //定義變量val2 void setup() { myservo.attach(10); //10 號引腳輸出舵機控制信號 Serial.begin(9600); //僅能使用9、10 號引腳 pinMode(8,OUTPUT); //定義I3 接口 pinMode(9,OUTPUT); //定義I4 接口 pinMode(11,OUTPUT); //定義EB(PWM 調速)接口 pinMode(5,OUTPUT); //定義EA(PWM 調速)接口 pinMode(6,OUTPUT); //定義I2 接口 pinMode(7,OUTPUT); //定義I1 接口 pinMode(srfPin,OUTPUT); //定義srfPin 為輸出接口 myservo.write(90); //使舵機轉到90 度 } void loop() { delay(20); //延時20 毫秒 Goahead(); //調用前進子程序 val=Ultrasonic(z); //將超聲波讀取的距離值賦值給val if(val<25) //判斷如果val 小于25 則繼續(xù)執(zhí)行 { Stop(); //調用停止子程序 myservo.write(7); //讓舵機轉0 度 delay(1000); //延時1 秒等待舵機到達指定位置 val1=Ultrasonic(z); //將超聲波讀取的距離值賦值給val1 delay(1000); //延時1 秒等待舵機到達指定位置 myservo.write(174); //讓舵機轉180 度 delay(1000); //延時1 秒等待舵機到達指定位置 val2=Ultrasonic(z); //將超聲波讀取的距離值賦值給val2 delay(1000); //延時1 秒等待舵機到達指定位置 myservo.write(90); //讓舵機轉90 度 delay(1000); //延時1 秒 if(val1<val2) { Turn_left(); //調用左轉子程序 delay(200); //延時200 毫秒 } else { Turn_right(); //調用右轉子程序 delay(200); //延時200 毫秒 } delay(500); //延時500 毫秒 } } int Ultrasonic(int distance) { digitalWrite(srfPin, LOW); //高電平觸發(fā)前發(fā)送2 微秒的低電平 delayMicroseconds(2); digitalWrite(srfPin, HIGH); //發(fā)送10 微秒的高電平開始檢測 delayMicroseconds(10); digitalWrite(srfPin, LOW); //等待脈沖返回前發(fā)送一個低電平 pinMode(srfPin, INPUT); duration = pulseIn(srfPin, HIGH); //從URF02 讀取脈沖 distance = duration/58; //除以58 得到距離值 return distance; } void Goahead()//前進 { analogWrite(5,145); //輸入模擬值進行設定速度 digitalWrite(6,HIGH); //使直流電機(左)順時針轉 digitalWrite(7,LOW); analogWrite(11,160); //輸入模擬值進行設定速度 digitalWrite(8,HIGH); //使直流電機(右)逆時針轉 digitalWrite(9,LOW); } void Stop()//停止 { digitalWrite(6,HIGH); //使直流電機(左)制動 digitalWrite(7,HIGH); digitalWrite(8,HIGH); //使直流電機(右)制動 digitalWrite(9,HIGH); } void Turn_right()//右轉 { analogWrite(5,165); //輸入模擬值進行設定速度 digitalWrite(6,LOW); //使直流電機(左)逆時針轉 digitalWrite(7,HIGH); analogWrite(11,140); //輸入模擬值進行設定速度 digitalWrite(8,HIGH); //使直流電機(右)逆時針轉 digitalWrite(9,LOW); } void Turn_left()//左轉 { analogWrite(5,165); //輸入模擬值進行設定速度 digitalWrite(6,HIGH); //使直流電機(左)逆時針轉 digitalWrite(7,LOW); analogWrite(11,160); //輸入模擬值進行設定速度 digitalWrite(8,LOW); //使直流電機(右)順時針轉 digitalWrite(9,HIGH); }
產品相關推薦
購買地址:4WD越野移動小車平臺