Browse Source

增加蜂鸣器报警话题,可以向该话题中发布int32消息

corvin rasp melodic 2 years ago
parent
commit
c71350f92f

+ 8 - 1
src/ros_arduino_bridge/ros_arduino_python/nodes/arduino_node.py

@@ -2,7 +2,7 @@
 #_*_ coding:utf-8 _*_
 
 """
-  Copyright:2016-2020 www.corvin.cn ROS小课堂
+  Copyright:2016-2022 www.corvin.cn ROS小课堂
   Description: A ROS Node for the Arduino DUE microcontroller
   Author: corvin
   History:
@@ -13,6 +13,7 @@ import rospy
 import thread
 from ros_arduino_msgs.srv import *
 from geometry_msgs.msg import Twist
+from std_msgs.msg import Int32
 from serial.serialutil import SerialException
 from ros_arduino_python.arduino_sensors import *
 from ros_arduino_python.arduino_driver import Arduino
@@ -20,6 +21,10 @@ from ros_arduino_python.base_controller import BaseController
 
 
 class ArduinoROS():
+
+    def beepCallBack(self, msg):
+        self.controller.beep_ring(msg.data)
+
     def __init__(self):
         rospy.init_node('mobilebase_arduino_node', log_level=rospy.INFO)
 
@@ -119,6 +124,8 @@ class ArduinoROS():
         # Initialize the base controller
         self.myBaseController = BaseController(self.is_use_serial, self.controller, self.base_frame, self.name + "_base_controller")
 
+        rospy.Subscriber("beep_ring", Int32, self.beepCallBack)
+
         # Start polling the sensors and base controller
         while not rospy.is_shutdown():
             mutex.acquire()

+ 1 - 1
src/ros_arduino_bridge/ros_arduino_python/src/ros_arduino_python/arduino_driver.py

@@ -2,7 +2,7 @@
 #-*- coding:utf-8 -*-
 
 """
-  Copyright: 2016-2020 ROS小课堂 www.corvin.cn
+  Copyright: 2016-2022 ROS小课堂 www.corvin.cn
   Description: A Python driver for the Arduino microcontroller.
   Author: corvin, jally
   History:

+ 1 - 1
src/ros_arduino_bridge/ros_arduino_python/src/ros_arduino_python/arduino_sensors.py

@@ -7,7 +7,7 @@
         20200330:增加获取电池剩余电量函数.
         20200423:增加获取电流函数
 """
-import roslib; roslib.load_manifest('ros_arduino_python')
+import roslib
 import rospy
 import numpy as np
 from decimal import Decimal

+ 5 - 1
src/voice_system/snowboy_wakeup/src/hotword_detector_node.cpp

@@ -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)
                     {