gcloud_speech_action_node.cc
Go to the documentation of this file.
00001 #include <functional>
00002 #include <memory>
00003 #include <mutex>
00004 
00005 #include "actionlib/server/simple_action_server.h"
00006 #include "gcloud_speech_msgs/SpeechToTextAction.h"
00007 #include "gcloud_speech_msgs/RecognitionHypothesis.h"
00008 #include "gcloud_speech_msgs/LinearPcm16Le16000Audio.h"
00009 
00010 #include "cogrob/cloud/basic/defaults.h"
00011 #include "cogrob/cloud/speech/google_speech.h"
00012 #include "cogrob/cloud/speech/google_speech_interface.h"
00013 #include "third_party/gflags.h"
00014 
00015 #include "speech_to_text_action_handler.h"
00016 
00017 namespace speech = ::cogrob::cloud::speech;
00018 
00019 using gcloud_speech_msgs::LinearPcm16Le16000Audio;
00020 using SpeechToTextSimpleActionServer =
00021     actionlib::SimpleActionServer<gcloud_speech_msgs::SpeechToTextAction>;
00022 
00023 int main(int argc, char* argv[]) {
00024   google::InitGoogleLogging(argv[0]);
00025   gflags::ParseCommandLineFlags(&argc, &argv, true);
00026   cogrob::cloud::PrepareGoogleCloudCredentials();
00027   grpc_init();
00028 
00029   ros::init(argc, argv, "gcloud_speech_action_server");
00030   ros::NodeHandle ros_node_handle;
00031 
00032   std::mutex action_handler_mutex;
00033   std::unique_ptr<gcloud_speech::SpeechToTextActionHandler> action_handler;
00034 
00035   std::unique_ptr<speech::GoogleSpeechRecognizerInterface> recognizer(
00036       new speech::GoogleSpeechRecognizer());
00037 
00038   std::function<void (const SpeechToTextSimpleActionServer::GoalConstPtr &)>
00039       exec_callback = [&action_handler_mutex, &action_handler]
00040       (const SpeechToTextSimpleActionServer::GoalConstPtr& goal) {
00041           std::lock_guard<std::mutex> lock(action_handler_mutex);
00042           if (action_handler) {
00043             action_handler->ExecuteSpeechToTextAction(goal);
00044           }
00045       };
00046 
00047   SpeechToTextSimpleActionServer action_server(
00048       ros_node_handle, "/cogrob/speech_to_text", exec_callback, false);
00049 
00050   {
00051     // Limit the scope of the lock.
00052     std::lock_guard<std::mutex> lock(action_handler_mutex);
00053     action_handler.reset(new gcloud_speech::SpeechToTextActionHandler(
00054         recognizer.get(), &action_server));
00055   }
00056 
00057   ros::Subscriber audio_subscriber =
00058       ros_node_handle.subscribe<LinearPcm16Le16000Audio>(
00059       "/cogrob/microphone_audio", 10,
00060       [&action_handler] (const LinearPcm16Le16000Audio::ConstPtr& msg) {
00061         action_handler->AudioMsgCallback(msg);
00062       });
00063 
00064   action_server.start();
00065   LOG(INFO) << "SpeechToTextSimpleActionServer started.";
00066   ros::spin();
00067   return 0;
00068 }


gcloud_speech
Author(s):
autogenerated on Thu Jun 6 2019 17:58:03