Go to the documentation of this file.00001 #include "bwi_services/SpeakMessage.h"
00002 #include <ros/ros.h>
00003 #include <string>
00004 #include <boost/regex.hpp>
00005 #include <boost/lexical_cast.hpp>
00006
00007 int32_t speed;
00008 int32_t pitch;
00009 std::string voice;
00010
00011
00012
00013 bool speak_message(bwi_services::SpeakMessage::Request &req,
00014 bwi_services::SpeakMessage::Response &res) {
00015
00016 std::string string_speed = boost::lexical_cast<std::string>(speed);
00017 std::string string_pitch = boost::lexical_cast<std::string>(pitch);
00018
00019 boost::regex sanitizeVoice("[^a-z-]");
00020 std::string voiceReplacement = "";
00021 std::string clean_voice = boost::regex_replace(voice, sanitizeVoice, voiceReplacement);
00022
00023 boost::regex sanitizeMessage("[^a-zA-Z\?!.,0-9-]");
00024 std::string messageReplacement = " ";
00025 std::string clean_message = boost::regex_replace(req.message, sanitizeMessage, messageReplacement);
00026
00027 ROS_INFO("Saying:%s", clean_message.c_str());
00028
00029 std::string command = "espeak -v " + clean_voice + " -s "
00030 + string_speed + " -p " + string_pitch + " \"" + clean_message + "\"";
00031
00032 int i = system(command.c_str());
00033
00034 res.result = i;
00035
00036 if (i != 0)
00037 {
00038 ROS_INFO("An error occured while calling espeak. Make sure espeak is installed and the voice is valid.");
00039 return false;
00040 }
00041
00042 return true;
00043 }
00044
00045 int main(int argc, char** argv) {
00046
00047 ros::init(argc, argv, "speak_message_service_node");
00048
00049 ros::NodeHandle nh("~");
00050
00051 nh.param<int32_t>("speed", speed, 160);
00052 nh.param<int32_t>("pitch", pitch, 50);
00053 nh.param<std::string>("voice", voice, "default");
00054
00055 ros::ServiceServer service = nh.advertiseService("speak_message", speak_message);
00056 ROS_INFO("SpeakMessage Service started");
00057 ROS_INFO("Speed:%s",(boost::lexical_cast<std::string>(speed)).c_str());
00058 ROS_INFO("Pitch:%s",(boost::lexical_cast<std::string>(pitch)).c_str());
00059 ROS_INFO("Voice:%s",voice.c_str());
00060
00061 ros::spin();
00062 ROS_INFO("Done spinning");
00063 return 0;
00064 }