11 #include <boost/filesystem.hpp> 12 #include <boost/thread.hpp> 16 #include <dynamic_reconfigure/server.h> 17 #include <voice_text/VoiceTextConfig.h> 18 #include <voice_text/TextToSpeech.h> 21 #ifdef USE_DUMMY_INCLUDE 24 #include "/usr/vt/sayaka/M16/inc/vt_jpn.h" 27 namespace fs = boost::filesystem;
32 typedef voice_text::VoiceTextConfig
Config;
38 dynamic_reconfigure::Server<Config>::CallbackType
f =
50 boost::mutex::scoped_lock lock(
mutex_);
57 char* db_path_char = (
char*)calloc(std::strlen(
db_path_.c_str())+1,
sizeof(
char));
58 std::strcpy(db_path_char,
db_path_.c_str());
59 char* license_path_char = NULL;
61 license_path_char = (
char*)calloc(std::strlen(
license_path_.c_str())+1,
sizeof(
char));
64 ret =
VT_LOADTTS_JPN((
int)NULL, -1, db_path_char, license_path_char);
68 ROS_FATAL(
"Failed to load TTS engine (code %d)", ret);
70 ROS_FATAL(
"You must install voice_text library before building this library");
84 voice_text::TextToSpeech::Response &res) {
85 boost::mutex::scoped_lock lock(
mutex_);
87 if (!fs::exists(fs::path(req.text_path))) {
92 std::ifstream ifs(req.text_path.c_str());
93 std::string text =
"", line =
"";
94 while (ifs && std::getline(ifs, line)) {
97 char* text_char = (
char*)calloc(std::strlen(text.c_str())+1,
sizeof(
char));
98 std::strcpy(text_char, text.c_str());
100 char* wave_char = (
char*)calloc(std::strlen(req.wave_path.c_str())+1,
sizeof(
char));
101 std::strcpy(wave_char, req.wave_path.c_str());
117 ROS_ERROR(
"Failed to execute tts: (code: %d)", ret);
135 int main(
int argc,
char** argv) {
void VT_UNLOADTTS_JPN(int)
int VT_LOADTTS_JPN(int, int, char *, char *)
bool text_to_speech(voice_text::TextToSpeech::Request &req, voice_text::TextToSpeech::Response &res)
std::string license_path_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void config_callback(Config &config, uint32_t level)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
voice_text::VoiceTextConfig Config
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
dynamic_reconfigure::Server< Config > dyn_srv_
int main(int argc, char **argv)
#define ROS_INFO_STREAM(args)
int VT_TextToFile_JPN(int, char *, char *, int, int, int, int, int, int, int)
#define ROS_ERROR_STREAM(args)
int VT_FILE_API_FMT_S16PCM_WAVE