|
@@ -60,6 +60,7 @@ namespace snowboy_wakeup
|
|
|
|
|
|
audio_sub_ = nh_.subscribe(audio_topic, 1000, &HotwordDetectorNode::audioCallback, this);
|
|
|
hotword_pub_ = nh_.advertise<std_msgs::Int32>(wakeup_topic, 1);
|
|
|
+ beep_pub_ = nh_.advertise<std_msgs::Int32>("/beep_ring", 1);
|
|
|
|
|
|
detector_.initialize(resource_filename.c_str(), model_filename.c_str());
|
|
|
dynamic_reconfigure_server_.setCallback(boost::bind(&HotwordDetectorNode::reconfigureCallback, this, _1, _2));
|
|
@@ -75,6 +76,7 @@ namespace snowboy_wakeup
|
|
|
|
|
|
ros::Subscriber audio_sub_;
|
|
|
ros::Publisher hotword_pub_;
|
|
|
+ ros::Publisher beep_pub_;
|
|
|
|
|
|
//! \brief dynamic_reconfigure_server_ In order to online tune the sensitivity and audio gain
|
|
|
dynamic_reconfigure::Server<SnowboyReconfigureConfig> dynamic_reconfigure_server_;
|
|
@@ -108,6 +110,7 @@ namespace snowboy_wakeup
|
|
|
}
|
|
|
|
|
|
std_msgs::Int32 hotword_msg;
|
|
|
+ std_msgs::Int32 beep_msg;
|
|
|
int result = detector_.runDetection( &sample_array[0], msg->data.size()/2);
|
|
|
if (result == 1 || btn_click == 1)
|
|
|
{
|
|
@@ -115,7 +118,8 @@ namespace snowboy_wakeup
|
|
|
ROS_INFO("wakeUp detected!");
|
|
|
hotword_msg.data = 1;
|
|
|
hotword_pub_.publish(hotword_msg);
|
|
|
- system(all_param.data());
|
|
|
+ beep_msg.data = 4;
|
|
|
+ beep_pub_.publish(beep_msg);
|
|
|
}
|
|
|
else if (result == -3)
|
|
|
{
|