Go to the documentation of this file.00001 #include <ros/ros.h>
00002 #include <actionlib/server/simple_action_server.h>
00003 #include <std_msgs/String.h>
00004 #include <cob_srvs/Trigger.h>
00005 #include <cob_sound/SayAction.h>
00006 #include <cob_sound/SayText.h>
00007
00008 class SayAction
00009 {
00010 protected:
00011
00012 ros::NodeHandle nh_;
00013 actionlib::SimpleActionServer<cob_sound::SayAction> as_;
00014 ros::ServiceServer srvServer_;
00015 ros::ServiceServer srvServer_mute_;
00016 ros::ServiceServer srvServer_unmute_;
00017 ros::Subscriber sub_;
00018 std::string action_name_;
00019 bool mute_;
00020
00021 public:
00022
00023 SayAction(std::string name) :
00024 as_(nh_, name, boost::bind(&SayAction::as_cb, this, _1), false),
00025 action_name_(name)
00026 {
00027 as_.start();
00028 srvServer_ = nh_.advertiseService("/say", &SayAction::service_cb, this);
00029 srvServer_mute_ = nh_.advertiseService("mute", &SayAction::service_cb_mute, this);
00030 srvServer_unmute_ = nh_.advertiseService("unmute", &SayAction::service_cb_unmute, this);
00031 sub_ = nh_.subscribe("/say", 1000, &SayAction::topic_cb, this);
00032 mute_ = false;
00033 }
00034
00035 ~SayAction(void)
00036 {
00037 }
00038
00039 void as_cb(const cob_sound::SayGoalConstPtr &goal)
00040 {
00041 bool ret = say(goal->text.data);
00042 if (ret)
00043 {
00044 as_.setSucceeded();
00045 }
00046 else
00047 {
00048 as_.setAborted();
00049 }
00050
00051 }
00052
00053 bool service_cb(cob_sound::SayText::Request &req,
00054 cob_sound::SayText::Response &res )
00055 {
00056 say(req.text);
00057 return true;
00058 }
00059
00060 void topic_cb(const std_msgs::String::ConstPtr& msg)
00061 {
00062 say(msg->data.c_str());
00063 }
00064
00065 bool service_cb_mute(cob_srvs::Trigger::Request &req,
00066 cob_srvs::Trigger::Response &res )
00067 {
00068 mute_ = true;
00069 res.success.data = true;
00070 return true;
00071 }
00072
00073 bool service_cb_unmute(cob_srvs::Trigger::Request &req,
00074 cob_srvs::Trigger::Response &res )
00075 {
00076 mute_ = false;
00077 res.success.data = true;
00078 return true;
00079 }
00080
00081 bool say(std::string text)
00082 {
00083 if (mute_)
00084 {
00085 ROS_WARN("Sound is set to mute. You will hear nothing.");
00086 return true;
00087 }
00088
00089 ROS_INFO("Saying: %s", text.c_str());
00090 std::string mode;
00091 std::string command;
00092 std::string cepstral_conf;
00093 nh_.param<std::string>("/sound_controller/mode",mode,"festival");
00094 nh_.param<std::string>("/sound_controller/cepstral_settings",cepstral_conf,"\"speech/rate=170\"");
00095 if (mode == "cepstral")
00096 {
00097 command = "/opt/swift/bin/swift -p " + cepstral_conf + " " + text;
00098 }
00099 else
00100 {
00101 command = "echo " + text + " | text2wave | aplay -q";
00102 }
00103 if (system(command.c_str()) != 0)
00104 {
00105 ROS_ERROR("Could not play sound");
00106 return false;
00107 }
00108 return true;
00109 }
00110
00111
00112 };
00113
00114
00115 int main(int argc, char** argv)
00116 {
00117 ros::init(argc, argv, "cob_sound");
00118
00119 SayAction say("say");
00120 ros::spin();
00121
00122 return 0;
00123 }
00124