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