gcloud_speech_action_node.cc
Go to the documentation of this file.
1 #include <functional>
2 #include <memory>
3 #include <mutex>
4 
6 #include "gcloud_speech_msgs/SpeechToTextAction.h"
7 #include "gcloud_speech_msgs/RecognitionHypothesis.h"
8 #include "gcloud_speech_msgs/LinearPcm16Le16000Audio.h"
9 
13 #include "third_party/gflags.h"
14 
16 
17 namespace speech = ::cogrob::cloud::speech;
18 
19 using gcloud_speech_msgs::LinearPcm16Le16000Audio;
22 
23 int main(int argc, char* argv[]) {
24  google::InitGoogleLogging(argv[0]);
25  gflags::ParseCommandLineFlags(&argc, &argv, true);
27  grpc_init();
28 
29  ros::init(argc, argv, "gcloud_speech_action_server");
30  ros::NodeHandle ros_node_handle;
31 
32  std::mutex action_handler_mutex;
33  std::unique_ptr<gcloud_speech::SpeechToTextActionHandler> action_handler;
34 
35  std::unique_ptr<speech::GoogleSpeechRecognizerInterface> recognizer(
37 
38  std::function<void (const SpeechToTextSimpleActionServer::GoalConstPtr &)>
39  exec_callback = [&action_handler_mutex, &action_handler]
40  (const SpeechToTextSimpleActionServer::GoalConstPtr& goal) {
41  std::lock_guard<std::mutex> lock(action_handler_mutex);
42  if (action_handler) {
43  action_handler->ExecuteSpeechToTextAction(goal);
44  }
45  };
46 
47  SpeechToTextSimpleActionServer action_server(
48  ros_node_handle, "/cogrob/speech_to_text", exec_callback, false);
49 
50  {
51  // Limit the scope of the lock.
52  std::lock_guard<std::mutex> lock(action_handler_mutex);
53  action_handler.reset(new gcloud_speech::SpeechToTextActionHandler(
54  recognizer.get(), &action_server));
55  }
56 
57  ros::Subscriber audio_subscriber =
58  ros_node_handle.subscribe<LinearPcm16Le16000Audio>(
59  "/cogrob/microphone_audio", 10,
60  [&action_handler] (const LinearPcm16Le16000Audio::ConstPtr& msg) {
61  action_handler->AudioMsgCallback(msg);
62  });
63 
64  action_server.start();
65  LOG(INFO) << "SpeechToTextSimpleActionServer started.";
66  ros::spin();
67  return 0;
68 }
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char *argv[])
ROSCPP_DECL void spin()
void PrepareGoogleCloudCredentials()
Definition: defaults.cc:51


gcloud_speech
Author(s):
autogenerated on Mon Jun 10 2019 13:20:53