Forráskód Böngészése

优化snowboy唤醒代码

corvin 5 éve
szülő
commit
5c892c2101

+ 3 - 5
catkin_ws/src/snowboy_wakeup/launch/snowboy_wakeup.launch

@@ -1,7 +1,6 @@
-<?xml version="1.0"?>
 <launch>
     <arg name="ASR_Topic" default="/voice_system/asr_topic" />
-    <arg name="publish_wave" default="false" />
+    <arg name="AUDIO_Topic" default="/voice_system/audio_data" />
 
     <node name="audio_capture" pkg="audio_capture" type="audio_capture" output="screen" required="true">
         <param name="format" value="wave" />
@@ -9,16 +8,15 @@
         <param name="depth" value="16" />
         <param name="sample_rate" value="16000" />
 
-        <remap from="audio" to="microphone" />
+        <remap from="audio" to="$(arg AUDIO_Topic)" />
     </node>
 
     <node pkg="snowboy_wakeup" type="hotword_detector_node" name="snowboy" required="true">
         <param name="resource_filename" value="$(find snowboy_wakeup)/resources/common.res" />
         <param name="model_filename" value="$(find snowboy_wakeup)/resources/snowboy.umdl" />
+
         <param name="sensitivity_str" value="0.5" type="str" />
         <param name="audio_gain" value="1.0" />
-        <param name="publish_wave" value="$(arg publish_wave)" />
         <param name="asr_topic" value="$(arg ASR_Topic)" />
     </node>
-
 </launch>

BIN
catkin_ws/src/snowboy_wakeup/resources/wakeup_alert.mp3


+ 12 - 14
catkin_ws/src/snowboy_wakeup/src/hotword_detector_node.cpp

@@ -1,12 +1,10 @@
-#include "snowboy_wakeup/hotword_detector.h"
-
-#include <ros/node_handle.h>
-#include <ros/debug.h>
+#include <ros/ros.h>
 #include <audio_common_msgs/AudioData.h>
 #include <std_msgs/Int32.h>
 
 #include <dynamic_reconfigure/server.h>
 #include <snowboy_wakeup/SnowboyReconfigureConfig.h>
+#include <snowboy_wakeup/hotword_detector.h>
 
 #include <boost/filesystem.hpp>
 
@@ -64,6 +62,13 @@ public:
       return false;
     }
 
+    std::string audio_topic;
+    if (!nh_p_.getParam("audio_topic", audio_topic))
+    {
+      ROS_ERROR("Mandatory parameter 'audio_topic' not present on the parameter server");
+      return false;
+    }    
+
     if ( !boost::filesystem::exists( model_filename ) )
     {
       ROS_ERROR("Model '%s' does not exist", model_filename.c_str());
@@ -77,11 +82,10 @@ public:
       return false;
     }
 
-    audio_sub_ = nh_.subscribe("microphone", 1000, &HotwordDetectorNode::audioCallback, this);
-    hotword_pub_ = nh_.advertise<std_msgs::Int32>(asr_topic, 10);
+    audio_sub_ = nh_.subscribe(audio_topic, 1000, &HotwordDetectorNode::audioCallback, this);
+    hotword_pub_ = nh_.advertise<std_msgs::Int32>(asr_topic, 1);
 
     detector_.initialize(resource_filename.c_str(), model_filename.c_str());
-
     dynamic_reconfigure_server_.setCallback(boost::bind(&HotwordDetectorNode::reconfigureCallback, this, _1, _2));
 
     return true;
@@ -137,11 +141,6 @@ private:
   {
     if (msg->data.size() != 0)
     {
-      /* Sound signal is encoded with bit depth 16 and cut up in a byte array. RunDetection wants it as an array of
-       * int16_t. Therefore, we bit shift the second (MSB) byte of a sample by 8 and cast it to an int16_t and add the
-       * first (LSB) byte of the sample to the result (also after typecast).
-       */
-
       if ( msg->data.size() % 2 )
       {
         ROS_ERROR("Not an even number of bytes in this message!");
@@ -158,7 +157,7 @@ private:
       {
         ROS_DEBUG("Hotword detected!");
 
-        system("play ~/Music/wakeup_alert.mp3");
+        system("play ~/Music/ding.wav");
         std_msgs::Int32 hotword_msg;
         hotword_msg.data = ASR_START_FLAG;
         hotword_pub_.publish(hotword_msg);
@@ -180,7 +179,6 @@ private:
 int main(int argc, char** argv)
 {
   ros::init(argc, argv, "snowboy_wakeup_node");
-
   snowboy_wakeup::HotwordDetectorNode ros_hotword_detector_node;
 
   if (ros_hotword_detector_node.initialize())