talking_watch_sample_en.cpp
Go to the documentation of this file.
00001 #include <iostream>
00002 #include <sstream>
00003 #include <boost/regex.hpp>
00004 #include <boost/date_time/posix_time/posix_time.hpp>
00005 #include <ros/ros.h>
00006 #include "rospeex_if/rospeex.h"
00007 
00008 static rospeex::Interface interface;
00009 
00010 void sr_response( const std::string& msg )
00011 {
00012         using boost::posix_time::ptime;
00013         using boost::posix_time::second_clock;
00014         std::string msg_tr(msg);
00015 
00016         std::cerr << "you said : " << msg << std::endl;
00017         std::transform(msg_tr.begin(), msg_tr.end(), msg_tr.begin(), ::tolower);
00018 
00019         boost::regex time_reg(".*what time.+");
00020         if ( boost::regex_match(msg_tr, time_reg) ) {
00021                 std::string text = "";
00022                 ptime now = second_clock::local_time();
00023                 std::stringstream ss;
00024                 ss << "It's " << now.time_of_day().hours() << ":" << now.time_of_day().minutes() << ".";
00025                 text = ss.str();
00026                 std::cerr << "rospeex reply : " << text << std::endl;
00027                 interface.say(text, "en", "nict");
00028         }
00029 }
00030 
00031 int main( int argc, char** argv )
00032 {
00033         ros::init(argc, argv, "sr_ss_demo");
00034 
00035         interface.init();
00036         interface.registerSRResponse( sr_response );
00037         interface.setSPIConfig("en", "nict");
00038         ros::spin();
00039         return 0;
00040 }


rospeex_samples
Author(s): Komei Sugiura
autogenerated on Thu Jun 6 2019 18:53:15