|
@@ -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 <audio_common_msgs/AudioData.h>
|
|
#include <std_msgs/Int32.h>
|
|
#include <std_msgs/Int32.h>
|
|
|
|
|
|
#include <dynamic_reconfigure/server.h>
|
|
#include <dynamic_reconfigure/server.h>
|
|
#include <snowboy_wakeup/SnowboyReconfigureConfig.h>
|
|
#include <snowboy_wakeup/SnowboyReconfigureConfig.h>
|
|
|
|
+#include <snowboy_wakeup/hotword_detector.h>
|
|
|
|
|
|
#include <boost/filesystem.hpp>
|
|
#include <boost/filesystem.hpp>
|
|
|
|
|
|
@@ -64,6 +62,13 @@ public:
|
|
return false;
|
|
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 ) )
|
|
if ( !boost::filesystem::exists( model_filename ) )
|
|
{
|
|
{
|
|
ROS_ERROR("Model '%s' does not exist", model_filename.c_str());
|
|
ROS_ERROR("Model '%s' does not exist", model_filename.c_str());
|
|
@@ -77,11 +82,10 @@ public:
|
|
return false;
|
|
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());
|
|
detector_.initialize(resource_filename.c_str(), model_filename.c_str());
|
|
-
|
|
|
|
dynamic_reconfigure_server_.setCallback(boost::bind(&HotwordDetectorNode::reconfigureCallback, this, _1, _2));
|
|
dynamic_reconfigure_server_.setCallback(boost::bind(&HotwordDetectorNode::reconfigureCallback, this, _1, _2));
|
|
|
|
|
|
return true;
|
|
return true;
|
|
@@ -137,11 +141,6 @@ private:
|
|
{
|
|
{
|
|
if (msg->data.size() != 0)
|
|
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 )
|
|
if ( msg->data.size() % 2 )
|
|
{
|
|
{
|
|
ROS_ERROR("Not an even number of bytes in this message!");
|
|
ROS_ERROR("Not an even number of bytes in this message!");
|
|
@@ -158,7 +157,7 @@ private:
|
|
{
|
|
{
|
|
ROS_DEBUG("Hotword detected!");
|
|
ROS_DEBUG("Hotword detected!");
|
|
|
|
|
|
- system("play ~/Music/wakeup_alert.mp3");
|
|
|
|
|
|
+ system("play ~/Music/ding.wav");
|
|
std_msgs::Int32 hotword_msg;
|
|
std_msgs::Int32 hotword_msg;
|
|
hotword_msg.data = ASR_START_FLAG;
|
|
hotword_msg.data = ASR_START_FLAG;
|
|
hotword_pub_.publish(hotword_msg);
|
|
hotword_pub_.publish(hotword_msg);
|
|
@@ -180,7 +179,6 @@ private:
|
|
int main(int argc, char** argv)
|
|
int main(int argc, char** argv)
|
|
{
|
|
{
|
|
ros::init(argc, argv, "snowboy_wakeup_node");
|
|
ros::init(argc, argv, "snowboy_wakeup_node");
|
|
-
|
|
|
|
snowboy_wakeup::HotwordDetectorNode ros_hotword_detector_node;
|
|
snowboy_wakeup::HotwordDetectorNode ros_hotword_detector_node;
|
|
|
|
|
|
if (ros_hotword_detector_node.initialize())
|
|
if (ros_hotword_detector_node.initialize())
|