Go to the documentation of this file.00001
00002
00003
00004
00005
00006 #include <fstream>
00007 #include <cstdlib>
00008 #include <sstream>
00009 #include <string>
00010
00011 #include <boost/filesystem.hpp>
00012 #include <boost/thread.hpp>
00013
00014
00015 #include <ros/ros.h>
00016 #include <dynamic_reconfigure/server.h>
00017 #include <voice_text/VoiceTextConfig.h>
00018 #include <voice_text/TextToSpeech.h>
00019
00020
00021 #ifdef USE_DUMMY_INCLUDE
00022 #include "dummy/vt_dummy.h"
00023 #else
00024 #include "/usr/vt/sayaka/M16/inc/vt_jpn.h"
00025 #endif
00026
00027 namespace fs = boost::filesystem;
00028
00029
00030 class VoiceText {
00031 public:
00032 typedef voice_text::VoiceTextConfig Config;
00033
00034 VoiceText() : nh_(), pnh_("~"), db_path_(""), license_path_(""), dyn_srv_(pnh_) {
00035 pnh_.param<std::string>("db_path", db_path_, "/usr/vt/sayaka/M16");
00036 pnh_.param<std::string>("license_path", license_path_, "");
00037
00038 dynamic_reconfigure::Server<Config>::CallbackType f =
00039 boost::bind(&VoiceText::config_callback, this, _1, _2);
00040 dyn_srv_.setCallback(f);
00041 }
00042
00043 ~VoiceText() {
00044 if (initialized_) {
00045 VT_UNLOADTTS_JPN(-1);
00046 }
00047 }
00048
00049 void config_callback(Config &config, uint32_t level) {
00050 boost::mutex::scoped_lock lock(mutex_);
00051 config_ = config;
00052 }
00053
00054 bool initialize() {
00055
00056 int ret = -1;
00057 char* db_path_char = (char*)calloc(std::strlen(db_path_.c_str())+1, sizeof(char));
00058 std::strcpy(db_path_char, db_path_.c_str());
00059 char* license_path_char = NULL;
00060 if (!license_path_.empty()) {
00061 license_path_char = (char*)calloc(std::strlen(license_path_.c_str())+1, sizeof(char));
00062 std::strcpy(license_path_char, license_path_.c_str());
00063 }
00064 ret = VT_LOADTTS_JPN((int)NULL, -1, db_path_char, license_path_char);
00065 free(db_path_char);
00066 if (!license_path_.empty()) free(license_path_char);
00067 if (ret != VT_LOADTTS_SUCCESS) {
00068 ROS_FATAL("Failed to load TTS engine (code %d)", ret);
00069 if (ret == -1) {
00070 ROS_FATAL("You must install voice_text library before building this library");
00071 }
00072 return false;
00073 }
00074
00075
00076 srv_ = nh_.advertiseService("text_to_speech", &VoiceText::text_to_speech, this);
00077
00078 ROS_INFO_STREAM("Advertised service text_to_speech");
00079
00080 return true;
00081 }
00082
00083 bool text_to_speech(voice_text::TextToSpeech::Request &req,
00084 voice_text::TextToSpeech::Response &res) {
00085 boost::mutex::scoped_lock lock(mutex_);
00086
00087 if (!fs::exists(fs::path(req.text_path))) {
00088 ROS_ERROR_STREAM("text file " << req.text_path << " not found");
00089 res.ok = false;
00090 return true;
00091 }
00092 std::ifstream ifs(req.text_path.c_str());
00093 std::string text = "", line = "";
00094 while (ifs && std::getline(ifs, line)) {
00095 text += line;
00096 }
00097 char* text_char = (char*)calloc(std::strlen(text.c_str())+1, sizeof(char));
00098 std::strcpy(text_char, text.c_str());
00099
00100 char* wave_char = (char*)calloc(std::strlen(req.wave_path.c_str())+1, sizeof(char));
00101 std::strcpy(wave_char, req.wave_path.c_str());
00102
00103 int ret = VT_TextToFile_JPN(VT_FILE_API_FMT_S16PCM_WAVE,
00104 text_char,
00105 wave_char,
00106 -1,
00107 config_.pitch,
00108 config_.speed,
00109 config_.volume,
00110 config_.pause,
00111 -1, -1);
00112
00113 free(text_char);
00114 free(wave_char);
00115
00116 if (ret != VT_FILE_API_SUCCESS) {
00117 ROS_ERROR("Failed to execute tts: (code: %d)", ret);
00118 res.ok = false;
00119 return true;
00120 }
00121
00122 res.ok = true;
00123 return true;
00124 }
00125
00126 ros::NodeHandle nh_, pnh_;
00127 boost::mutex mutex_;
00128 dynamic_reconfigure::Server<Config> dyn_srv_;
00129 Config config_;
00130 ros::ServiceServer srv_;
00131 bool initialized_;
00132 std::string db_path_, license_path_;
00133 };
00134
00135 int main(int argc, char** argv) {
00136 ros::init(argc, argv, "voice_text");
00137
00138 VoiceText vt;
00139 if (!vt.initialize()) {
00140 return 1;
00141 };
00142
00143 ros::spin();
00144
00145 return 0;
00146 }