|
@@ -4,13 +4,18 @@
|
|
|
#include <audio_common_msgs/AudioData.h>
|
|
|
#include <dynamic_reconfigure/server.h>
|
|
|
#include <hotword_detector.h>
|
|
|
+#include <wiringPi.h>
|
|
|
|
|
|
+#define BTN_PIN 27
|
|
|
+volatile char btn_click = 0;
|
|
|
|
|
|
namespace snowboy_wakeup
|
|
|
{
|
|
|
- //!
|
|
|
+ std::string beep_filename;
|
|
|
+ std::string pre_param = "play -q --multi-threaded ";
|
|
|
+ std::string all_param;
|
|
|
+
|
|
|
//! \brief The HotwordDetectorNode class Wraps the C++ 11 Snowboy detector in a ROS node
|
|
|
- //!
|
|
|
class HotwordDetectorNode
|
|
|
{
|
|
|
public:
|
|
@@ -33,10 +38,16 @@ namespace snowboy_wakeup
|
|
|
return false;
|
|
|
}
|
|
|
|
|
|
- std::string asr_topic;
|
|
|
- if (!nh_p_.getParam("asr_topic", asr_topic))
|
|
|
+ if (!nh_p_.getParam("beep_filename", beep_filename))
|
|
|
+ {
|
|
|
+ ROS_WARN("Mandatory parameter 'beep_filename' not present on the parameter server");
|
|
|
+ }
|
|
|
+ all_param = pre_param + beep_filename;
|
|
|
+
|
|
|
+ std::string wakeup_topic;
|
|
|
+ if (!nh_p_.getParam("wakeup_topic", wakeup_topic))
|
|
|
{
|
|
|
- ROS_ERROR("Mandatory parameter 'asr_topic' not present on the parameter server");
|
|
|
+ ROS_ERROR("Mandatory parameter 'wakeup_topic' not present on the parameter server");
|
|
|
return false;
|
|
|
}
|
|
|
|
|
@@ -48,7 +59,7 @@ namespace snowboy_wakeup
|
|
|
}
|
|
|
|
|
|
audio_sub_ = nh_.subscribe(audio_topic, 1000, &HotwordDetectorNode::audioCallback, this);
|
|
|
- hotword_pub_ = nh_.advertise<std_msgs::Int32>(asr_topic, 1);
|
|
|
+ hotword_pub_ = nh_.advertise<std_msgs::Int32>(wakeup_topic, 1);
|
|
|
|
|
|
detector_.initialize(resource_filename.c_str(), model_filename.c_str());
|
|
|
dynamic_reconfigure_server_.setCallback(boost::bind(&HotwordDetectorNode::reconfigureCallback, this, _1, _2));
|
|
@@ -59,38 +70,28 @@ namespace snowboy_wakeup
|
|
|
private:
|
|
|
ros::NodeHandle nh_;
|
|
|
|
|
|
- //!
|
|
|
//! \brief nh_p_ Local nodehandle for parameters
|
|
|
- //!
|
|
|
ros::NodeHandle nh_p_;
|
|
|
|
|
|
ros::Subscriber audio_sub_;
|
|
|
ros::Publisher hotword_pub_;
|
|
|
|
|
|
- //!
|
|
|
//! \brief dynamic_reconfigure_server_ In order to online tune the sensitivity and audio gain
|
|
|
- //!
|
|
|
dynamic_reconfigure::Server<SnowboyReconfigureConfig> dynamic_reconfigure_server_;
|
|
|
|
|
|
- //!
|
|
|
//! \brief detector_ C++ 11 Wrapped Snowboy detect
|
|
|
- //!
|
|
|
HotwordDetector detector_;
|
|
|
|
|
|
- //!
|
|
|
//! \brief reconfigureCallback Reconfigure update for sensitiviy and audio level
|
|
|
//! \param cfg The updated config
|
|
|
- //!
|
|
|
void reconfigureCallback(SnowboyReconfigureConfig cfg, uint32_t)
|
|
|
{
|
|
|
detector_.configure(cfg.sensitivity, cfg.audio_gain);
|
|
|
- ROS_INFO("SnowboyROS (Re)Configured");
|
|
|
+ ROS_INFO("SnowboyROS ReConfigured callback init");
|
|
|
}
|
|
|
|
|
|
- //!
|
|
|
//! \brief audioCallback Audio stream callback
|
|
|
//! \param msg The audo data
|
|
|
- //!
|
|
|
void audioCallback(const audio_common_msgs::AudioDataConstPtr& msg)
|
|
|
{
|
|
|
if (msg->data.size() != 0)
|
|
@@ -107,13 +108,14 @@ namespace snowboy_wakeup
|
|
|
}
|
|
|
|
|
|
std_msgs::Int32 hotword_msg;
|
|
|
- int result = detector_.runDetection( &sample_array[0], msg->data.size()/2);
|
|
|
- if (result == 1)
|
|
|
+ int result = detector_.runDetection( &sample_array[0], msg->data.size()/2);
|
|
|
+ if (result == 1 || btn_click == 1)
|
|
|
{
|
|
|
- ROS_INFO("Hotword 1 detected!");
|
|
|
- hotword_msg.data = result;
|
|
|
+ btn_click = 0;
|
|
|
+ ROS_INFO("wakeUp detected!");
|
|
|
+ hotword_msg.data = 1;
|
|
|
hotword_pub_.publish(hotword_msg);
|
|
|
- system("play -q --multi-threaded ~/Music/ding.wav");
|
|
|
+ system(all_param.data());
|
|
|
}
|
|
|
else if (result == -3)
|
|
|
{
|
|
@@ -126,7 +128,12 @@ namespace snowboy_wakeup
|
|
|
}
|
|
|
}
|
|
|
};
|
|
|
+}
|
|
|
|
|
|
+//click btn ISR function
|
|
|
+void btnISR()
|
|
|
+{
|
|
|
+ btn_click = 1;
|
|
|
}
|
|
|
|
|
|
int main(int argc, char** argv)
|
|
@@ -134,6 +141,11 @@ int main(int argc, char** argv)
|
|
|
ros::init(argc, argv, "snowboy_wakeup_node");
|
|
|
snowboy_wakeup::HotwordDetectorNode ros_hotword_detector_node;
|
|
|
|
|
|
+ wiringPiSetup();
|
|
|
+ pinMode(BTN_PIN, INPUT);
|
|
|
+ pullUpDnControl(BTN_PIN, PUD_UP);
|
|
|
+ wiringPiISR(BTN_PIN, INT_EDGE_RISING, &btnISR);
|
|
|
+
|
|
|
if (ros_hotword_detector_node.initialize())
|
|
|
{
|
|
|
ros::spin();
|