ROS学习笔记-使用C++类用以编程(以机器人语音交互为例)

voice_control_class.h 头文件:

使用到的文本合成等函数以及相关数据结构,以及定义一个类,定义了类的成员变量和方法

#ifndef EXAMPLE_ROS_CLASS_H_
#define EXAMPLE_ROS_CLASS_H_

#include <math.h>
#include <string.h>
#include <stdlib.h>
#include <unistd.h>
#include <string>
#include <vector>

#include <ros/ros.h> 
#include <std_msgs/String.h> 
#include <std_msgs/Float32.h>
#include <std_srvs/Trigger.h> 
#include <geometry_msgs/Twist.h>

#include "robot_voice/qtts.h"
#include "robot_voice/msp_cmn.h"
#include "robot_voice/msp_errors.h"


class voice_control_class
{
public:
    voice_control_class(ros::NodeHandle* nodehandle); 
    
private:

    ros::NodeHandle nh_; 
    ros::Subscriber minimal_subscriber_; 
    ros::ServiceServer minimal_service_;
    ros::Publisher  minimal_publisher_;
    
    std_msgs::String::ConstPtr val_from_subscriber_; 
    
    void initializeSubscribers(); 
    void initializePublishers();
    void initializeServices();
    
    void subscriberCallback(const std_msgs::String::ConstPtr& msg); 
    bool serviceCallback(std_srvs::TriggerRequest& request, std_srvs::TriggerResponse& response);
}; 

/* wav音频头部格式 */
typedef struct _wave_pcm_hdr
{
	char            riff[4];                // = "RIFF"
	int		size_8;                 // = FileSize - 8
	char            wave[4];                // = "WAVE"
	char            fmt[4];                 // = "fmt "
	int		fmt_size;		// = 下一个结构体的大小 : 16

	short int       format_tag;             // = PCM : 1
	short int       channels;               // = 通道数 : 1
	int		samples_per_sec;        // = 采样率 : 8000 | 6000 | 11025 | 16000
	int		avg_bytes_per_sec;      // = 每秒字节数 : samples_per_sec * bits_per_sample / 8
	short int       block_align;            // = 每采样点字节数 : wBitsPerSample / 8
	short int       bits_per_sample;        // = 量化比特数: 8 | 16

	char            data[4];                // = "data";
	int		data_size;              // = 纯数据长度 : FileSize - 44 
} wave_pcm_hdr;

/* 默认wav音频头部数据 */
wave_pcm_hdr default_wav_hdr = 
{
	{ 'R', 'I', 'F', 'F' },
	0,
	{'W', 'A', 'V', 'E'},
	{'f', 'm', 't', ' '},
	16,
	1,
	1,
	16000,
	32000,
	2,
	16,
	{'d', 'a', 't', 'a'},
	0  
};
std::string to_string(int val) 
{
    char buf[20];
    sprintf(buf, "%d", val);
    return std::string(buf);
}

/* 文本合成 */
int text_to_speech(const char* src_text, const char* des_path, const char* params)
{
	int          ret          = -1;
	FILE*        fp           = NULL;
	const char*  sessionID    = NULL;
	unsigned int audio_len    = 0;
	wave_pcm_hdr wav_hdr      = default_wav_hdr;
	int          synth_status = MSP_TTS_FLAG_STILL_HAVE_DATA;

	if (NULL == src_text || NULL == des_path)
	{
		printf("params is error!\n");
		return ret;
	}
	fp = fopen(des_path, "wb");
	if (NULL == fp)
	{
		printf("open %s error.\n", des_path);
		return ret;
	}
	/* 开始合成 */
	sessionID = QTTSSessionBegin(params, &ret);
	if (MSP_SUCCESS != ret)
	{
		printf("QTTSSessionBegin failed, error code: %d.\n", ret);
		fclose(fp);
		return ret;
	}
	ret = QTTSTextPut(sessionID, src_text, (unsigned int)strlen(src_text), NULL);
	if (MSP_SUCCESS != ret)
	{
		printf("QTTSTextPut failed, error code: %d.\n",ret);
		QTTSSessionEnd(sessionID, "TextPutError");
		fclose(fp);
		return ret;
	}
	printf("正在合成 ...\n");
	fwrite(&wav_hdr, sizeof(wav_hdr) ,1, fp); //添加wav音频头,使用采样率为16000
	while (1) 
	{
		/* 获取合成音频 */
		const void* data = QTTSAudioGet(sessionID, &audio_len, &synth_status, &ret);
		if (MSP_SUCCESS != ret)
			break;
		if (NULL != data)
		{
			fwrite(data, audio_len, 1, fp);
		    wav_hdr.data_size += audio_len; //计算data_size大小
		}
		if (MSP_TTS_FLAG_DATA_END == synth_status)
			break;
		printf(">");
		usleep(150*1000); //防止频繁占用CPU
	}
	printf("\n");
	if (MSP_SUCCESS != ret)
	{
		printf("QTTSAudioGet failed, error code: %d.\n",ret);
		QTTSSessionEnd(sessionID, "AudioGetError");
		fclose(fp);
		return ret;
	}
	/* 修正wav文件头数据的大小 */
	wav_hdr.size_8 += wav_hdr.data_size + (sizeof(wav_hdr) - 8);
	
	/* 将修正过的数据写回文件头部,音频文件为wav格式 */
	fseek(fp, 4, 0);
	fwrite(&wav_hdr.size_8,sizeof(wav_hdr.size_8), 1, fp); //写入size_8的值
	fseek(fp, 40, 0); //将文件指针偏移到存储data_size值的位置
	fwrite(&wav_hdr.data_size,sizeof(wav_hdr.data_size), 1, fp); //写入data_size的值
	fclose(fp);
	fp = NULL;
	/* 合成完毕 */
	ret = QTTSSessionEnd(sessionID, "Normal");
	if (MSP_SUCCESS != ret)
	{
		printf("QTTSSessionEnd failed, error code: %d.\n",ret);
	}

	return ret;
}

void toExit()
{
    printf("按任意键退出 ...\n");
    getchar();
    MSPLogout(); //退出登录
}

#endif  
voice_control_class.c 类的实现:

包含了上述头文件,在构造函数中封装必要的初始化代码,以及编写成员函数,专注于实现语音控制相关的ROS控制

#include "voice_control_class.h"

voice_control_class::voice_control_class(ros::NodeHandle* nodehandle):nh_(*nodehandle)
{ 
    ROS_INFO("in class constructor of voice_control_class");
    initializeSubscribers(); 
    initializePublishers();
    initializeServices();
    // val_to_remember_=0.0; 
}

void voice_control_class::initializeSubscribers()
{
    ROS_INFO("Initializing Subscribers");
    minimal_subscriber_ = nh_.subscribe("voiceWords", 1000, &voice_control_class::subscriberCallback,this);  
}
void voice_control_class::initializeServices()
{
    ROS_INFO("Initializing Services");
}
void voice_control_class::initializePublishers()
{
    ROS_INFO("Initializing Publishers");
    minimal_publisher_ = nh_.advertise<geometry_msgs::Twist>("/cmd_vel", 1, true); 
}
void voice_control_class::subscriberCallback(const std_msgs::String::ConstPtr& msg) {

    char cmd[2000];
    const char* text;
    int         ret                  = MSP_SUCCESS;
    const char* session_begin_params = "voice_name = xiaoyan, text_encoding = utf8, sample_rate = 16000, speed = 50, volume = 50, pitch = 50, rdn = 2";
    const char* filename             = "tts_sample.wav"; //合成的语音文件名称

    std::cout<<"I heard :"<<msg->data.c_str()<<std::endl;

    geometry_msgs::Twist output_msg;
    output_msg.linear.x=0; 
    output_msg.linear.y=0;
    output_msg.linear.z=0;
    output_msg.angular.x=0;
    output_msg.angular.y=0;
    output_msg.angular.z=0;

    double speed = 0.0; // 0m/s speed command
    double yaw_rate = 0.0; //0.0 rad/sec yaw rate command

    std::string dataString = msg->data;

    if(dataString.find("你是谁") != std::string::npos 
    || dataString.find("名字") != std::string::npos)
    {
        char nameString[100] = "我是mobot机器人";
        text = nameString;
        std::cout<<text<<std::endl;
    }
    else if(dataString.find("前") != std::string::npos )
    {
        char eageString[100] = "前进";
        text = eageString;
        std::cout<<text<<std::endl;
		speed = 1.0; 
		yaw_rate = 0.0;
    }     
    else if(dataString.find("后") != std::string::npos )
    {
        char eageString[100] = "后退";
        text = eageString;
        std::cout<<text<<std::endl;
		speed = -1.0; 
		yaw_rate = 0.0;
    }    
	else if(dataString.find("左") != std::string::npos )
    {
        char eageString[100] = "向左";
        text = eageString;
        std::cout<<text<<std::endl;
		speed = 1.0; 
		yaw_rate = 0.33;
    }    
	else if(dataString.find("右") != std::string::npos )
    {
        char eageString[100] = "向右";
        text = eageString;
        std::cout<<text<<std::endl;
		speed = 1.0; 
		yaw_rate = -0.5; 
    }
	else if(dataString.find("停") != std::string::npos )
    {
        char eageString[100] = "停止";
        text = eageString;
        std::cout<<text<<std::endl;
		speed = 0.0; 
		yaw_rate = 0.0; 
    }
    else if(dataString.find("时间") != std::string::npos)
    {
        //获取当前时间
        struct tm *ptm; 
        long ts; 

        ts = time(NULL); 
        ptm = localtime(&ts); 
        std::string string = "现在时间" + to_string(ptm-> tm_hour) + "点" + to_string(ptm-> tm_min) + "分";

        char timeString[40] = {0};
        string.copy(timeString, sizeof(string), 0);
        text = timeString;
        std::cout<<text<<std::endl;
    }
    else
    {
        text = msg->data.c_str();
    }

    /* 文本合成 */
    printf("开始合成 ...\n");
    ret = text_to_speech(text, filename, session_begin_params);
    if (MSP_SUCCESS != ret)
    {
        printf("text_to_speech failed, error code: %d.\n", ret);
    }
    printf("合成完毕\n");
 
    popen("play tts_sample.wav","r");


    output_msg.linear.x=speed; 
    output_msg.angular.z=yaw_rate;
    int i=10;
    while(i--)
    {
        minimal_publisher_.publish(output_msg);  
		usleep(5000); //防止频繁占用CPU
    }
    
}

bool voice_control_class::serviceCallback(std_srvs::TriggerRequest& request, std_srvs::TriggerResponse& response) {
    ROS_INFO("service callback activated");
    response.success = true; // boring, but valid response info
    response.message = "here is a response string";
    return true;
}


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

	int         ret                  = MSP_SUCCESS;
	const char* login_params         = "appid = 594a7b46, work_dir = .";
	ret = MSPLogin(NULL, NULL, login_params);
	if (MSP_SUCCESS != ret)
	{
		printf("MSPLogin failed, error code: %d.\n", ret);
        toExit();
	}
	printf("\n###########################################################################\n");
	printf("## 语音合成(Text To Speech,TTS)技术能够自动将任意文字实时转换为连续的 ##\n");
	printf("## 自然语音,是一种能够在任何时间、任何地点,向任何人提供语音信息服务的  ##\n");
	printf("## 高效便捷手段,非常符合信息时代海量数据、动态更新和个性化查询的需求。  ##\n");
	printf("###########################################################################\n\n");

    ros::init(argc, argv, "voiceControl"); //node name
    ros::NodeHandle nh;
    ROS_INFO("main: instantiating an object of type voiceControl");
    voice_control_class voice_control_class(&nh);  
    ROS_INFO("main: going into spin; let the callbacks do all the work");
    ros::spin();

exit:
	printf("按任意键退出 ...\n");
	getchar();
	MSPLogout(); //退出登录

	return 0;
}

后记:

关于使用C++类用于ROS通信的编程方式带来的好处就不细讲了,具体可参照官方wiki:
http://wiki.ros.org/roscpp/Overview/Publishers and Subscribers

  • 0
    点赞
  • 8
    收藏
    觉得还不错? 一键收藏
  • 0
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值