voice_text.cpp
Go to the documentation of this file.
1 /*
2  * voice_text_server.cpp
3  * Author: Yuki Furuta <furushchev@jsk.imi.i.u-tokyo.ac.jp>
4  */
5 
6 #include <fstream>
7 #include <cstdlib>
8 #include <sstream>
9 #include <string>
10 
11 #include <boost/filesystem.hpp>
12 #include <boost/thread.hpp>
13 
14 // ROS
15 #include <ros/ros.h>
16 #include <dynamic_reconfigure/server.h>
17 #include <voice_text/VoiceTextConfig.h>
18 #include <voice_text/TextToSpeech.h>
19 
20 // VoiceText
21 #ifdef USE_DUMMY_INCLUDE
22 #include "dummy/vt_dummy.h"
23 #else
24 #include "/usr/vt/sayaka/M16/inc/vt_jpn.h"
25 #endif
26 
27 namespace fs = boost::filesystem;
28 
29 
30 class VoiceText {
31 public:
32  typedef voice_text::VoiceTextConfig Config;
33 
34  VoiceText() : nh_(), pnh_("~"), db_path_(""), license_path_(""), dyn_srv_(pnh_) {
35  pnh_.param<std::string>("db_path", db_path_, "/usr/vt/sayaka/M16");
36  pnh_.param<std::string>("license_path", license_path_, "");
37 
38  dynamic_reconfigure::Server<Config>::CallbackType f =
39  boost::bind(&VoiceText::config_callback, this, _1, _2);
40  dyn_srv_.setCallback(f);
41  }
42 
44  if (initialized_) {
45  VT_UNLOADTTS_JPN(-1);
46  }
47  }
48 
49  void config_callback(Config &config, uint32_t level) {
50  boost::mutex::scoped_lock lock(mutex_);
51  config_ = config;
52  }
53 
54  bool initialize() {
55  // initialize voice text
56  int ret = -1;
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;
60  if (!license_path_.empty()) {
61  license_path_char = (char*)calloc(std::strlen(license_path_.c_str())+1, sizeof(char));
62  std::strcpy(license_path_char, license_path_.c_str());
63  }
64  ret = VT_LOADTTS_JPN((int)NULL, -1, db_path_char, license_path_char);
65  free(db_path_char);
66  if (!license_path_.empty()) free(license_path_char);
67  if (ret != VT_LOADTTS_SUCCESS) {
68  ROS_FATAL("Failed to load TTS engine (code %d)", ret);
69  if (ret == -1) {
70  ROS_FATAL("You must install voice_text library before building this library");
71  }
72  return false;
73  }
74 
75  // advertise service
76  srv_ = nh_.advertiseService("text_to_speech", &VoiceText::text_to_speech, this);
77 
78  ROS_INFO_STREAM("Advertised service text_to_speech");
79 
80  return true;
81  }
82 
83  bool text_to_speech(voice_text::TextToSpeech::Request &req,
84  voice_text::TextToSpeech::Response &res) {
85  boost::mutex::scoped_lock lock(mutex_);
86  // load text from file
87  if (!fs::exists(fs::path(req.text_path))) {
88  ROS_ERROR_STREAM("text file " << req.text_path << " not found");
89  res.ok = false;
90  return true;
91  }
92  std::ifstream ifs(req.text_path.c_str());
93  std::string text = "", line = "";
94  while (ifs && std::getline(ifs, line)) {
95  text += line;
96  }
97  char* text_char = (char*)calloc(std::strlen(text.c_str())+1, sizeof(char));
98  std::strcpy(text_char, text.c_str());
99 
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());
102 
104  text_char,
105  wave_char,
106  -1,
107  config_.pitch,
108  config_.speed,
109  config_.volume,
110  config_.pause,
111  -1, -1);
112 
113  free(text_char);
114  free(wave_char);
115 
116  if (ret != VT_FILE_API_SUCCESS) {
117  ROS_ERROR("Failed to execute tts: (code: %d)", ret);
118  res.ok = false;
119  return true;
120  }
121 
122  res.ok = true;
123  return true;
124  }
125 
127  boost::mutex mutex_;
128  dynamic_reconfigure::Server<Config> dyn_srv_;
129  Config config_;
132  std::string db_path_, license_path_;
133 };
134 
135 int main(int argc, char** argv) {
136  ros::init(argc, argv, "voice_text");
137 
138  VoiceText vt;
139  if (!vt.initialize()) {
140  return 1;
141  };
142 
143  ros::spin();
144 
145  return 0;
146 }
void VT_UNLOADTTS_JPN(int)
Definition: vt_dummy.cpp:4
Config config_
Definition: voice_text.cpp:129
#define ROS_FATAL(...)
int VT_LOADTTS_JPN(int, int, char *, char *)
Definition: vt_dummy.cpp:5
f
ros::ServiceServer srv_
Definition: voice_text.cpp:130
bool text_to_speech(voice_text::TextToSpeech::Request &req, voice_text::TextToSpeech::Response &res)
Definition: voice_text.cpp:83
boost::mutex mutex_
Definition: voice_text.cpp:127
ros::NodeHandle nh_
Definition: voice_text.cpp:126
bool initialized_
Definition: voice_text.cpp:131
std::string license_path_
Definition: voice_text.cpp:132
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void config_callback(Config &config, uint32_t level)
Definition: voice_text.cpp:49
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
voice_text::VoiceTextConfig Config
Definition: voice_text.cpp:32
bool param(const std::string &param_name, T &param_val, const T &default_val) const
ROSCPP_DECL void spin()
std::string db_path_
Definition: voice_text.cpp:132
dynamic_reconfigure::Server< Config > dyn_srv_
Definition: voice_text.cpp:128
int main(int argc, char **argv)
Definition: voice_text.cpp:135
int VT_LOADTTS_SUCCESS
Definition: vt_dummy.h:7
#define ROS_INFO_STREAM(args)
int VT_FILE_API_SUCCESS
Definition: vt_dummy.h:8
int VT_TextToFile_JPN(int, char *, char *, int, int, int, int, int, int, int)
Definition: vt_dummy.cpp:11
#define ROS_ERROR_STREAM(args)
ros::NodeHandle pnh_
Definition: voice_text.cpp:126
#define ROS_ERROR(...)
bool initialize()
Definition: voice_text.cpp:54
int VT_FILE_API_FMT_S16PCM_WAVE
Definition: vt_dummy.h:9


voice_text
Author(s): Kei Okada
autogenerated on Wed Jul 10 2019 03:47:19