Skip to content

Commit

Permalink
Merge pull request #10 from HLP-R/update_param
Browse files Browse the repository at this point in the history
change so that we can guarantee params are loaded at the start from o…
  • Loading branch information
vchu authored Sep 16, 2016
2 parents e7887d9 + 94b82a5 commit 5f44670
Show file tree
Hide file tree
Showing 6 changed files with 70 additions and 62 deletions.
10 changes: 10 additions & 0 deletions hlpr_speech_recognition/config/speech.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
# Controls the speech node configuration. DO NOT CHANGE THE PARAMETER NAMES
# The first commented value is the default per the node

speech:
publish_topic: 'hlpr_speech_commands' # default 'hlpr_speech_commands'
verbose: true # default True
command_type: 'StampedString' # default StampedString (string vs. stampedstring)
rec_threshold: 300 # default 300
service_topic: 'get_last_speech_cmd' # default 'get_last_speech_cmd'

17 changes: 17 additions & 0 deletions hlpr_speech_recognition/launch/speech_listener.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
<?xml version="1.0"?>
<launch>

<!-- Arguments that need to be passed into this launch file -->
<!-- This file is not intended to called on its own at any time -->
<arg name="yaml_list" />
<arg name="config_file" />

<!-- Load parameters for speech -->
<rosparam command="load" file="$(arg config_file)" />

<!-- Start the speech_listener node recording action server -->
<node name="speech_listener" pkg="hlpr_speech_recognition" type="speech_listener" respawn="false" output="screen" >
<rosparam param="yaml_list" subst_value="True"> [$(arg yaml_list)]</rosparam>
</node>

</launch>
32 changes: 12 additions & 20 deletions hlpr_speech_recognition/launch/speech_rec.launch
Original file line number Diff line number Diff line change
Expand Up @@ -3,44 +3,36 @@

<!-- Param for if we are launching mic vs. fake speech input -->
<arg name="speech_gui" default="true" />
<arg name="speech_config_file" default="$(find hlpr_speech_recognition)/config/speech.yaml" />

<!-- Params for real input with microphone -->
<arg name="verbose" default="true" />
<arg name="pub_topic" default="hlpr_speech_commands" />
<arg name="str_msg" default="false" />
<arg name="rec_threshold" default="300" />
<arg name="dict_path" default="$(find hlpr_speech_recognition)/data/kps.dic" />
<arg name="kps_path" default="$(find hlpr_speech_recognition)/data/kps.txt" />

<!-- Params for the speech listener - used for real or fake speech -->
<arg name="yaml_list" default="$(find hlpr_speech_recognition)/data/kps.yaml" />
<!-- Example of how to have multiple yaml files -->
<!-- WARNING: currently if there are duplicate keys, the 2nd file will overwrite the first -->
<!--arg name="yaml_list" default="$(find hlpr_speech_recognition)/data/kps.yaml, $(find hlpr_speech_recognition)/data/kps.yaml" /-->
<arg name="yaml_list" default="$(find hlpr_speech_recognition)/data/kps.yaml" />

<!-- Start the speech_listener node recording action server -->
<node name="speech_listener" pkg="hlpr_speech_recognition" type="speech_listener" respawn="false" output="screen" >
<param name="pub_topic" value="$(arg pub_topic)"/>
<param name="str_msg" value="$(arg str_msg)"/>
<rosparam param="yaml_list" subst_value="True"> [$(arg yaml_list)]</rosparam>
</node>
<!-- Load parameters for speech -->
<rosparam command="load" file="$(arg speech_config_file)" />

<node name="speech_gui" pkg="hlpr_speech_recognition" type="speech_gui" respawn="false" output="screen" if="$(arg speech_gui)">
<param name="pub_topic" value="$(arg pub_topic)"/>
`<rosparam param="yaml_list" subst_value="True"> [$(arg yaml_list)]</rosparam>
</node>
<!-- Start the speech_listener node recording action server -->
<include file="$(find hlpr_speech_recognition)/launch/speech_listener.launch">
<arg name="config_file" value="$(arg speech_config_file)"/>
<arg name="yaml_list" value="$(arg yaml_list)"/>
</include>

<!-- Start the GUI if speech_gui set to true -->
<node name="speech_gui" pkg="hlpr_speech_recognition" type="speech_gui" respawn="false" output="screen" if="$(arg speech_gui)"/>

<!-- Start the hlpr_speech_recognizer
Note: just an example of how to launch with params
like the gui, but not tested with mic input! -->
<node name="speech_recognizer" pkg="hlpr_speech_recognition" type="speech_recognizer" respawn="false" output="screen" unless="$(arg speech_gui)">
<param name="verbose" value="$(arg verbose)"/>
<param name="pub_topic" value="$(arg pub_topic)"/>
<param name="str_msg" value="$(arg str_msg)"/>
<param name="rec_threshold" value="$(arg rec_threshold)"/>
<param name="dict_path" value="$(arg dict_path)" />
<param name="kps_path" value="$(arg kps_path)" />
</node>


</launch>
30 changes: 15 additions & 15 deletions hlpr_speech_recognition/src/hlpr_speech_recognition/speech_gui.py
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,7 @@
from std_msgs.msg import String
from hlpr_speech_msgs.msg import StampedString
from PyQt4 import QtGui, QtCore
from .speech_listener import SpeechListener

class SpeechGui(QtGui.QWidget):

Expand All @@ -68,21 +69,21 @@ def __init__(self):
# Default values for speech listeners
rospack = rospkg.RosPack()
default_pub_topic = 'hlpr_speech_commands'
default_yaml_files = [rospack.get_path('hlpr_speech_recognition')+'/data/kps.yaml']

# Pull values from rosparam
self.recog_topic = rospy.get_param("~pub_topic", default_pub_topic)
self.yaml_files = rospy.get_param("~yaml_list", default_yaml_files)
self.str_msg = rospy.get_param("~str_msg", False)

self.commands = []
for kps_path in self.yaml_files:
for data in yaml.load_all(file(kps_path,'r')):
for key, value in data.iteritems():
if key == "speech":
for i in value:
if i not in self.commands: # remove duplicates
self.commands.append(i)
self.recog_topic = rospy.get_param(SpeechListener.COMMAND_TOPIC_PARAM, default_pub_topic)
self.str_msg = rospy.get_param(SpeechListener.COMMAND_TYPE, False)

# Wait for listener to be ready to know what commands to send
self.service_topic = rospy.get_param(SpeechListener.SERVICE_TOPIC_PARAM, None)
rospy.loginfo("Waiting for speech service for keywords")
rospy.wait_for_service(self.service_topic)
rospy.loginfo("Speech service loaded")

# Get commands from the listener
self.keywords = rospy.get_param(SpeechListener.KEYWORDS_PARAM, dict()).values()
self.commands = [val for sublist in self.keywords for val in sublist]
self.commands.sort()

positions = [(i,j) for i in range(len(self.commands)) for j in range(3)]

Expand Down Expand Up @@ -114,8 +115,7 @@ def handleButton(self):

# Publish everytime a command is selected from the combo box
command = str(clicked_button.objectName())
print (command)
if self.str_msg:
if self.str_msg == 'String':
self.pub.publish(command)
else:
keyphrase = StampedString()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -53,10 +53,10 @@

class SpeechListener:

COMMAND_TOPIC_PARAM = "speech_command_topic"
SERVICE_TOPIC_PARAM = "speech_service_topic"
KEYWORDS_PARAM = "speech_keywords"
COMMAND_TYPE = "speech_command_type"
COMMAND_TOPIC_PARAM = "/speech/publish_topic"
SERVICE_TOPIC_PARAM = "/speech/service_topic"
KEYWORDS_PARAM = "/speech/keywords"
COMMAND_TYPE = "/speech/command_type"

def __init__(self, commandBuffSize=10, init_node=True):

Expand All @@ -71,20 +71,12 @@ def __init__(self, commandBuffSize=10, init_node=True):
default_service_topic = 'get_last_speech_cmd'

# Pull values from rosparam
self.recog_topic = rospy.get_param("~pub_topic", default_pub_topic)
self.recog_topic = rospy.get_param(SpeechListener.COMMAND_TOPIC_PARAM, default_pub_topic)
self.yaml_files = rospy.get_param("~yaml_list", default_yaml_files)
self.service_topic = rospy.get_param("~speech_service_topic", default_service_topic)
self.str_msg = rospy.get_param("~str_msg", False) # True if message is only str, false includes header

self.msg_type = String
# Listen to the voice based on topic type
if self.str_msg:
rospy.Subscriber(self.recog_topic, String, self.callback)
rospy.set_param(SpeechListener.COMMAND_TYPE, "String")
else:
rospy.Subscriber(self.recog_topic, StampedString, self.callback)
rospy.set_param(SpeechListener.COMMAND_TYPE, "StampedString")
self.msg_type = StampedString
self.service_topic = rospy.get_param(SpeechListener.SERVICE_TOPIC_PARAM, default_service_topic)
self.msg_type = eval(rospy.get_param(SpeechListener.COMMAND_TYPE, 'StampedString')) # True if message is only str, false includes header

rospy.Subscriber(self.recog_topic, self.msg_type, self.callback)

# Converts the yaml files into keywords to store into the dictionary
self.keywords_to_commands = {}
Expand All @@ -94,10 +86,6 @@ def __init__(self, commandBuffSize=10, init_node=True):

# Store this on the rosparam server now
rospy.set_param(SpeechListener.KEYWORDS_PARAM, self.keywords_to_commands)
rospy.set_param(SpeechListener.COMMAND_TOPIC_PARAM, self.recog_topic)
rospy.set_param(SpeechListener.SERVICE_TOPIC_PARAM, self.service_topic)

#print self.keywords_to_commands

self._commandBuffSize = commandBuffSize
#self.commandsQueue = deque(maxlen=self._commandBuffSize)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,7 @@
from sphinxbase.sphinxbase import *
import pyaudio
import rospkg
from .speech_listener import SpeechListener

# Global values specific to speech
N_CHANNELS = 1
Expand Down Expand Up @@ -72,12 +73,12 @@ def __init__(self):
modeldir = rospy.get_param("~model_dir", default_modeldir)
dict_path = rospy.get_param("~dict_path", default_dict_path)
kps_path = rospy.get_param("~kps_path", default_kps_path)
self.verbose = rospy.get_param("~verbose", True) # default prints out more info
self.str_msg = rospy.get_param("~str_msg", False) # True if message is only str, false includes header
self.cmd_pub_topic = rospy.get_param("~pub_topic", default_pub_topic)
self.verbose = rospy.get_param("/speech/verbose", True) # default prints out more info
self.str_msg = rospy.get_param(SpeechListener.COMMAND_TYPE, 'StampedString') # True if message is only str, false includes header
self.cmd_pub_topic = rospy.get_param(SpeechListener.COMMAND_TOPIC_PARAM, default_pub_topic)

# Parameters for recognition
self.RECOGNITION_THRESHOLD = rospy.get_param("~rec_thresh", default_rec_thresh)
self.RECOGNITION_THRESHOLD = rospy.get_param("/speech/rec_thresh", default_rec_thresh)

# Create a decoder with certain model
self.config = Decoder.default_config()
Expand All @@ -99,7 +100,7 @@ def __init__(self):
self.config.set_string('-logfn','/dev/null')

# Setup the publisher
if self.str_msg:
if self.str_msg == 'String':
self.pub = rospy.Publisher(self.cmd_pub_topic, String, queue_size=1)
else:
self.pub = rospy.Publisher(self.cmd_pub_topic, StampedString, queue_size=1)
Expand Down Expand Up @@ -149,7 +150,7 @@ def begin_rec(self):
# Get the time stamp for the message
now = rospy.get_rostime()

if self.str_msg:
if self.str_msg == 'String':
keyphrase = selectedSegment.word
else:
keyphrase = StampedString()
Expand Down

0 comments on commit 5f44670

Please sign in to comment.