30 #include "gcloud_speech_msgs/LinearPcm16Le16000Audio.h" 40 namespace speech = ::cogrob::cloud::speech;
44 "Timeout (ms) to terminate the program if no sample is available.");
46 int main(
int argc,
char *argv[]) {
47 google::InitGoogleLogging(argv[0]);
48 google::LogToStderr();
49 gflags::SetUsageMessage(
50 "Record audio and publish as LinearPcm16Le16000Audio message.");
51 gflags::SetVersionString(
"1.0.0");
52 gflags::ParseCommandLineFlags(&argc, &argv,
true);
61 (
"/cogrob/microphone_audio", 10);
66 if (!queue_result.
ok()) {
67 LOG(FATAL) <<
"Getting audio from microphone timed out.";
69 std::unique_ptr<AudioSample> sample = std::move(
72 audio_msg.data = *sample;
int main(int argc, char *argv[])
void publish(const boost::shared_ptr< M > &message) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
std::vector< uint8_t > AudioSample
DEFINE_int32(mic_fatal_timeout_msec, 2000,"Timeout (ms) to terminate the program if no sample is available.")