SKU:RB-13K049 AS-4WD語音識別操控移動機(jī)器人

來自ALSROBOT WiKi
2021年12月18日 (六) 16:08Zhangxin討論 | 貢獻(xiàn)的版本

(差異) ←上一版本 | 最后版本 (差異) | 下一版本→ (差異)
跳轉(zhuǎn)至: 導(dǎo)航、 搜索
RB13K04901.png

目錄

產(chǎn)品概述

AS - 4WD 語音識別移動機(jī)器人語音識別采用凌陽單片機(jī)控制器,它可以學(xué)習(xí)記錄你的聲音,并且跟你實(shí)現(xiàn)人機(jī)對話,通過識別和理解過程把語音信號轉(zhuǎn)變?yōu)橄鄳?yīng)的命令,經(jīng)過無線藍(lán)牙模塊傳輸給機(jī)器人,從而可以完成前進(jìn)、后退、左轉(zhuǎn)、右轉(zhuǎn)、測距播報(bào)等功能,實(shí)現(xiàn)人機(jī)互動。

產(chǎn)品參數(shù)

  1. 產(chǎn)品名稱:AS - 4WD 語音識別操控移動平臺
  2. 產(chǎn)品類型:輪式移動機(jī)器人
  3. 產(chǎn)品貨號:RB - 13K049
  4. 編程軟件:Arduino IDE
  5. 基礎(chǔ)模塊:凌陽61、藍(lán)牙模塊、Carduino UNO R3、傳感器擴(kuò)展板 V5.0、雙 H 橋電機(jī)驅(qū)動板
  6. 控制方式:語音操控
  7. 操控距離:5 m - 8 m
  8. 產(chǎn)品尺寸:215 * 200 * 120 mm
  9. 產(chǎn)品重量:1.5 kg

配件技術(shù)參數(shù)

移動平臺參數(shù)

  • 平臺長度:206mm
  • 平臺寬度:200mm
  • 平臺高度:65mm
  • 平臺重量:620g

平臺尺寸圖

RB13K00610.png

直流減速電機(jī)(1:48)

  • 驅(qū)動電機(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
  • 尺寸大?。?0.50 mm×27.00 mm×23.00 mm(長×寬×高)
  • 重量大?。杭s 30g

電控配件參數(shù)

  1. 藍(lán)牙模塊
  2. Starduino UNO R3 控制器
  3. 傳感器擴(kuò)展板 V5.0
  4. 雙 H 橋電機(jī)驅(qū)動板
  5. 凌陽 61 開發(fā)板資料
  6. RB - 35PG 舵機(jī)資料

配件清單

  • 4WD 鋁合金移動平臺 * 1套
RB13K00601.jpg
  • 4WD 語音識別操控移動機(jī)器人附件
RB13K04900.png

安裝步驟 - 4WD鋁合金平臺部分

4wd 鋁合金平臺內(nèi)部元件詳解(圖片標(biāo)號對應(yīng)清單序號

13K00820.png

步驟1:焊接部分

電機(jī)連接線焊接

1、準(zhǔn)備如下圖所示的材料

  • 4 * 直流減速電機(jī);
  • 4 * 紅色導(dǎo)線(長度為 15cm);
  • 4 * 黑色導(dǎo)線(長度為 15cm);
  • 4 * 扎帶
13K00821.png

2、如下圖所示,將紅黑導(dǎo)線焊接到電機(jī)上,并將兩個電機(jī)連接到一起

13K00822.png

3、如下圖所示,分別在兩組電機(jī)上焊接兩條線,為了后續(xù)連接到驅(qū)動板使用,再將四個電機(jī)都捆綁上扎帶后,電機(jī)部分的焊接就完成了

13K00823.png

開關(guān)接口線焊接

1、準(zhǔn)備如下圖所示的材料

  • 充電接口
  • 撥動開關(guān)
  • 連接線(紅色 10cm * 1條、紅色 15cm * 1條、黑色 15cm * 1條、紅色 20cm * 1條、黑色 20cm * 1條)、熱縮管、電池盒
13K00824.png

2、如圖所示,進(jìn)行連接線的焊接

13K008251.png

3、如圖所示,連接充電接口和撥動開關(guān)

13K00826.png

4、如圖所示,使用兩根較短的線連接電池盒

13K00827.png

注意:本例中小車的供電使用的電池盒,本電池盒需要使用的是 6 節(jié) 5 號電池盒,若使用鋰電池,焊接的方式是相同的。
更加詳細(xì)的制作過程,可以點(diǎn)擊:充電接口及撥動開關(guān)制作方法

步驟2:側(cè)板電機(jī)安裝

1、準(zhǔn)備如下圖所示的材料:

  • 2 * 黃色直流減速電機(jī)
  • 1 * 平臺側(cè)板
  • 4 * M3 * 25 螺絲
  • 4 * M3 六角螺母
13K00828.png

2、如圖所示,將電機(jī)安裝到側(cè)板 實(shí)物安裝圖:

13K00829.png
RB13K00607.png

3、進(jìn)行另一側(cè)板電機(jī)的安裝,如圖所示,為兩側(cè)電機(jī)安裝完成效果圖

13K00830.png

步驟3:側(cè)板與底板的安裝

1、準(zhǔn)備如下圖所示的材料:

  • 2 * 步驟 2 中安裝好的側(cè)板
  • 1 * 平臺底板
  • 4 * M3 * 6螺絲
13K00831.png

2、按照下圖進(jìn)行安裝 安裝實(shí)物圖:

13K00832.png
RB13K00602.png

步驟4:電機(jī)驅(qū)動板的安裝

1、準(zhǔn)備如下圖所示的材料:

  • 步驟 3 中安裝好的零件
  • 1 * 電機(jī)驅(qū)動板
  • 4 * M3 * 6螺絲
  • 4 * M3 螺母
  • 4 * M3 * 10 尼龍柱
13K00833.png

2、將尼龍柱固定到小車的底板上,位置如下圖所示:

13K00834.png

3、安裝雙H橋驅(qū)動板,如圖所示:

13K00835.png

步驟5:電機(jī)接線

1、如圖所示,將兩側(cè)電機(jī)的紅線連接到電機(jī)驅(qū)動板的 A 接口,黑線連接到電機(jī)驅(qū)動板的 B 接口

13K00836.png

2、安裝完成效果如下圖所示

13K00837.png

步驟6:上板充電接口撥動開關(guān)安裝

1、準(zhǔn)備如下圖所示的材料:

  • 步驟 1 中做好的充電接口撥動開關(guān)連接線
  • 平臺上板
13K00838.png

2、安裝完成效果如圖所示

13K00839.png
RB13K00603.png

步驟7:控制器的安裝

1、準(zhǔn)備如下圖所示的材料

  • 步驟 6 中安裝好的零件
  • Carduino UNO 控制器
  • 傳感器擴(kuò)展板 V5.0
  • 3 * 尼龍柱 M3 * 10
  • 3 * M3 螺母
  • 3 * M3 * 6 螺絲
13K00840.png

2、在小車上支撐板安裝控制器的固定尼龍柱,位置如下圖所示:

13K00841.png

3、如圖所示,安裝 Carduino UNO 控制器

13K00842.png

4、如圖所示,插入擴(kuò)展板

13K00843.png

擴(kuò)展板插入效果圖:

13K00844.png

步驟8:電控部分接線

1、準(zhǔn)備如下圖所示的材料

  • 2 * 3P 傳感器連接線
  • 供電線,紅色黑色各一條 * 20cm
  • 平臺車體
  • 平臺上板
13K00845.png

2、如圖所示為雙H橋驅(qū)動板和 Carduino UNO 控制器的接線順序
(1) 雙H橋驅(qū)動板端接線順序

  • 黃色 EA、紅色 I2、黑色 I1
  • 黃色 EB、紅色 I4、黑色 I1
13K00846.png

(2)傳感器擴(kuò)展板端接線順序

  • EA - D5、I2 - D6、I1 - D7
  • EB - D11、I4 - D10、I3 - D9
13K05631.png

(3)完成效果如下圖所示,為了布線看起來更加整齊,我們將 3P 線從小車上板的孔穿出

13K00848.png

3、供電部分連接
(1)如圖所示為雙H橋驅(qū)動板部分供電線連接,充電接口紅色導(dǎo)線接到 VMS,黑色導(dǎo)線接到 GND;將雙 H 橋驅(qū)動板輸出的 5v 電源連接到 V5.0 擴(kuò)展板的紅色端子,連接時注意正負(fù)極不要接錯;

13K00849.png

(2)如圖所示為傳感器擴(kuò)展板 V5.0 供電線連接

13K00850.png

步驟9:舵機(jī)安裝

1、準(zhǔn)備如下圖所示的材料:

  • 1 * 35PG 舵機(jī)
  • 1 * 小車車體
  • 1 * M4 * 8 螺絲套裝
13K05650.png

2、按照下圖進(jìn)行安裝 安裝實(shí)物圖:

13K05651.png

3、舵機(jī)接線
語音小車的舵機(jī)起到的是支撐超聲波傳感器作用,所以不需要連接到 Arduino 的接口上。接線懸空即可

步驟10:超聲波傳感器支架安裝

1、準(zhǔn)備如下圖所示的材料:

  • 1 * 超聲波傳感器支架
  • 1 * 圓形舵盤
  • 1 * 黑色自攻釘(大)
  • 4 * 黑色自攻釘(?。?
13K05652.png

2、按照下圖給超聲波傳感器支架分別安裝橡膠套圈、圓形舵盤 安裝實(shí)物圖:

13K05653.png
13K05654.png



3、如圖所示,將超聲波支架連接到舵機(jī)軸,注意在連接舵機(jī)和超聲波支架的時候,盡量不要轉(zhuǎn)動舵機(jī),使舵機(jī)仍然保持在中間位置上

13K05655.png

步驟11:超聲波傳感器安裝

1、準(zhǔn)備如下圖所示的材料:

  • 1 * 安裝好的車體
  • 1 * 超聲波傳感器
  • 2 * M3 * 10 尼龍柱
  • 2 * M3 螺母
  • 2 * M3 * 6 螺絲
13K05656.png

2、如下圖所示,首先將超聲波傳感器調(diào)節(jié)到模式 1

13K05657.png

3、在下圖所示位置安裝尼龍柱用來固定超聲波傳感器,并將 4P 線從超聲波支架較小的孔中穿出

13K05658.png

4、如圖所示,安裝超聲波傳感器,由于例程中使用的是單模式,超聲波傳感器只需連接 input 引腳,所以我們將 4P 線中的黃色線取掉

13K05659.png

步驟12:傳感器接線

如圖所示,將超聲波傳感器連接到傳感器擴(kuò)展板 V5.0
注意:4WD 語音識別小車中的舵機(jī),不需要連接任何接口,只是起到了固定超聲波傳感器的作用。

RB13K049041.png

步驟13:4WD 平臺上板安裝

1、準(zhǔn)備如下圖所示的材料:

  • 未固定上板的車體
  • 4 * M3 * 6螺絲
13K056611.png

2、在圖中圓圈位置安裝 4 個 M3 * 6 螺絲來固定小車上板

13K056622.png

步驟14:4WD 平臺端板安裝

1、準(zhǔn)備如下圖所示的材料:

  • 步驟 13 中安裝好的車體
  • 2 * 小車端板
  • 8 * M3 * 6 螺絲
13K056633.png

2、如圖所示,將端板與車體進(jìn)行固定

13K056644.png

步驟15:4WD 平臺車輪安裝

1、準(zhǔn)備如下圖所示的材料:

  • 步驟 14 中安裝好的車體
  • 4 * 車輪
13K056655.png

2、如圖所示,將車輪與車體安裝在一起

13K056666.png

步驟16:插接藍(lán)牙模塊

1、準(zhǔn)備如下圖所示的材料:

  • 1 * 藍(lán)牙模塊
  • 步驟 15 中安裝好的小車平臺整體
RB13K049021.png

2、將藍(lán)牙模塊插接到傳感器擴(kuò)展板的藍(lán)牙接口上,如圖所示

RB13K049031.png

安裝步驟 - 語音操控部分

1、準(zhǔn)備如下產(chǎn)品

  • 凌陽開發(fā)板 * 1套
  • 藍(lán)牙模塊 * 1個(模式:主)

注:如果不知道如何配置藍(lán)牙模塊主從模式,可以參考:藍(lán)牙模塊說明書

  • 10P 杜邦線 * 1組

2、凌陽61實(shí)驗(yàn)板部分接線

  • 如圖所示,連接電池盒凌陽實(shí)驗(yàn)板
RB13K049100.png

3、語音訓(xùn)練
按一下KEY3 鍵開始按照語音提示進(jìn)行語音訓(xùn)練。

RB13K049101.png

訓(xùn)練采用應(yīng)答形式,每條指令訓(xùn)練兩次,每條命令的訓(xùn)練方法是相同的,以第一條命令“前進(jìn)”為例說明:
第一步:控制器提示“前進(jìn)”
第二步:我們對著話筒說“前進(jìn)”
第三步:語音控制器提示“再說一遍”
第四步:我們再次對著話筒說“前進(jìn)”
到此第一條命令訓(xùn)練完畢。如果訓(xùn)練成功控制器會自動進(jìn)入下一條命令的訓(xùn)練,如果環(huán)境很吵或前后你說的話偏差太大,控制器會提示“沒有聲音”或者“沒有聽清”這樣這條命令就會從新訓(xùn)練。當(dāng)所有的命令訓(xùn)練完畢,控制器會提示“準(zhǔn)備好了”。此時命令已經(jīng)存儲完畢,斷電后開啟不用從新訓(xùn)練,如果在訓(xùn)練過程中斷電,則再次上電時會從新從第一條訓(xùn)練。
4、按鍵說明
按鍵位置圖:

RB13K049101.png
  • KEY1:按下KEY1 鍵播放控制器內(nèi)所有語音(控制器自檢功能)
  • KEY2:緊急停止命令等同語音“停止”命令
  • KEY3:從新進(jìn)行語音訓(xùn)練(當(dāng)識別靈敏度降低或更換法令人時使用)

5、接線說明
按照圖中說明連接凌陽61板和藍(lán)牙模塊

RB13K049102.png

說明:控制器——無線藍(lán)牙模塊

  • IOB7(RXD) ——PIN5(TXD)
  • IOB10(TXD)——PIN4(RXD)
  • IOB+(5V) ———PIN1(5V)
  • IOB-(GND)———PIN2(GND)

例子程序

凌陽板燒錄程序

//========================================================
//按鍵3可從新訓(xùn)練
//程序說明學(xué)習(xí)五條語音命令并控制相應(yīng)動作
//命令名稱       對應(yīng)位置        對應(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ù)
//播放超聲測試距離精度5CM 范圍1-45CM	超過播放999
//	TXD     IOB10
//	RXD     IOB7        高電`平
//========================================================
//修改前后左右提示“請注意”
#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情況下使用哪個用哪個
//=============================================================
//#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)練存儲地址
#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							//請?jiān)僬f一遍
#define S_NOVOICE			7							//沒有聽到任何聲音
#define S_CMDDIFF			8							//沒有聽清
#define S_NOISY				8							//沒有聽清
#define S_START				9							//準(zhǔn)備就緒,開始辨識
#define S_QZY				10							//請注意	
#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],辨識器自帶
extern void F_FlashWrite1Word(unsigned int addr,unsigned int Value);
extern void F_FlashErase(unsigned int sector);
unsigned int uiTimeset = 3;								//運(yùn)行時間定時,調(diào)整該參數(shù)控制運(yùn)行時間
unsigned int uiTimecont; 								//運(yùn)行時間計(jì)時

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;
//=============================================================
// 語法格式:	void Delay();
// 實(shí)現(xiàn)功能:	延時
// 參數(shù):		無
// 返回值:		無
//=============================================================
void Delay()							
{
	unsigned int i;
	for(i=0;i<0x3Fff;i++)
	{
		*P_Watchdog_Clear=0x0001;
	}
}
//=============================================================
// 語法格式:	void Delay_Us(unsigned int TimeCnt)
// 實(shí)現(xiàn)功能:	延時(uS)
// 參數(shù):		unsigned int TimeCnt:延時的us數(shù)
// 返回值:		無
//=============================================================
void Delay_Us(unsigned int TimeCnt)
{
	int i;
	*P_SystemClock = 0x98;
	for(i = 0; i < TimeCnt; i++)
	{
		*P_Watchdog_Clear = 0x0001;
	}
}
/*
//============================================================= 
// 語法格式:    void IRQ7(void);
// 實(shí)現(xiàn)功能:	接收UART數(shù)據(jù)并存
// 參數(shù):        無
// 返回值:      無
//=============================================================
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
}

//=============================================================
// 語法格式:	void PlaySnd(unsigned SndIndex,unsigned DAC_Channel);
// 實(shí)現(xiàn)功能:	語音播放函數(shù)
// 參數(shù):		SndIndex-播放語音資源索引號
//				DAC_Channel-播放聲道選擇
// 返回值:		無
//=============================================================
void PlaySnd(unsigned SndIndex,unsigned DAC_Channel)
{
	BSR_StopRecognizer();								//停止識別器
	SACM_S480_Initial(1);								//初始化為自動播放
	SACM_S480_Play(SndIndex, DAC_Channel, 3);			//開始播放一段語音
	while((SACM_S480_Status()&0x0001)!= 0)				//是否播放完畢?
	{
		SACM_S480_ServiceLoop();						//解碼并填充隊(duì)列
		*P_Watchdog_Clear=0x0001;						//清看門狗
	}
	SACM_S480_Stop();									//停止播放
	BSR_InitRecognizer(BSR_MIC);						//初始化識別器
}

//=============================================================
// 語法格式:	int TrainWord(int WordID,int SndID);
// 實(shí)現(xiàn)功能:	訓(xùn)練一條指令
// 參數(shù):		WordID-指令編碼
//				SndID-指令提示音索引號
// 返回值:		無
//=============================================================
int TrainWord(unsigned int WordID,unsigned int SndID)
{
	int Result;
	PlaySnd(SndID,3);									//引導(dǎo)訓(xùn)練,播放指令對應(yīng)動作
	while(1)
	{
		Result = BSR_Train(WordID,BSR_TRAIN_TWICE);		//訓(xùn)練兩次,獲得訓(xùn)練結(jié)果
										
		if(Result==0)break;
		switch(Result)
		{
		case -1:										//沒有檢測出聲音
			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ù)庫滿
	 		return -4;	
		case -5: 			            				//檢測出聲音不同
			PlaySnd(S_CMDDIFF,3);
			return -5;
		case -6: 			            				//序號錯誤
			return -6;
		default:
			break;
		}
	}
	return 0;
}

//=============================================================
// 語法格式:	void TrainSD();
// 實(shí)現(xiàn)功能:	訓(xùn)練函數(shù)
// 參數(shù):		無
// 返回值:		無
//=============================================================
void TrainSD()
{
	while(TrainWord(RED_ON,S_ACT0) != 0);  		//訓(xùn)練第1個動作   前進(jìn)
	while(TrainWord(BLUE_ON,S_ACT1) != 0);  	//訓(xùn)練第2個動作   后退
	while(TrainWord(RED_OFF,S_ACT2) != 0);  	//訓(xùn)練第3個動作   左
	while(TrainWord(BLUE_OFF,S_ACT3) != 0);  	//訓(xùn)練第4個動作   右
	while(TrainWord(ALL_OFF,S_ACT4) != 0);		//訓(xùn)練第5個動作   停
}

//=============================================================
// 語法格式:	void StoreSD();
// 實(shí)現(xiàn)功能:	存儲語音模型函數(shù)
// 參數(shù):		無
// 返回值:		無
//=============================================================
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++)								//保存語音模型SD1(0xe000---0xe063)
		{
		    F_FlashWrite1Word(ulAddr,BSR_SDModel[i]);
			ulAddr+=1;												
		}
	}
}

//=============================================================
// 語法格式:	void StoreSD();
// 實(shí)現(xiàn)功能:	裝載語音模型函數(shù)
// 參數(shù):		無
// 返回值:		無
//=============================================================
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;					//裝載語音模型			
			p+=1;													
		}					
		g_Ret=BSR_ImportSDWord();				
		while(g_Ret!=0)							//模型裝載成功?
		g_Ret=BSR_ImportSDWord();								
	}
}
/*
//=============================================================
// 語法格式:	void paydistance(data);
// 實(shí)現(xiàn)功能:	播放串口數(shù)據(jù)
// 參數(shù):		無
// 返回值:		無
//=============================================================
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){			//沒有十位時不讀
	PlaySnd(decade+15,3);//
	PlaySnd(TEN,3);//10
	}else if(theunit > 0&& theunit <10){		//沒有個位時不讀
	PlaySnd(theunit+15,3);//
//	data = 0;//清除接收緩存
	}
}
*/
//=============================================================
// 語法格式:	void BSR(void);
// 實(shí)現(xiàn)功能:	辨識子函數(shù)
// 參數(shù):		無
// 返回值:		無
//=============================================================
void BSR(void)
{	
	int Result;									//辨識結(jié)果寄存
	Result = BSR_GetResult();					//獲得識別結(jié)果
	
	if(Result>0)								//有語音觸發(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);    //請注意
  			SPEED = 0;STOP = 0;			//轉(zhuǎn)彎后減到一檔  清除STOP次數(shù)
			break;
		case RED_OFF:			
			UartSendByte('A');
  			PlaySnd(S_ACT2,3);    //左轉(zhuǎn)
//  			PlaySnd(S_QZY,3);    //請注意
  			SPEED = 0;STOP = 0;			//轉(zhuǎn)彎后減到一檔	清除STOP次數(shù)		
			break;
		case BLUE_OFF:			
			UartSendByte('D');
  			PlaySnd(S_ACT3,3);    //右轉(zhuǎn)
//  			PlaySnd(S_QZY,3);    //請注意
  			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ù)請求
					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;
		}
	}
}
//=============================================================
// 語法格式:	int main(void);
// 實(shí)現(xiàn)功能:	主函數(shù)
// 參數(shù):		無
// 返回值:		無
//=============================================================
int main(void)
 {	
 	unsigned int BS_Flag;						//Train標(biāo)志位   空
	BSR_DeleteSDGroup(0);						//初始化存儲器RAM
	BS_Flag=*(unsigned int *)0xe000;			//讀存儲單元0xe000
	if(BS_Flag==0xffff)							//沒有經(jīng)過訓(xùn)練(0xe000內(nèi)容為0xffff)
	{
		TrainSD();								//訓(xùn)練
		StoreSD();								//存儲訓(xùn)練結(jié)果(語音模型)
	}
	else 										//經(jīng)過訓(xùn)練(0xe000內(nèi)容為0x0055)
	{
		LoadSD();								//語音模型載入識別器
	}
	
	PlaySnd(S_START,3);							//開始識別提示
	BSR_InitRecognizer(BSR_MIC);				//初始化識別器
	
	UART_Init();								//UART初始化

	__asm("IRQ ON");							//開中斷	
	while(1)
	{
		     
  		BSR();// 語音識別
  		*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);//測試聲音
		PlaySnd(S_ACT1,3);//測試聲音
		PlaySnd(S_ACT2,3);//測試聲音
		PlaySnd(S_ACT3,3);//測試聲音
		PlaySnd(S_ACT4,3);//測試聲音
		PlaySnd(S_RDY,3);//測試聲音
		PlaySnd(S_AGAIN,3);//測試聲音
		PlaySnd(S_NOISY,3);//測試聲音
		PlaySnd(S_START,3);//測試聲音
		PlaySnd(S_QZY,3);//測試聲音	
		PlaySnd(JIASU,3);//測試聲音	
		PlaySnd(QUANSU,3);//測試聲音
		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 平臺端程序

將下列程序上傳到 Carduino 控制器中

將下載到的壓縮文件解壓到到 Arduino IDE 軟件的 libraries 文件中(·····\arduino-1.7.6\libraries),啟動 Arduino IDE 選擇文件 -- 示例 -- RB-13K049_AS-4WD_yu_yin-master -- 打開 example 中的相應(yīng)例子程序,上傳到 Arduino UNO 控制器中,就可以實(shí)現(xiàn)代碼測試。操作方法下圖所示:
解壓過程

05L007A10.png
05L007A11.png
int srfPin = 15; //定義srfPin 發(fā)送引腳為15
int z; //定義全局變量z
int Distance; //定義距離寄存器存放測試距離數(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ā)送一個高脈沖開始測距
  delayMicroseconds(10); //保持10ms
  digitalWrite(srfPin, LOW); //在等待脈沖返回來之前發(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){ //判斷測試距離為1 至10CM
      Serial.print('a');} //發(fā)送字符'a'
    else if(Distance > 10 && Distance <= 15){ //判斷測試距離為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); //打開串口并設(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() //主程序開始
{ 
  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 '#': //測試當(dāng)前距離命令
          PLAYDISTANCE(); //發(fā)送當(dāng)前距離函數(shù)
          Serial.flush(); //刷新串口緩沖區(qū)數(shù)據(jù)
          break;
     default:
          break;
}
}

程序效果概述

  • 發(fā)出語音命令“前進(jìn)” - 凌陽板播報(bào)“前進(jìn)”,小車向前行進(jìn)
  • 第二次發(fā)出語音命令“前進(jìn)” - 凌陽板播報(bào)“加速前進(jìn)”,小車向前行進(jìn)
  • 第三次發(fā)出語音命令“前進(jìn)” - 凌陽板播報(bào)“全速前進(jìn)”,小車向前行進(jìn)
  • 發(fā)出語音命令“后退” - 凌陽板播報(bào)“后退,請注意”,小車向后行進(jìn)
  • 發(fā)出語音命令“左轉(zhuǎn)” - 凌陽板播報(bào)“左轉(zhuǎn)”,小車向左轉(zhuǎn)彎
  • 發(fā)出語音命令“右轉(zhuǎn)” - 凌陽板播報(bào)“右轉(zhuǎn)”,小車向右轉(zhuǎn)彎
  • 發(fā)出語音命令“停止” - 凌陽板播報(bào)“停止”,小車停止
  • 發(fā)出語音命令“停止 、 停止” - 凌陽板播報(bào)“停止,當(dāng)前距離 XX 厘米”,小車停止

注意: 1、盡量是錄音的人對小車進(jìn)行操作,不然錯誤率會提高
2、語音命令發(fā)出時,盡量保證吐字的清晰度,不然也會造成錯誤識別,小車不能按照語音進(jìn)行運(yùn)動
3、由于小車在向前行進(jìn)過程中,不能自動避障,所以請您注意操作距離,距離過長會造成藍(lán)牙斷開

產(chǎn)品相關(guān)推薦

Erweima.png

產(chǎn)品資料

下載鏈接:https://pan.baidu.com/s/189SAlN4wH-9cDhcUsnPKEw 提取碼:ag69

產(chǎn)品購買地址

Arduino 4WD 語音識別移動機(jī)器人平臺

周邊產(chǎn)品推薦

Arduino 4WD鋁合金移動平臺車燈套件
Arduino 光電碼盤 光電測速傳感器
Arduino 雙H橋直流電機(jī)驅(qū)動板

相關(guān)問題解答

AS-4WD 碰撞機(jī)器人如何安裝
4wd 紅外線巡線壁障車調(diào)試助手沒有反應(yīng)

相關(guān)學(xué)習(xí)資料

視頻:機(jī)器人調(diào)試助手無線操控AS-4WD輪式機(jī)器人
視頻:Arduino-4WD移動機(jī)器人尋線功能演示
視頻:Arduino-4WD移動機(jī)器人碰撞功能演示
視頻:Arduino-4WD移動機(jī)器人追光功能演示
視頻:Arduino-4WD移動機(jī)器人尋線與避障功能演示
視頻:Arduino-4WD移動機(jī)器人偵測避障功能演示
視頻:直流減速電機(jī)驅(qū)動實(shí)例
奧松機(jī)器人技術(shù)論壇