SKU:RB-13K049 AS-4WD語(yǔ)音識(shí)別操控移動(dòng)機(jī)器人
產(chǎn)品概述
AS - 4WD 語(yǔ)音識(shí)別移動(dòng)機(jī)器人語(yǔ)音識(shí)別采用凌陽(yáng)單片機(jī)控制器,它可以學(xué)習(xí)記錄你的聲音,并且跟你實(shí)現(xiàn)人機(jī)對(duì)話,通過(guò)識(shí)別和理解過(guò)程把語(yǔ)音信號(hào)轉(zhuǎn)變?yōu)橄鄳?yīng)的命令,經(jīng)過(guò)無(wú)線藍(lán)牙模塊傳輸給機(jī)器人,從而可以完成前進(jìn)、后退、左轉(zhuǎn)、右轉(zhuǎn)、測(cè)距播報(bào)等功能,實(shí)現(xiàn)人機(jī)互動(dòng)。
產(chǎn)品參數(shù)
- 產(chǎn)品名稱:AS - 4WD 語(yǔ)音識(shí)別操控移動(dòng)平臺(tái)
- 產(chǎn)品類型:輪式移動(dòng)機(jī)器人
- 產(chǎn)品貨號(hào):RB - 13K049
- 編程軟件:Arduino IDE
- 基礎(chǔ)模塊:凌陽(yáng)61、藍(lán)牙模塊、Carduino UNO R3、傳感器擴(kuò)展板 V5.0、雙 H 橋電機(jī)驅(qū)動(dòng)板
- 控制方式:語(yǔ)音操控
- 操控距離:5 m - 8 m
- 產(chǎn)品尺寸:215 * 200 * 120 mm
- 產(chǎn)品重量:1.5 kg
配件技術(shù)參數(shù)
移動(dòng)平臺(tái)參數(shù)
- 平臺(tái)長(zhǎng)度:206mm
- 平臺(tái)寬度:200mm
- 平臺(tái)高度:65mm
- 平臺(tái)重量:620g
平臺(tái)尺寸圖
直流減速電機(jī)(1:48)
- 驅(qū)動(dòng)電機(jī)齒輪箱減速比:1:48
- 額定轉(zhuǎn)速(6V):270±10 rpm
- 額定轉(zhuǎn)速(7.4V):340±10 rpm
- 額定電流(6V):180±10 mA
- 額定電流(7.4V):200±10 mA
- 最大扭矩(6V):大于等于 0.095 Nm
- 最大扭矩(7.4V):0.11 Nm
- 堵轉(zhuǎn)電流(6V):小于等于1A
- 堵轉(zhuǎn)電流(7.4V):小于等于1.2A
- 尺寸大小:70.50 mm×27.00 mm×23.00 mm(長(zhǎng)×寬×高)
- 重量大?。杭s 30g
電控配件參數(shù)
- 藍(lán)牙模塊
- Starduino UNO R3 控制器
- 傳感器擴(kuò)展板 V5.0
- 雙 H 橋電機(jī)驅(qū)動(dòng)板
- 凌陽(yáng) 61 開(kāi)發(fā)板資料
- RB - 35PG 舵機(jī)資料
配件清單
- 4WD 鋁合金移動(dòng)平臺(tái) * 1套
- 4WD 語(yǔ)音識(shí)別操控移動(dòng)機(jī)器人附件
安裝步驟 - 4WD鋁合金平臺(tái)部分
4wd 鋁合金平臺(tái)內(nèi)部元件詳解(圖片標(biāo)號(hào)對(duì)應(yīng)清單序號(hào))
步驟1:焊接部分
電機(jī)連接線焊接
1、準(zhǔn)備如下圖所示的材料
- 4 * 直流減速電機(jī);
- 4 * 紅色導(dǎo)線(長(zhǎng)度為 15cm);
- 4 * 黑色導(dǎo)線(長(zhǎng)度為 15cm);
- 4 * 扎帶
2、如下圖所示,將紅黑導(dǎo)線焊接到電機(jī)上,并將兩個(gè)電機(jī)連接到一起
3、如下圖所示,分別在兩組電機(jī)上焊接兩條線,為了后續(xù)連接到驅(qū)動(dòng)板使用,再將四個(gè)電機(jī)都捆綁上扎帶后,電機(jī)部分的焊接就完成了
開(kāi)關(guān)接口線焊接
1、準(zhǔn)備如下圖所示的材料
- 充電接口
- 撥動(dòng)開(kāi)關(guān)
- 連接線(紅色 10cm * 1條、紅色 15cm * 1條、黑色 15cm * 1條、紅色 20cm * 1條、黑色 20cm * 1條)、熱縮管、電池盒
2、如圖所示,進(jìn)行連接線的焊接
3、如圖所示,連接充電接口和撥動(dòng)開(kāi)關(guān)
4、如圖所示,使用兩根較短的線連接電池盒
注意:本例中小車的供電使用的電池盒,本電池盒需要使用的是 6 節(jié) 5 號(hào)電池盒,若使用鋰電池,焊接的方式是相同的。
更加詳細(xì)的制作過(guò)程,可以點(diǎn)擊:充電接口及撥動(dòng)開(kāi)關(guān)制作方法
步驟2:側(cè)板電機(jī)安裝
1、準(zhǔn)備如下圖所示的材料:
- 2 * 黃色直流減速電機(jī)
- 1 * 平臺(tái)側(cè)板
- 4 * M3 * 25 螺絲
- 4 * M3 六角螺母
2、如圖所示,將電機(jī)安裝到側(cè)板 實(shí)物安裝圖:
3、進(jìn)行另一側(cè)板電機(jī)的安裝,如圖所示,為兩側(cè)電機(jī)安裝完成效果圖
步驟3:側(cè)板與底板的安裝
1、準(zhǔn)備如下圖所示的材料:
- 2 * 步驟 2 中安裝好的側(cè)板
- 1 * 平臺(tái)底板
- 4 * M3 * 6螺絲
2、按照下圖進(jìn)行安裝 安裝實(shí)物圖:
步驟4:電機(jī)驅(qū)動(dòng)板的安裝
1、準(zhǔn)備如下圖所示的材料:
- 步驟 3 中安裝好的零件
- 1 * 電機(jī)驅(qū)動(dòng)板
- 4 * M3 * 6螺絲
- 4 * M3 螺母
- 4 * M3 * 10 尼龍柱
2、將尼龍柱固定到小車的底板上,位置如下圖所示:
3、安裝雙H橋驅(qū)動(dòng)板,如圖所示:
步驟5:電機(jī)接線
1、如圖所示,將兩側(cè)電機(jī)的紅線連接到電機(jī)驅(qū)動(dòng)板的 A 接口,黑線連接到電機(jī)驅(qū)動(dòng)板的 B 接口
2、安裝完成效果如下圖所示
步驟6:上板充電接口撥動(dòng)開(kāi)關(guān)安裝
1、準(zhǔn)備如下圖所示的材料:
- 步驟 1 中做好的充電接口撥動(dòng)開(kāi)關(guān)連接線
- 平臺(tái)上板
2、安裝完成效果如圖所示
步驟7:控制器的安裝
1、準(zhǔn)備如下圖所示的材料
- 步驟 6 中安裝好的零件
- Carduino UNO 控制器
- 傳感器擴(kuò)展板 V5.0
- 3 * 尼龍柱 M3 * 10
- 3 * M3 螺母
- 3 * M3 * 6 螺絲
2、在小車上支撐板安裝控制器的固定尼龍柱,位置如下圖所示:
3、如圖所示,安裝 Carduino UNO 控制器
4、如圖所示,插入擴(kuò)展板
擴(kuò)展板插入效果圖:
步驟8:電控部分接線
1、準(zhǔn)備如下圖所示的材料
- 2 * 3P 傳感器連接線
- 供電線,紅色黑色各一條 * 20cm
- 平臺(tái)車體
- 平臺(tái)上板
2、如圖所示為雙H橋驅(qū)動(dòng)板和 Carduino UNO 控制器的接線順序
(1) 雙H橋驅(qū)動(dòng)板端接線順序
- 黃色 EA、紅色 I2、黑色 I1
- 黃色 EB、紅色 I4、黑色 I1
(2)傳感器擴(kuò)展板端接線順序
- EA - D5、I2 - D6、I1 - D7
- EB - D11、I4 - D10、I3 - D9
(3)完成效果如下圖所示,為了布線看起來(lái)更加整齊,我們將 3P 線從小車上板的孔穿出
3、供電部分連接
(1)如圖所示為雙H橋驅(qū)動(dòng)板部分供電線連接,充電接口紅色導(dǎo)線接到 VMS,黑色導(dǎo)線接到 GND;將雙 H 橋驅(qū)動(dòng)板輸出的 5v 電源連接到 V5.0 擴(kuò)展板的紅色端子,連接時(shí)注意正負(fù)極不要接錯(cuò);
(2)如圖所示為傳感器擴(kuò)展板 V5.0 供電線連接
步驟9:舵機(jī)安裝
1、準(zhǔn)備如下圖所示的材料:
- 1 * 35PG 舵機(jī)
- 1 * 小車車體
- 1 * M4 * 8 螺絲套裝
2、按照下圖進(jìn)行安裝 安裝實(shí)物圖:
3、舵機(jī)接線
語(yǔ)音小車的舵機(jī)起到的是支撐超聲波傳感器作用,所以不需要連接到 Arduino 的接口上。接線懸空即可
步驟10:超聲波傳感器支架安裝
1、準(zhǔn)備如下圖所示的材料:
- 1 * 超聲波傳感器支架
- 1 * 圓形舵盤(pán)
- 1 * 黑色自攻釘(大)
- 4 * 黑色自攻釘(?。?
2、按照下圖給超聲波傳感器支架分別安裝橡膠套圈、圓形舵盤(pán) 安裝實(shí)物圖:
3、如圖所示,將超聲波支架連接到舵機(jī)軸,注意在連接舵機(jī)和超聲波支架的時(shí)候,盡量不要轉(zhuǎn)動(dòng)舵機(jī),使舵機(jī)仍然保持在中間位置上
步驟11:超聲波傳感器安裝
1、準(zhǔn)備如下圖所示的材料:
- 1 * 安裝好的車體
- 1 * 超聲波傳感器
- 2 * M3 * 10 尼龍柱
- 2 * M3 螺母
- 2 * M3 * 6 螺絲
2、如下圖所示,首先將超聲波傳感器調(diào)節(jié)到模式 1
3、在下圖所示位置安裝尼龍柱用來(lái)固定超聲波傳感器,并將 4P 線從超聲波支架較小的孔中穿出
4、如圖所示,安裝超聲波傳感器,由于例程中使用的是單模式,超聲波傳感器只需連接 input 引腳,所以我們將 4P 線中的黃色線取掉
步驟12:傳感器接線
如圖所示,將超聲波傳感器連接到傳感器擴(kuò)展板 V5.0
注意:4WD 語(yǔ)音識(shí)別小車中的舵機(jī),不需要連接任何接口,只是起到了固定超聲波傳感器的作用。
步驟13:4WD 平臺(tái)上板安裝
1、準(zhǔn)備如下圖所示的材料:
- 未固定上板的車體
- 4 * M3 * 6螺絲
2、在圖中圓圈位置安裝 4 個(gè) M3 * 6 螺絲來(lái)固定小車上板
步驟14:4WD 平臺(tái)端板安裝
1、準(zhǔn)備如下圖所示的材料:
- 步驟 13 中安裝好的車體
- 2 * 小車端板
- 8 * M3 * 6 螺絲
2、如圖所示,將端板與車體進(jìn)行固定
步驟15:4WD 平臺(tái)車輪安裝
1、準(zhǔn)備如下圖所示的材料:
- 步驟 14 中安裝好的車體
- 4 * 車輪
2、如圖所示,將車輪與車體安裝在一起
步驟16:插接藍(lán)牙模塊
1、準(zhǔn)備如下圖所示的材料:
- 1 * 藍(lán)牙模塊
- 步驟 15 中安裝好的小車平臺(tái)整體
2、將藍(lán)牙模塊插接到傳感器擴(kuò)展板的藍(lán)牙接口上,如圖所示
安裝步驟 - 語(yǔ)音操控部分
1、準(zhǔn)備如下產(chǎn)品
- 凌陽(yáng)開(kāi)發(fā)板 * 1套
- 藍(lán)牙模塊 * 1個(gè)(模式:主)
注:如果不知道如何配置藍(lán)牙模塊主從模式,可以參考:藍(lán)牙模塊說(shuō)明書(shū)
- 10P 杜邦線 * 1組
2、凌陽(yáng)61實(shí)驗(yàn)板部分接線
- 如圖所示,連接電池盒凌陽(yáng)實(shí)驗(yàn)板
3、語(yǔ)音訓(xùn)練
按一下KEY3 鍵開(kāi)始按照語(yǔ)音提示進(jìn)行語(yǔ)音訓(xùn)練。
訓(xùn)練采用應(yīng)答形式,每條指令訓(xùn)練兩次,每條命令的訓(xùn)練方法是相同的,以第一條命令“前進(jìn)”為例說(shuō)明:
第一步:控制器提示“前進(jìn)”
第二步:我們對(duì)著話筒說(shuō)“前進(jìn)”
第三步:語(yǔ)音控制器提示“再說(shuō)一遍”
第四步:我們?cè)俅螌?duì)著話筒說(shuō)“前進(jìn)”
到此第一條命令訓(xùn)練完畢。如果訓(xùn)練成功控制器會(huì)自動(dòng)進(jìn)入下一條命令的訓(xùn)練,如果環(huán)境很吵或前后你說(shuō)的話偏差太大,控制器會(huì)提示“沒(méi)有聲音”或者“沒(méi)有聽(tīng)清”這樣這條命令就會(huì)從新訓(xùn)練。當(dāng)所有的命令訓(xùn)練完畢,控制器會(huì)提示“準(zhǔn)備好了”。此時(shí)命令已經(jīng)存儲(chǔ)完畢,斷電后開(kāi)啟不用從新訓(xùn)練,如果在訓(xùn)練過(guò)程中斷電,則再次上電時(shí)會(huì)從新從第一條訓(xùn)練。
4、按鍵說(shuō)明
按鍵位置圖:
- KEY1:按下KEY1 鍵播放控制器內(nèi)所有語(yǔ)音(控制器自檢功能)
- KEY2:緊急停止命令等同語(yǔ)音“停止”命令
- KEY3:從新進(jìn)行語(yǔ)音訓(xùn)練(當(dāng)識(shí)別靈敏度降低或更換法令人時(shí)使用)
5、接線說(shuō)明
按照?qǐng)D中說(shuō)明連接凌陽(yáng)61板和藍(lán)牙模塊
說(shuō)明:控制器——無(wú)線藍(lán)牙模塊
- IOB7(RXD) ——PIN5(TXD)
- IOB10(TXD)——PIN4(RXD)
- IOB+(5V) ———PIN1(5V)
- IOB-(GND)———PIN2(GND)
例子程序
凌陽(yáng)板燒錄程序
//======================================================== //按鍵3可從新訓(xùn)練 //程序說(shuō)明學(xué)習(xí)五條語(yǔ)音命令并控制相應(yīng)動(dòng)作 //命令名稱 對(duì)應(yīng)位置 對(duì)應(yīng)文件 發(fā)送數(shù)據(jù) //紅燈亮 S_ACT0 go.48k W 第二次‘1’第三次‘2’ //綠燈亮 S_ACT1 back.48k X //紅燈滅 S_ACT2 left.48k A //綠燈滅 S_ACT3 right.48k D //全都滅 S_ACT4 stop.48k S 第二次‘#’接收數(shù)據(jù) //播放超聲測(cè)試距離精度5CM 范圍1-45CM 超過(guò)播放999 // TXD IOB10 // RXD IOB7 高電`平 //======================================================== //修改前后左右提示“請(qǐng)注意” #include "s480.h" #include "bsrsd.h" #include "SPCE061A.h" #define P_IOA_Data (volatile unsigned int *)0x7000 #define P_IOA_Dir (volatile unsigned int *)0x7002 #define P_IOA_Attrib (volatile unsigned int *)0x7003 #define P_IOB_Data (volatile unsigned int *)0x7005 #define P_IOB_Dir (volatile unsigned int *)0x7007 #define P_IOB_Attrib (volatile unsigned int *)0x7008 #define P_TimerA_Data (volatile unsigned int *)0x700A #define P_TimerA_Ctrl (volatile unsigned int *)0x700B #define P_TimerB_Data (volatile unsigned int *)0x700C #define P_TimerB_Ctrl (volatile unsigned int *)0x700D #define P_Watchdog_Clear (volatile unsigned int *)0x7012 #define P_INT_Mask (volatile unsigned int *)0x702D #define P_INT_Clear (volatile unsigned int *)0x7011 //============================================================= // 波特率定義 49MHz情況下使用哪個(gè)用哪個(gè) //============================================================= //#define C_UARTBaudRate_9600_H 0x05 ////波特率設(shè)置為9600bps //#define C_UARTBaudRate_9600_L 0x00 #define C_UARTBaudRate_115200_H 0x00; //波特率設(shè)置為115200bps #define C_UARTBaudRate_115200_L 0x6B #define RED_ON 0x100 //訓(xùn)練存儲(chǔ)地址 #define BLUE_ON 0x101 #define RED_OFF 0x102 #define BLUE_OFF 0x103 #define ALL_OFF 0x104 #define S_ACT0 0 //紅燈亮 #define S_ACT1 1 //綠燈亮 #define S_ACT2 2 //紅燈滅 #define S_ACT3 3 //綠燈滅 #define S_ACT4 4 //全滅 #define S_RDY 5 //Yeah #define S_AGAIN 6 //請(qǐng)?jiān)僬f(shuō)一遍 #define S_NOVOICE 7 //沒(méi)有聽(tīng)到任何聲音 #define S_CMDDIFF 8 //沒(méi)有聽(tīng)清 #define S_NOISY 8 //沒(méi)有聽(tīng)清 #define S_START 9 //準(zhǔn)備就緒,開(kāi)始辨識(shí) #define S_QZY 10 //請(qǐng)注意 #define JIASU 11 //加速 #define QUANSU 12 //減速 #define DQJL 13 //當(dāng)前距離 #define CM 14 //厘米 #define POINT 15 //點(diǎn) #define ONE 16 //1 #define TWO 17 //2 #define THREE 18 //3 #define FOUR 19 //4 #define FIVE 20 //5 #define SIX 21 //6 #define SEVEN 22 //7 #define EIGHT 23 //8 #define NINE 24 //9 #define TEN 25 //10 extern unsigned int BSR_SDModel[100]; //外部變量BSR_SDModel[100],辨識(shí)器自帶 extern void F_FlashWrite1Word(unsigned int addr,unsigned int Value); extern void F_FlashErase(unsigned int sector); unsigned int uiTimeset = 3; //運(yùn)行時(shí)間定時(shí),調(diào)整該參數(shù)控制運(yùn)行時(shí)間 unsigned int uiTimecont; //運(yùn)行時(shí)間計(jì)時(shí) unsigned int SPEED = 0; //速度標(biāo)志位 unsigned int STOP = 0; //停止次數(shù)記錄 unsigned int g_uiData; //收到的數(shù)據(jù) unsigned int RxNum = 0, RxEndSign = 0; //收到數(shù)據(jù)寄存器 //char RxData[3]; unsigned int TxNumTemp, TxNum, TxEndSign; //發(fā)送數(shù)據(jù)標(biāo)志 char RXdata; //============================================================= // 語(yǔ)法格式: void Delay(); // 實(shí)現(xiàn)功能: 延時(shí) // 參數(shù): 無(wú) // 返回值: 無(wú) //============================================================= void Delay() { unsigned int i; for(i=0;i<0x3Fff;i++) { *P_Watchdog_Clear=0x0001; } } //============================================================= // 語(yǔ)法格式: void Delay_Us(unsigned int TimeCnt) // 實(shí)現(xiàn)功能: 延時(shí)(uS) // 參數(shù): unsigned int TimeCnt:延時(shí)的us數(shù) // 返回值: 無(wú) //============================================================= void Delay_Us(unsigned int TimeCnt) { int i; *P_SystemClock = 0x98; for(i = 0; i < TimeCnt; i++) { *P_Watchdog_Clear = 0x0001; } } /* //============================================================= // 語(yǔ)法格式: void IRQ7(void); // 實(shí)現(xiàn)功能: 接收UART數(shù)據(jù)并存 // 參數(shù): 無(wú) // 返回值: 無(wú) //============================================================= void IRQ7(void) __attribute__ ((ISR)); void IRQ7(void) { *P_Watchdog_Clear = 0x0001; if((*P_UART_Command2&0x0080) != 0) { for(RxNum=0;RxNum<3;RxNum++){ g_uiData = *P_UART_Data; //取收到數(shù)據(jù) RxData[RxNum] = g_uiData; } } }*/ /*========================================================== // 實(shí)現(xiàn)功能 UART中斷 ============================================================*/ void IRQ7(void)__attribute__((ISR)); void IRQ7(void) { // if((*P_UART_Command2&0x80)!=0) // { RXdata = *P_UART_Data; // } } //============================================================= // 實(shí)現(xiàn)功能: ULTRA初始化 //============================================================= void UART_Init(void) { *P_IOB_Dir |= 0x0400; // bit10設(shè)為輸出口(Tx),bit7設(shè)為輸入口(Rx) *P_IOB_Dir &= 0xff7f; *P_IOB_Attrib |= 0x0400; *P_IOB_Attrib &= 0xff7f; *P_IOB_Buffer |= 0x0400; *P_UART_Command1 = C_UART_Reset; //UART復(fù)位 *P_UART_BaudScalarHigh = C_UARTBaudRate_115200_H; //波特率設(shè)為115200 *P_UART_BaudScalarLow = C_UARTBaudRate_115200_L; *P_UART_Command1 = 0x80; //UART接收中斷使能 *P_UART_Command2 = 0xc0; //UART接收發(fā)送管腳使能 } //============================================================= // 實(shí)現(xiàn)功能: 串口接收數(shù)據(jù) //============================================================= unsigned int UartreciveByte(void) //該函數(shù)在中斷服務(wù)程序中 { int a,dat; a=*P_UART_Command2; a=a&0x0080; while(a==0) //Check bit 6 to see if TxRDY = 1 { a=*P_UART_Command2; a=a&0x0080; *P_Watchdog_Clear=0x0001; } dat =*P_UART_Data; // recive data return dat; } //============================================================= // 實(shí)現(xiàn)功能: 串口發(fā)送數(shù)據(jù) //============================================================= void UartSendByte(unsigned int data) // { int a; a=*P_UART_Command2; a=a&0x0040; while(!a) //Check bit 6 to see if TxRDY = 1 { a=*P_UART_Command2; a=a&0x0040; } *P_UART_Data=data; // send data } //============================================================= // 語(yǔ)法格式: void PlaySnd(unsigned SndIndex,unsigned DAC_Channel); // 實(shí)現(xiàn)功能: 語(yǔ)音播放函數(shù) // 參數(shù): SndIndex-播放語(yǔ)音資源索引號(hào) // DAC_Channel-播放聲道選擇 // 返回值: 無(wú) //============================================================= void PlaySnd(unsigned SndIndex,unsigned DAC_Channel) { BSR_StopRecognizer(); //停止識(shí)別器 SACM_S480_Initial(1); //初始化為自動(dòng)播放 SACM_S480_Play(SndIndex, DAC_Channel, 3); //開(kāi)始播放一段語(yǔ)音 while((SACM_S480_Status()&0x0001)!= 0) //是否播放完畢? { SACM_S480_ServiceLoop(); //解碼并填充隊(duì)列 *P_Watchdog_Clear=0x0001; //清看門(mén)狗 } SACM_S480_Stop(); //停止播放 BSR_InitRecognizer(BSR_MIC); //初始化識(shí)別器 } //============================================================= // 語(yǔ)法格式: int TrainWord(int WordID,int SndID); // 實(shí)現(xiàn)功能: 訓(xùn)練一條指令 // 參數(shù): WordID-指令編碼 // SndID-指令提示音索引號(hào) // 返回值: 無(wú) //============================================================= int TrainWord(unsigned int WordID,unsigned int SndID) { int Result; PlaySnd(SndID,3); //引導(dǎo)訓(xùn)練,播放指令對(duì)應(yīng)動(dòng)作 while(1) { Result = BSR_Train(WordID,BSR_TRAIN_TWICE); //訓(xùn)練兩次,獲得訓(xùn)練結(jié)果 if(Result==0)break; switch(Result) { case -1: //沒(méi)有檢測(cè)出聲音 PlaySnd(S_NOVOICE,3); return -1; case -2: //需要訓(xùn)練第二次 PlaySnd(S_AGAIN,3); break; case -3: //環(huán)境太吵 PlaySnd(S_NOISY,3); return -3; case -4: //數(shù)據(jù)庫(kù)滿 return -4; case -5: //檢測(cè)出聲音不同 PlaySnd(S_CMDDIFF,3); return -5; case -6: //序號(hào)錯(cuò)誤 return -6; default: break; } } return 0; } //============================================================= // 語(yǔ)法格式: void TrainSD(); // 實(shí)現(xiàn)功能: 訓(xùn)練函數(shù) // 參數(shù): 無(wú) // 返回值: 無(wú) //============================================================= void TrainSD() { while(TrainWord(RED_ON,S_ACT0) != 0); //訓(xùn)練第1個(gè)動(dòng)作 前進(jìn) while(TrainWord(BLUE_ON,S_ACT1) != 0); //訓(xùn)練第2個(gè)動(dòng)作 后退 while(TrainWord(RED_OFF,S_ACT2) != 0); //訓(xùn)練第3個(gè)動(dòng)作 左 while(TrainWord(BLUE_OFF,S_ACT3) != 0); //訓(xùn)練第4個(gè)動(dòng)作 右 while(TrainWord(ALL_OFF,S_ACT4) != 0); //訓(xùn)練第5個(gè)動(dòng)作 停 } //============================================================= // 語(yǔ)法格式: void StoreSD(); // 實(shí)現(xiàn)功能: 存儲(chǔ)語(yǔ)音模型函數(shù) // 參數(shù): 無(wú) // 返回值: 無(wú) //============================================================= void StoreSD() { unsigned int ulAddr,i,commandID,g_Ret; F_FlashWrite1Word(0xef00,0xaaaa); F_FlashErase(0xe000); F_FlashErase(0xe100); F_FlashErase(0xe200); ulAddr=0xe000;//******** for(commandID=0x100;commandID<0x105;commandID++) //五條commandID<0x105 { g_Ret=BSR_ExportSDWord(commandID); while(g_Ret!=0) //模型導(dǎo)出成功? g_Ret=BSR_ExportSDWord(commandID); for(i=0;i<100;i++) //保存語(yǔ)音模型SD1(0xe000---0xe063) { F_FlashWrite1Word(ulAddr,BSR_SDModel[i]); ulAddr+=1; } } } //============================================================= // 語(yǔ)法格式: void StoreSD(); // 實(shí)現(xiàn)功能: 裝載語(yǔ)音模型函數(shù) // 參數(shù): 無(wú) // 返回值: 無(wú) //============================================================= void LoadSD() { unsigned int *p,k,jk,Ret,g_Ret; p=(int *)0xe000; for(jk=0;jk<5;jk++)//原jk<5///////////////////////////////////////////////////////////////////////////////////// { for(k=0;k<100;k++) { Ret=*p; BSR_SDModel[k]=Ret; //裝載語(yǔ)音模型 p+=1; } g_Ret=BSR_ImportSDWord(); while(g_Ret!=0) //模型裝載成功? g_Ret=BSR_ImportSDWord(); } } /* //============================================================= // 語(yǔ)法格式: void paydistance(data); // 實(shí)現(xiàn)功能: 播放串口數(shù)據(jù) // 參數(shù): 無(wú) // 返回值: 無(wú) //============================================================= void playdistance(unsigned int udata){ unsigned int decade; unsigned int theunit; unsigned int hundreds; if(udata > 100){ hundreds = udata/100; udata = udata - hundreds*100; } decade = udata/10; theunit = udata%10; if(decade >0 && decade < 10){ //沒(méi)有十位時(shí)不讀 PlaySnd(decade+15,3);// PlaySnd(TEN,3);//10 }else if(theunit > 0&& theunit <10){ //沒(méi)有個(gè)位時(shí)不讀 PlaySnd(theunit+15,3);// // data = 0;//清除接收緩存 } } */ //============================================================= // 語(yǔ)法格式: void BSR(void); // 實(shí)現(xiàn)功能: 辨識(shí)子函數(shù) // 參數(shù): 無(wú) // 返回值: 無(wú) //============================================================= void BSR(void) { int Result; //辨識(shí)結(jié)果寄存 Result = BSR_GetResult(); //獲得識(shí)別結(jié)果 if(Result>0) //有語(yǔ)音觸發(fā)? { *P_Watchdog_Clear = 0x1; switch(Result) { case RED_ON: if(SPEED == 0){ UartSendByte('W'); SPEED++;STOP = 0; PlaySnd(S_ACT0,3);//播放前進(jìn) }else if(SPEED == 1){ UartSendByte('1'); SPEED++;STOP = 0; PlaySnd(JIASU,3); //播放加速前進(jìn) }else if(SPEED == 2){ UartSendByte('2'); SPEED = 2;STOP = 0; //預(yù)留檔位 PlaySnd(QUANSU,3);//播放全速前進(jìn) } break; case BLUE_ON: UartSendByte('X'); PlaySnd(S_ACT1,3); //后退 PlaySnd(S_QZY,3); //請(qǐng)注意 SPEED = 0;STOP = 0; //轉(zhuǎn)彎后減到一檔 清除STOP次數(shù) break; case RED_OFF: UartSendByte('A'); PlaySnd(S_ACT2,3); //左轉(zhuǎn) // PlaySnd(S_QZY,3); //請(qǐng)注意 SPEED = 0;STOP = 0; //轉(zhuǎn)彎后減到一檔 清除STOP次數(shù) break; case BLUE_OFF: UartSendByte('D'); PlaySnd(S_ACT3,3); //右轉(zhuǎn) // PlaySnd(S_QZY,3); //請(qǐng)注意 SPEED = 0;STOP = 0; //轉(zhuǎn)彎后減到一檔 清除STOP次數(shù) break; case ALL_OFF: if(STOP == 0){ UartSendByte('S'); STOP = 1; PlaySnd(S_ACT4,3); //停止 SPEED = 0; //轉(zhuǎn)彎后減到一檔 }else if(STOP == 1){ STOP = 1; //允許重復(fù)讀取 UartSendByte('#'); //發(fā)送超聲波數(shù)據(jù)請(qǐng)求 Delay(600); //等待數(shù)據(jù)接收完 while(RXdata != 0){ switch(RXdata){ case 'a': PlaySnd(DQJL,3);//當(dāng)前距離 PlaySnd(ONE,3);//1 PlaySnd(TEN,3);//10 PlaySnd(CM,3);//厘米 RXdata = 0; STOP = 1; //允許重復(fù)讀取 break; case 'b': PlaySnd(DQJL,3);//當(dāng)前距離 PlaySnd(ONE,3);//1 PlaySnd(TEN,3);//10 PlaySnd(FIVE,3);//5 PlaySnd(CM,3);//厘米 RXdata = 0; STOP = 1; //允許重復(fù)讀取 break; case 'c': PlaySnd(DQJL,3);//當(dāng)前距離 PlaySnd(TWO,3);//2 PlaySnd(TEN,3);//10 PlaySnd(CM,3);//厘米 RXdata = 0; STOP = 1; //允許重復(fù)讀取 break; case 'd': PlaySnd(DQJL,3);//當(dāng)前距離 PlaySnd(TWO,3);//2 PlaySnd(TEN,3);//10 PlaySnd(FIVE,3);//5 PlaySnd(CM,3);//厘米 RXdata = 0; STOP = 1; //允許重復(fù)讀取 break; case 'e': PlaySnd(DQJL,3);//當(dāng)前距離 PlaySnd(THREE,3);//3 PlaySnd(TEN,3);//10 PlaySnd(CM,3);//厘米 RXdata = 0; STOP = 1; //允許重復(fù)讀取 break; case 'f': PlaySnd(DQJL,3);//當(dāng)前距離 PlaySnd(THREE,3);//3 PlaySnd(TEN,3);//10 PlaySnd(FIVE,3);//5 PlaySnd(CM,3);//厘米 RXdata = 0; STOP = 1; //允許重復(fù)讀取 break; case 'g': PlaySnd(DQJL,3);//當(dāng)前距離 PlaySnd(FOUR,3);//4 PlaySnd(TEN,3);//10 PlaySnd(CM,3);//厘米 RXdata = 0; STOP = 1; //允許重復(fù)讀取 case 'h': PlaySnd(DQJL,3);//當(dāng)前距離 PlaySnd(FOUR,3);//4 PlaySnd(TEN,3);//10 PlaySnd(FIVE,3);//5 PlaySnd(CM,3);//厘米 RXdata = 0; STOP = 1; //允許重復(fù)讀取 break; case 'i': PlaySnd(DQJL,3);//當(dāng)前距離 PlaySnd(FIVE,3);//5 PlaySnd(TEN,3);//10 PlaySnd(CM,3);//厘米 RXdata = 0; STOP = 1; //允許重復(fù)讀取 break; case 'j': PlaySnd(DQJL,3);//當(dāng)前距離 PlaySnd(FIVE,3);//5 PlaySnd(TEN,3);//10 PlaySnd(FIVE,3);//5 PlaySnd(CM,3);//厘米 RXdata = 0; STOP = 1; //允許重復(fù)讀取 break; case 'k': PlaySnd(DQJL,3);//當(dāng)前距離 PlaySnd(SIX,3);//6 PlaySnd(TEN,3);//10 PlaySnd(CM,3);//厘米 RXdata = 0; STOP = 1; //允許重復(fù)讀取 break; case 'l': PlaySnd(DQJL,3);//當(dāng)前距離 PlaySnd(SIX,3);//6 PlaySnd(TEN,3);//10 PlaySnd(FIVE,3);//5 PlaySnd(CM,3);//厘米 RXdata = 0; STOP = 1; //允許重復(fù)讀取 break; case 'm': PlaySnd(DQJL,3);//當(dāng)前距離 PlaySnd(SEVEN,3);//7 PlaySnd(TEN,3);//10 PlaySnd(CM,3);//厘米 RXdata = 0; STOP = 1; //允許重復(fù)讀取 break; case 'n': PlaySnd(DQJL,3);//當(dāng)前距離 PlaySnd(SEVEN,3);//7 PlaySnd(TEN,3);//10 PlaySnd(FIVE,3);//5 PlaySnd(CM,3);//厘米 RXdata = 0; STOP = 1; //允許重復(fù)讀取 break; case 'o': PlaySnd(DQJL,3);//當(dāng)前距離 PlaySnd(EIGHT,3);//8 PlaySnd(TEN,3);//10 PlaySnd(CM,3);//厘米 RXdata = 0; STOP = 1; //允許重復(fù)讀取 break; case 'p': PlaySnd(DQJL,3);//當(dāng)前距離 PlaySnd(EIGHT,3);//8 PlaySnd(TEN,3);//10 PlaySnd(FIVE,3);//5 PlaySnd(CM,3);//厘米 RXdata = 0; STOP = 1; //允許重復(fù)讀取 break; case 'q': PlaySnd(DQJL,3);//當(dāng)前距離 PlaySnd(NINE,3);//9 PlaySnd(TEN,3);//10 PlaySnd(CM,3);//厘米 RXdata = 0; STOP = 1; //允許重復(fù)讀取 break; case 'r': PlaySnd(DQJL,3);//當(dāng)前距離 PlaySnd(NINE,3);//9 PlaySnd(TEN,3);//10 PlaySnd(FIVE,3);//5 PlaySnd(CM,3);//厘米 RXdata = 0; STOP = 1; //允許重復(fù)讀取 break; /* case 's': PlaySnd(DQJL,3);//當(dāng)前距離 PlaySnd(FOUR,3);//4 PlaySnd(TEN,3);//10 PlaySnd(FIVE,3);//5 PlaySnd(CM,3);//厘米 RXdata = 0; break; case 't': PlaySnd(DQJL,3);//當(dāng)前距離 PlaySnd(FOUR,3);//4 PlaySnd(TEN,3);//10 PlaySnd(FIVE,3);//5 PlaySnd(CM,3);//厘米 RXdata = 0; break; case 'u': PlaySnd(DQJL,3);//當(dāng)前距離 PlaySnd(FOUR,3);//4 PlaySnd(TEN,3);//10 PlaySnd(FIVE,3);//5 PlaySnd(CM,3);//厘米 RXdata = 0; break; */ case '~': PlaySnd(DQJL,3);//當(dāng)前距離 PlaySnd(NINE,3);//9 PlaySnd(NINE,3);//9 PlaySnd(NINE,3);//9 PlaySnd(CM,3);//厘米 RXdata = 0; break; default: RXdata = 0; break; } } } break; default: break; } } } //============================================================= // 語(yǔ)法格式: int main(void); // 實(shí)現(xiàn)功能: 主函數(shù) // 參數(shù): 無(wú) // 返回值: 無(wú) //============================================================= int main(void) { unsigned int BS_Flag; //Train標(biāo)志位 空 BSR_DeleteSDGroup(0); //初始化存儲(chǔ)器RAM BS_Flag=*(unsigned int *)0xe000; //讀存儲(chǔ)單元0xe000 if(BS_Flag==0xffff) //沒(méi)有經(jīng)過(guò)訓(xùn)練(0xe000內(nèi)容為0xffff) { TrainSD(); //訓(xùn)練 StoreSD(); //存儲(chǔ)訓(xùn)練結(jié)果(語(yǔ)音模型) } else //經(jīng)過(guò)訓(xùn)練(0xe000內(nèi)容為0x0055) { LoadSD(); //語(yǔ)音模型載入識(shí)別器 } PlaySnd(S_START,3); //開(kāi)始識(shí)別提示 BSR_InitRecognizer(BSR_MIC); //初始化識(shí)別器 UART_Init(); //UART初始化 __asm("IRQ ON"); //開(kāi)中斷 while(1) { BSR();// 語(yǔ)音識(shí)別 *P_Watchdog_Clear=0x0001; // __asm("IRQ OFF"); //跳出關(guān)中斷 if((*P_IOA_Data)&0x0004) //按鍵4從新訓(xùn)練 { F_FlashErase(0xe000); while(1); } if((*P_IOA_Data)&0x0002){ //緊急停止按鍵2 UartSendByte('S'); // playdistance(RxData[0]-30); // UartSendByte(RxData[0]);//RXdata -48 // playdistance(RxData[1]-30); // UartSendByte(RxData[1]);//RXdata -48 // UartSendByte(RxData[2]);//RXdata -48 } if((*P_IOA_Data)&0x0001) //按鍵1播放所有聲音 { PlaySnd(S_ACT0,3);//測(cè)試聲音 PlaySnd(S_ACT1,3);//測(cè)試聲音 PlaySnd(S_ACT2,3);//測(cè)試聲音 PlaySnd(S_ACT3,3);//測(cè)試聲音 PlaySnd(S_ACT4,3);//測(cè)試聲音 PlaySnd(S_RDY,3);//測(cè)試聲音 PlaySnd(S_AGAIN,3);//測(cè)試聲音 PlaySnd(S_NOISY,3);//測(cè)試聲音 PlaySnd(S_START,3);//測(cè)試聲音 PlaySnd(S_QZY,3);//測(cè)試聲音 PlaySnd(JIASU,3);//測(cè)試聲音 PlaySnd(QUANSU,3);//測(cè)試聲音 PlaySnd(DQJL,3);//當(dāng)前距離 PlaySnd(CM,3);//厘米 PlaySnd(POINT,3);//點(diǎn) PlaySnd(ONE,3);//1 PlaySnd(TWO,3);//2 PlaySnd(THREE,3);//3 PlaySnd(FOUR,3);//4 PlaySnd(FIVE,3);//5 PlaySnd(SIX,3);//6 PlaySnd(SEVEN,3);//7 PlaySnd(EIGHT,3);//8 PlaySnd(NINE,3);//9 PlaySnd(TEN,3);//10 } } }
4WD 平臺(tái)端程序
將下列程序上傳到 Carduino 控制器中
- 點(diǎn)擊此處 Arduino 入門(mén)教程查看程序上傳方法
- * 示例程序下載
將下載到的壓縮文件解壓到到 Arduino IDE 軟件的 libraries 文件中(·····\arduino-1.7.6\libraries),啟動(dòng) Arduino IDE 選擇文件 -- 示例 -- RB-13K049_AS-4WD_yu_yin-master -- 打開(kāi) example 中的相應(yīng)例子程序,上傳到 Arduino UNO 控制器中,就可以實(shí)現(xiàn)代碼測(cè)試。操作方法下圖所示:
解壓過(guò)程
int srfPin = 15; //定義srfPin 發(fā)送引腳為15 int z; //定義全局變量z int Distance; //定義距離寄存器存放測(cè)試距離數(shù)據(jù) int duration; //定義脈寬寄存器 int data; //定義串口接收寄存器 #define EA 5 #define I2 6 #define I1 7 #define EB 11 #define I4 10 #define I3 9 int ultrasonic(int distance) { digitalWrite(srfPin, LOW); //確保在發(fā)送脈沖前保持該引腳為低電平 delayMicroseconds(2); //保持低電平2ms digitalWrite(srfPin, HIGH); //發(fā)送一個(gè)高脈沖開(kāi)始測(cè)距 delayMicroseconds(10); //保持10ms digitalWrite(srfPin, LOW); //在等待脈沖返回來(lái)之前發(fā)送低電平 pinMode(srfPin, INPUT); //調(diào)整超聲波引腳為輸入 duration = pulseIn(srfPin, HIGH); //從SRF05 回波脈沖在讀取在微秒 distance = duration/58; //除以58 就是我們要得到的厘米數(shù) return distance; //返回厘米數(shù) } void BACK() //后退 { analogWrite(EA,130);//輸入模擬值進(jìn)行設(shè)定速度 analogWrite(EB,130); digitalWrite(I2,HIGH);//使直流電機(jī)運(yùn)轉(zhuǎn) digitalWrite(I1,LOW); digitalWrite(I3,HIGH);//使直流電機(jī)運(yùn)轉(zhuǎn) digitalWrite(I4,LOW); } void GO() //前進(jìn) { analogWrite(EA,100);//輸入模擬值進(jìn)行設(shè)定速度 analogWrite(EB,100); digitalWrite(I2,LOW);//使直流電機(jī)運(yùn)轉(zhuǎn) digitalWrite(I1,HIGH); digitalWrite(I3,LOW);//使直流電機(jī)運(yùn)轉(zhuǎn) digitalWrite(I4,HIGH); } void QUICKEN() //加速前進(jìn) { analogWrite(EA,140); //輸入模擬值進(jìn)行設(shè)定速度 analogWrite(EB,140); digitalWrite(I2,LOW);//使直流電機(jī)運(yùn)轉(zhuǎn) digitalWrite(I1,HIGH); digitalWrite(I3,LOW);//使直流電機(jī)運(yùn)轉(zhuǎn) digitalWrite(I4,HIGH); } void FULLSPEED() //全速前進(jìn) { analogWrite(EA,165); //輸入模擬值進(jìn)行設(shè)定速度 analogWrite(EB,165); digitalWrite(I2,LOW);//使直流電機(jī)運(yùn)轉(zhuǎn) digitalWrite(I1,HIGH); digitalWrite(I3,LOW);//使直流電機(jī)運(yùn)轉(zhuǎn) digitalWrite(I4,HIGH); } void LEFT() //左轉(zhuǎn) { analogWrite(EA,130);//輸入模擬值進(jìn)行設(shè)定速度 analogWrite(EB,130); digitalWrite(I2,LOW);//使直流電機(jī)運(yùn)轉(zhuǎn) digitalWrite(I1,HIGH); digitalWrite(I3,HIGH);//使直流電機(jī)運(yùn)轉(zhuǎn) digitalWrite(I4,LOW); } void RIGHT() //右轉(zhuǎn) { analogWrite(EA,130);//輸入模擬值進(jìn)行設(shè)定速度 analogWrite(EB,130); digitalWrite(I2,HIGH);//使直流電機(jī)運(yùn)轉(zhuǎn) digitalWrite(I1,LOW); digitalWrite(I3,LOW);//使直流電機(jī)運(yùn)轉(zhuǎn) digitalWrite(I4,HIGH); } void STOP() //停止 { digitalWrite(I2,HIGH);//使直流電機(jī)停轉(zhuǎn) digitalWrite(I1,HIGH); digitalWrite(I3,HIGH);//使直流電機(jī)停轉(zhuǎn) digitalWrite(I4,HIGH); } void PLAYDISTANCE() //發(fā)送超聲波數(shù)據(jù) { Distance = ultrasonic(z); if(Distance > 0 && Distance <= 10){ //判斷測(cè)試距離為1 至10CM Serial.print('a');} //發(fā)送字符'a' else if(Distance > 10 && Distance <= 15){ //判斷測(cè)試距離為11 至15CM Serial.print('b');} //發(fā)送字符'b' else if(Distance > 15 && Distance <= 20){ Serial.print('c');} else if(Distance > 20 && Distance <= 25){ Serial.print('d');} else if(Distance > 25 && Distance <= 30){ Serial.print('e');} else if(Distance > 30 && Distance <= 35){ Serial.print('f');} else if(Distance > 35 && Distance <= 40){ Serial.print('g');} else if(Distance > 40 && Distance <= 45){ Serial.print('h');} else if(Distance > 45 && Distance <= 50){ Serial.print('i');} else if(Distance > 50 && Distance <= 55){ Serial.print('j');} else if(Distance > 55 && Distance <= 60){ Serial.print('k');} else if(Distance > 60 && Distance <= 65){ Serial.print('l');} else if(Distance > 65 && Distance <= 70){ Serial.print('m');} else if(Distance > 70 && Distance <= 75){ Serial.print('n');} else if(Distance > 75 && Distance <= 80){ Serial.print('o');} else if(Distance > 80 && Distance <= 85){ Serial.print('p');} else if(Distance > 85 && Distance <= 90){ Serial.print('q');} else if(Distance > 90 && Distance <= 95){ Serial.print('r');} else{ Serial.print('~');} } void setup() { Serial.begin(115200); //打開(kāi)串口并設(shè)置通信波特率為115200 pinMode(9,OUTPUT); //定義I3 接口 pinMode(10,OUTPUT); //定義I4 接口 pinMode(11,OUTPUT); //定義EB(PWM 調(diào)速)接口 pinMode(5,OUTPUT); //定義EA(PWM 調(diào)速)接口 pinMode(6,OUTPUT); //定義I2接口 pinMode(7,OUTPUT); //定義I1接口 } void loop() //主程序開(kāi)始 { Distance = ultrasonic(z); //讀取超聲波值 data = Serial.read(); //讀取串口數(shù)據(jù) switch (data){ case 'W': //前進(jìn)命令 GO(); //前進(jìn)函數(shù) Serial.flush(); //刷新串口緩沖區(qū)數(shù)據(jù) break; case 'X': //后退命令 BACK(); //后退函數(shù) Serial.flush(); //刷新串口緩沖區(qū)數(shù)據(jù) break; case 'A': //左轉(zhuǎn)命令 LEFT(); //左轉(zhuǎn)函數(shù) Serial.flush(); //刷新串口緩沖區(qū)數(shù)據(jù) break; case 'D': //右轉(zhuǎn)命令 RIGHT(); //右轉(zhuǎn)函數(shù) Serial.flush(); //刷新串口緩沖區(qū)數(shù)據(jù) break; case 'S': //停止命令 STOP(); //停止函數(shù) Serial.flush(); //刷新串口緩沖區(qū)數(shù)據(jù) break; case '1': //加速前進(jìn)命令 QUICKEN(); //加速前進(jìn)函數(shù) Serial.flush(); //刷新串口緩沖區(qū)數(shù)據(jù) case '2': //全速前進(jìn)命令 FULLSPEED(); //全速前進(jìn)函數(shù) Serial.flush(); //刷新串口緩沖區(qū)數(shù)據(jù) break; case '#': //測(cè)試當(dāng)前距離命令 PLAYDISTANCE(); //發(fā)送當(dāng)前距離函數(shù) Serial.flush(); //刷新串口緩沖區(qū)數(shù)據(jù) break; default: break; } }
程序效果概述
- 發(fā)出語(yǔ)音命令“前進(jìn)” - 凌陽(yáng)板播報(bào)“前進(jìn)”,小車向前行進(jìn)
- 第二次發(fā)出語(yǔ)音命令“前進(jìn)” - 凌陽(yáng)板播報(bào)“加速前進(jìn)”,小車向前行進(jìn)
- 第三次發(fā)出語(yǔ)音命令“前進(jìn)” - 凌陽(yáng)板播報(bào)“全速前進(jìn)”,小車向前行進(jìn)
- 發(fā)出語(yǔ)音命令“后退” - 凌陽(yáng)板播報(bào)“后退,請(qǐng)注意”,小車向后行進(jìn)
- 發(fā)出語(yǔ)音命令“左轉(zhuǎn)” - 凌陽(yáng)板播報(bào)“左轉(zhuǎn)”,小車向左轉(zhuǎn)彎
- 發(fā)出語(yǔ)音命令“右轉(zhuǎn)” - 凌陽(yáng)板播報(bào)“右轉(zhuǎn)”,小車向右轉(zhuǎn)彎
- 發(fā)出語(yǔ)音命令“停止” - 凌陽(yáng)板播報(bào)“停止”,小車停止
- 發(fā)出語(yǔ)音命令“停止 、 停止” - 凌陽(yáng)板播報(bào)“停止,當(dāng)前距離 XX 厘米”,小車停止
注意:
1、盡量是錄音的人對(duì)小車進(jìn)行操作,不然錯(cuò)誤率會(huì)提高
2、語(yǔ)音命令發(fā)出時(shí),盡量保證吐字的清晰度,不然也會(huì)造成錯(cuò)誤識(shí)別,小車不能按照語(yǔ)音進(jìn)行運(yùn)動(dòng)
3、由于小車在向前行進(jìn)過(guò)程中,不能自動(dòng)避障,所以請(qǐng)您注意操作距離,距離過(guò)長(zhǎng)會(huì)造成藍(lán)牙斷開(kāi)
產(chǎn)品相關(guān)推薦
產(chǎn)品資料
下載鏈接:https://pan.baidu.com/s/189SAlN4wH-9cDhcUsnPKEw 提取碼:ag69
產(chǎn)品購(gòu)買地址
Arduino 4WD 語(yǔ)音識(shí)別移動(dòng)機(jī)器人平臺(tái)
周邊產(chǎn)品推薦
Arduino 4WD鋁合金移動(dòng)平臺(tái)車燈套件
Arduino 光電碼盤(pán) 光電測(cè)速傳感器
Arduino 雙H橋直流電機(jī)驅(qū)動(dòng)板
相關(guān)問(wèn)題解答
AS-4WD 碰撞機(jī)器人如何安裝
4wd 紅外線巡線壁障車調(diào)試助手沒(méi)有反應(yīng)
相關(guān)學(xué)習(xí)資料
視頻:機(jī)器人調(diào)試助手無(wú)線操控AS-4WD輪式機(jī)器人
視頻:Arduino-4WD移動(dòng)機(jī)器人尋線功能演示
視頻:Arduino-4WD移動(dòng)機(jī)器人碰撞功能演示
視頻:Arduino-4WD移動(dòng)機(jī)器人追光功能演示
視頻:Arduino-4WD移動(dòng)機(jī)器人尋線與避障功能演示
視頻:Arduino-4WD移動(dòng)機(jī)器人偵測(cè)避障功能演示
視頻:直流減速電機(jī)驅(qū)動(dòng)實(shí)例
奧松機(jī)器人技術(shù)論壇