這個(gè)創(chuàng)意是個(gè)舶來(lái)品。記得有個(gè)國(guó)外作者做了一個(gè)基于Arduino和wifi路由器的智能機(jī)器人。
要求有攝像頭,能夠拍攝小車(chē)經(jīng)過(guò)地方的影像。
要求使用Arduino模塊實(shí)現(xiàn)控制。
要求使用PC通過(guò)路由器控制小車(chē)。
實(shí)現(xiàn)這樣的機(jī)器人很難嗎?能不能做一個(gè)簡(jiǎn)化版的?
組件列表
A4WD小車(chē);ROMEO控制板;5節(jié)2300MAH電池;12V電池包;充電器;上海貝爾 RG-100A路由器;中星微301攝像頭 ;兩自由度DF15MG云臺(tái)。
圖1 基于Arduino開(kāi)源平臺(tái)的WiFi視頻監(jiān)控小車(chē)
圖2 Arduino_romeo主控板
圖3 小車(chē)
圖4 云臺(tái)和攝像頭
圖5 攝像頭
源代碼
下面放出ROMEO板的源程序?qū)⑦@個(gè)程序使用Arduino 0022 下載進(jìn)去:
#include
#define EN1 5//控制左側(cè)電機(jī)速度
#define EN2 6//控制右側(cè)電機(jī)速度
#define IN1 4//控制左側(cè)電機(jī)方向
#define IN2 7//控制右側(cè)電機(jī)方向
#define FORW 0//前進(jìn)
#define BACK 1//后退
#define dataLenMax 16 //設(shè)置最大數(shù)據(jù)幀長(zhǎng)度 不大于16
Servo servoX; //云臺(tái)X軸舵機(jī) 左右
Servo servoY; //云臺(tái)Y軸舵機(jī) 上下
//控制電機(jī)轉(zhuǎn)動(dòng)子函數(shù)
void Motor_Control(int M1_DIR,int M1_EN,int M2_DIR,int M2_EN)
{
//////////M1////////////////////////
if(M1_DIR==FORW)//M1電機(jī)的方向
digitalWrite(IN1,LOW); //置高,設(shè)置方向向前
else
digitalWrite(IN1,HIGH);//置低,設(shè)置方向向后
if(M1_EN==0)//M1電機(jī)的速度
analogWrite(EN1,LOW);//置低,停止
else
analogWrite(EN1,M1_EN);//否則,就設(shè)置相應(yīng)的數(shù)值
///////////M2//////////////////////
if(M2_DIR==FORW)//M2電機(jī)的方向
digitalWrite(IN2,LOW);//置高,方向向前
else
digitalWrite(IN2,HIGH);//置低,方向向后
if(M2_EN==0)//M2電機(jī)的速度
analogWrite(EN2,LOW);//置低,停止
else
analogWrite(EN2,M2_EN);//否則,就設(shè)置相應(yīng)的數(shù)值
}
void setup()
{
int i;
for(i=4;i<=7;i++)//設(shè)置控制電機(jī)的各端口為輸出模式
pinMode(i, OUTPUT);
Serial.begin(19200);//設(shè)置波特率為19200bps
servoX.attach(10);
servoY.attach(11);
}
///////////////////UART通訊命令字宏定義///////////////////////////////////////////
#define UART_START0 0X55 //通訊數(shù)據(jù)幀頭
#define UART_START1 0XAA //通訊數(shù)據(jù)幀頭
#define UART_END 0X0A //返回?cái)?shù)據(jù)包結(jié)束標(biāo)志
////////////////////////// 命令字定義/////////////////////////////////////////////////////
// 波特率 57600BPS,無(wú)奇偶效驗(yàn),一位停止位。文中的數(shù)字都是8位的十六進(jìn)制數(shù) /////
///////////////////////////////////2路舵機(jī)控制/////////////////////////////////////////////
//本指令可同時(shí)控制6路舵機(jī),每路可單獨(dú)控制位置和速度。
//字頭 楨長(zhǎng)度 命令字 S1位置 S1速度 S2位置 S2速度 校驗(yàn)和
//55 aa 4 01
//"S1位置,s2位置"為2個(gè)舵機(jī)的角度值,范圍為0~180,90為中位。
//"S1速度,s2速度"為運(yùn)動(dòng)的速度值,spd越高,運(yùn)動(dòng)速度越快,范圍為0~0xff。
//返回值:
//字頭 楨長(zhǎng)度 命令字 應(yīng)答標(biāo)志 校驗(yàn)和
//55 aa 01 01 S SUM
//返回操作標(biāo)志。設(shè)置成功S返回0X01,失敗無(wú)返回。
//////////////////////////////////////////////////////////////////////////////////////////////
#define RC_MOTO_SET 0X01 // 2路舵機(jī)控制
////////////////////////////////2路電機(jī)調(diào)速控制////////////////////////////////////////////////
//本指令可同時(shí)控制2路直流電機(jī)速度。(機(jī)器人頭超前方,人面對(duì)機(jī)器人后方)
//字頭 楨長(zhǎng)度 命令字 左電機(jī) 右電機(jī) 校驗(yàn)和
//55 aa 2 02 S1 S2 SUM
//S1,S2分別代表2個(gè)電機(jī)的PWM輸出占空比。0x80代表電機(jī)停止,0x00代表正轉(zhuǎn)最大速度(100%占空比,機(jī)器人向前),0xff代表反轉(zhuǎn)最大速度(100%占空比機(jī)器人向后)。
//返回值:
//字頭 楨長(zhǎng)度 命令字 應(yīng)答標(biāo)志 校驗(yàn)和
//55 aa 01 02 S SUM
//返回操作標(biāo)志。設(shè)置成功S返回0X01,失敗無(wú)返回。
///////////////////////////////////////////////////////////////////////////////////////////////////////////////
#define MOTO_SET 0X02 //2路電機(jī)調(diào)速控制
void loop()
{
//定義變量
int dataLen = 0; //數(shù)據(jù)長(zhǎng)度
int start_flag = 0; //數(shù)據(jù)幀起始標(biāo)志
int data_index = 0; //數(shù)據(jù)幀索引
int com_index = 0; //命令索引
int temp_char1 = 0; //接收暫存器1
int temp_char0 = 0; //接收暫存器1
int i,x,y; //變量
int state = 0; //接收數(shù)據(jù)幀狀態(tài) 1代表有數(shù)據(jù)幀,0代表沒(méi)有接收到數(shù)據(jù)幀
int SUM; //校驗(yàn)和
int RxData[32]; //數(shù)據(jù)存儲(chǔ)寄存器
int Serial_flag;
int Moto1S,Moto2S; //電機(jī)1.2 速度控制暫存
int Moto1D,Moto2D; //電機(jī)1.2 方向控制暫存
while(1)
{
temp_char1 = Serial.read(); //讀取串口數(shù)據(jù)
if(temp_char1!=-1) //有數(shù)據(jù)接收到
{
Serial_flag=1;
if(start_flag == 0) // 判斷 是否有 0X55 0XAA 數(shù)據(jù)幀頭
{
if( temp_char1 == UART_START1)
{
if(temp_char0 == UART_START0)
{
start_flag = 1;
RxData[0]=UART_START0;
RxData[1]=UART_START1;
data_index = 0;
com_index = 0;
}
}
else temp_char0 = temp_char1;
}
else if( com_index < 2)
{
switch(com_index)
{
case 0 : RxData[2] = temp_char1; //數(shù)據(jù)長(zhǎng)度
dataLen = temp_char1;
break;
case 1 : RxData[3] = temp_char1; //命令字
break;
}
com_index++;
}
else if((data_index < dataLen) && (dataLen < dataLenMax)) //接收數(shù)據(jù),同時(shí)數(shù)據(jù)不大于最大數(shù)據(jù)長(zhǎng)度
{
RxData[data_index+4] = temp_char1;
data_index ++;
}
else
{
RxData[data_index+4] = temp_char1;
state = 1;
start_flag = 0;
}
}
if(state == 1) //如果有數(shù)據(jù)幀接收到
{
SUM = 0;
for(i=0; i
SUM%=256;
if(SUM == RxData[dataLen+4]) //如果校驗(yàn)和正確 解析命令
{
if(RxData[3] == RC_MOTO_SET) //舵機(jī)云臺(tái)控制命令
{
if(RxData[4]>=150) x=150;
else if(RxData [4]<=30) x=30;
else x = RxData[4];
if(RxData[6]>=150) y=150;
else if(RxData[6]<=30) y=30;
else y = RxData[6];
servoX.write(x);
servoY.write(y);
state = 0;
}
else if(RxData[3] == MOTO_SET) //電機(jī)控制命令
{
///////////////////電機(jī)1控制量變換/////////////////////////////
if(RxData[4] == 0X80) Moto1S = 0;
else if(RxData[4] < 0X80) //小于0X80的控制數(shù)據(jù) 代表正轉(zhuǎn)
{
Moto1D = FORW; //正轉(zhuǎn)
Moto1S = 0xff - RxData[4]*2; //將0X00最大速度 到0X7F 最小速度,轉(zhuǎn)換為0最小到255最大速度的值
}
else //大于0X80的控制數(shù)據(jù) 代表反轉(zhuǎn)
{
Moto1D = BACK; //反轉(zhuǎn)
Moto1S = (RxData[4] - 0X80)*2; //將0XFF最大速度 到0X81 最小速度,轉(zhuǎn)換為0最小到254最大速度的值
}
///////////////////電機(jī)2控制量變換/////////////////////////////
if(RxData[5] == 0X80) Moto2S = 0;
else if(RxData[5] < 0X80) //小于0X80的控制數(shù)據(jù) 代表正轉(zhuǎn)
{
Moto2D = FORW; //正轉(zhuǎn)
Moto2S = 0xff - RxData[5]*2; //將0X00最大速度 到0X7F 最小速度,轉(zhuǎn)換為0最小到255最大速度的值
}
else //大于0X80的控制數(shù)據(jù) 代表反轉(zhuǎn)
{
Moto2D = BACK; //反轉(zhuǎn)
Moto2S = (RxData[5] - 0X80)*2; //將0XFF最大速度 到0X81 最小速度,轉(zhuǎn)換為0最小到254最大速度的值
}
Motor_Control(Moto1D,Moto1S,Moto2D,Moto2S);//電機(jī)速度及其方向控制
state = 0;
}
}
}
}
}
程序使用了一種幀結(jié)構(gòu) 每個(gè)數(shù)據(jù)命令都是 55 AA開(kāi)頭,最后一個(gè)字節(jié)有一個(gè)簡(jiǎn)單的校驗(yàn)和。這樣是為了防止路由器發(fā)出錯(cuò)誤數(shù)據(jù)干擾小車(chē)。因?yàn)閾?jù)我觀察,路由器在啟動(dòng)的時(shí)候會(huì)發(fā)出一大堆字符。如果協(xié)議太簡(jiǎn)單小車(chē)可能會(huì)讀取到錯(cuò)誤數(shù)據(jù)亂動(dòng)作。
程序做了小車(chē)速度控制,及其兩個(gè)云臺(tái)舵機(jī)控制在里面。云臺(tái)X軸舵機(jī)接數(shù)字10口,Y軸舵機(jī)接11口。其他功能可以在上面增加。此時(shí)下載好程序后可以通過(guò) JoystickInterface 這個(gè)軟件用USB線連接測(cè)試一下小車(chē)是否能夠可靠運(yùn)行。
如果USB線能控制,將路由器的串口線接在ROMEO的串口,對(duì)應(yīng)關(guān)系為 路由器G接ROMEO板GND,T接RX,R接TX。注意接線最好都斷電操作。
修改控制按鍵鍵值,下面是一些控制代碼,將鍵抬起設(shè)置為停止這樣就可以在無(wú)按鍵的時(shí)候小車(chē)自動(dòng)停止。
停止 55AA0202808003
100% 速度前進(jìn) 55AA0202000003
100% 速度后退 55AA0202FFFF01
100% 速度左轉(zhuǎn) 55AA0202FF0002
100% 速度右轉(zhuǎn) 55AA020200FF02
直至Wifi監(jiān)控小車(chē)就算基本功能實(shí)現(xiàn)完畢。后面還有很多功能可以試試,比如通過(guò)以太網(wǎng)遠(yuǎn)程遙控。加一些傳感器,車(chē)燈什么的。可以發(fā)揮的空間很大。
相關(guān)問(wèn)題
Q:什么是Wifi Robot無(wú)線遠(yuǎn)程智能遙控小車(chē)?
A:Wifi Robot無(wú)線遠(yuǎn)程智能遙控小車(chē)就是利用非常成熟的WIFI無(wú)線網(wǎng)絡(luò)為數(shù)據(jù)載體,實(shí)現(xiàn)控制數(shù)據(jù),音視頻雙向數(shù)據(jù)交換而達(dá)到控制小車(chē)和視頻監(jiān)控等等功能。
Q:Wifi Robot無(wú)線遠(yuǎn)程智能遙控小車(chē)有什么功能?
A:Wifi Robot無(wú)線遠(yuǎn)程智能遙控小車(chē)是集無(wú)線通訊、實(shí)時(shí)四驅(qū)、多向機(jī)械云臺(tái)、視頻監(jiān)控、電器紅外遙控、環(huán)境溫度檢測(cè)、為一體的多功能智能遙控車(chē)。
Q:Wifi Robot無(wú)線遠(yuǎn)程智能遙控小車(chē)用在什么地方?
A:Wifi Robot無(wú)線遠(yuǎn)程智能遙控小車(chē)可以放在公司作為產(chǎn)品演示的高級(jí)智能助手,幫你遞送文件,幫你拿聽(tīng)百威,幫你拿盒萬(wàn)寶路,又或者向你的客戶打聲招呼。
Wifi Robot無(wú)線遠(yuǎn)程智能遙控小車(chē)可以放在家里當(dāng)做一貼切保姆,你可以在公司用電腦監(jiān)控家里的的一切動(dòng)態(tài),可以在車(chē)上就設(shè)定好家里空調(diào)溫度,可以定時(shí)電視機(jī)在什么時(shí)候換什么臺(tái),這一切你只需要連接到ITELNET。
Wifi Robot無(wú)線遠(yuǎn)程智能遙控小車(chē)也是廣場(chǎng)上的明星,你帶著他在城市廣場(chǎng)上炫耀,玩耍,讓它拿個(gè)小禮物送心儀的MM,讓他幫你丟垃圾,這一切都不是問(wèn)題。
評(píng)論