语音控制机器人小车运动科大讯飞SDK

在前面文章小车实现语音识别的基础之上,对小车实现语音控制运动

修改CMakeLists.txt文件

语音控制机器人小车运动科大讯飞SDK_第1张图片
在末尾加上以下代码:

add_executable(sub_word src/sub_word.cpp)
target_link_libraries(sub_word ${catkin_LIBRARIES} )

修改发布文件

打开xfei_asr/src目录下的int_publish_speak.cpp文件,然后将下面的代码覆盖进去,请将appid填写为你在讯飞那申请的appid 。修改后的发布文件,将是全程自动唤醒不再是每次唤醒都需要手动输入代码。

#include 

#include 

#include 

#include 

#include "qisr.h"

#include "msp_cmn.h"

#include "msp_errors.h"

#include "speech_recognizer.h"

#include 



#include "ros/ros.h"

#include "std_msgs/String.h"



#define FRAME_LEN   640

#define BUFFER_SIZE 4096



int wakeupFlag   = 1 ;

int resultFlag   = 0 ;



static void show_result(char *string, char is_over)

{

    resultFlag=1;   

    printf("\rResult: [ %s ]", string);

    if(is_over)

        putchar('\n');

}



static char *g_result = NULL;

static unsigned int g_buffersize = BUFFER_SIZE;



void on_result(const char *result, char is_last)

{

    if (result) {

        size_t left = g_buffersize - 1 - strlen(g_result);

        size_t size = strlen(result);

        if (left < size) {

            g_result = (char*)realloc(g_result, g_buffersize + BUFFER_SIZE);

            if (g_result)

                g_buffersize += BUFFER_SIZE;

            else {

                printf("mem alloc failed\n");

                return;

            }

        }

        strncat(g_result, result, size);

        show_result(g_result, is_last);

    }

}



void on_speech_begin()

{

    if (g_result)

    {

        free(g_result);

    }

    g_result = (char*)malloc(BUFFER_SIZE);

    g_buffersize = BUFFER_SIZE;

    memset(g_result, 0, g_buffersize);



    printf("Start Listening...\n");

}

void on_speech_end(int reason)

{

    if (reason == END_REASON_VAD_DETECT)

        printf("\nSpeaking done \n");

    else

        printf("\nRecognizer error %d\n", reason);

}



/* demo recognize the audio from microphone */

static void demo_mic(const char* session_begin_params)

{

    int errcode;

    int i = 0;



    struct speech_rec iat;



    struct speech_rec_notifier recnotifier = {

        on_result,

        on_speech_begin,

        on_speech_end

    };



    errcode = sr_init(&iat, session_begin_params, SR_MIC, &recnotifier);

    if (errcode) {

        printf("speech recognizer init failed\n");

        return;

    }

    errcode = sr_start_listening(&iat);

    if (errcode) {

        printf("start listen failed %d\n", errcode);

    }

    /* demo 10 seconds recording */

    while(i++ < 3)

        sleep(1);

    errcode = sr_stop_listening(&iat);

    if (errcode) {

        printf("stop listening failed %d\n", errcode);

    }



    sr_uninit(&iat);

}





/* main thread: start/stop record ; query the result of recgonization.

 * record thread: record callback(data write)

 * helper thread: ui(keystroke detection)

 */



void WakeUp(const std_msgs::String::ConstPtr& msg)

{

    printf("waking up\r\n");

    sleep(10000);

    wakeupFlag=1;

}



int main(int argc, char* argv[])

{

    // 初始化ROS

    ros::init(argc, argv, "voiceRecognition");

    ros::NodeHandle n;

    ros::Rate loop_rate(10);



    // 声明Publisher和Subscriber

    // 订阅唤醒语音识别的信号

    ros::Subscriber wakeUpSub = n.subscribe("voiceWakeup", 1000, WakeUp);   

    // 订阅唤醒语音识别的信号    

    ros::Publisher voiceWordsPub = n.advertise<std_msgs::String>("voiceWords", 1000);  



    ROS_INFO("Sleeping...");

    int count=0;

    while(ros::ok())

    {

        // 语音识别唤醒

        if (wakeupFlag){

            ROS_INFO("Wakeup...");

            int ret = MSP_SUCCESS;

            const char* login_params = "appid =, work_dir = .";



            const char* session_begin_params =

                "sub = iat, domain = iat, language = zh_cn, "

                "accent = mandarin, sample_rate = 16000, "

                "result_type = plain, result_encoding = utf8";



            ret = MSPLogin(NULL, NULL, login_params);

            if(MSP_SUCCESS != ret){

                MSPLogout();

                printf("MSPLogin failed , Error code %d.\n",ret);

            }



            printf("Demo recognizing the speech from microphone\n");

            printf("Speak in 10 seconds\n");



            demo_mic(session_begin_params);



            printf("10 sec passed\n");

        

            wakeupFlag=1;

            MSPLogout();

        }



        // 语音识别完成

        if(resultFlag){

            resultFlag=0;

            std_msgs::String msg;

            msg.data = g_result;

            voiceWordsPub.publish(msg);

        }



        ros::spinOnce();

        loop_rate.sleep();

        count++;

    }



exit:

    MSPLogout(); // Logout...



    return 0;

}

添加指令文件

创建新的文件命名为sub_word.cpp 粘贴以下代码。具体识别控制指令执行请按需修改

#include
#include
#include
#include
#include
#include

using namespace std;
ros::Publisher pub;
geometry_msgs::Twist vel_cmd;
pthread_t pth_[5];


void* vel_ctr(void* arg)
{
    while(true)
    {
        pub.publish(vel_cmd);
        ros::spinOnce();
        sleep(1);
    }
    return 0;
}

void callback(const std_msgs::String::ConstPtr& msg)
{
    cout<<"接收到指令:"<<msg->data.c_str()<<endl;
    string str1 = msg->data.c_str();
    string str2 = "前进。";
    string str2_1 = "up.";
    string str3 = "后退。";
    string str3_1 = "back.";
    string str4 = "左转。";
    string str4_1 = "left.";
    string str5 = "右转。";
    string str5_1 = "right.";
    string str6 = "停。";
    string str6_1 = "stop.";
    if(str1 == str2 || str1==str2_1)
    {
        vel_cmd.linear.x = 1;
        vel_cmd.angular.z = 0;
        pthread_create(&pth_[0],NULL,vel_ctr,NULL);
    }
    if(str1 == str3 || str1 == str3_1)
    {
        vel_cmd.linear.x = -1;
        vel_cmd.angular.z = 0;
        pthread_create(&pth_[1],NULL,vel_ctr,NULL);
    }
    if(str1 == str4 || str1 == str4_1)
    {
        vel_cmd.linear.x = 0;
        vel_cmd.angular.z = 1;
        pthread_create(&pth_[2],NULL,vel_ctr,NULL);
    }
    if(str1 == str5 || str1 == str5_1)
    {
        vel_cmd.linear.x = 0;
        vel_cmd.angular.z = -1;
        pthread_create(&pth_[3],NULL,vel_ctr,NULL);
    }
    if(str1 == str6 || str1 == str6_1)
    {
        vel_cmd.linear.x = 0;
        vel_cmd.angular.z = 0;
        pthread_create(&pth_[0],NULL,vel_ctr,NULL);
    }    
}

int main(int argc, char** argv)
{
 

    ros::init(argc, argv, "sub_word");
    ros::NodeHandle n;
    
    pub = n.advertise<geometry_msgs::Twist>("/ria_base_controller/cmd_vel",10);
    ros::Subscriber sub = n.subscribe("voiceWords",10,callback);
cout<<"语音控制程序已开启"<<endl;
cout<<"中文关键字控制字:前进 后退 左转 右转 停"<<endl;
cout<<"英文关键字控制字:UP BACK LEFT RIGHT STOP"<<endl;
cout<<"程序将识别标准的普通话和英语单词"<<endl;


    ros::spin();
}

测试

测试前记得编译啊

依次在终端执行以下命令,然后对麦克风说控制命令。建议打开翻译等软件说标准的普通话或英文,识别度更高

roslaunch e100_sim gazebo.launch
rosrun xfei_asr iat_publish_speak
rosrun xfei_asr sub_word

成功控制小车运动。
语音控制机器人小车运动科大讯飞SDK_第2张图片

你可能感兴趣的:(ROS,ROS,语音控制)