client.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # -*- coding: utf-8 -*-
00003 # Author: furushchev <furushchev@jsk.imi.i.u-tokyo.ac.jp>
00004 
00005 from dynamic_reconfigure.client import Client
00006 import rospy
00007 from speech_recognition_msgs.srv import SpeechRecognition
00008 from ros_speech_recognition.cfg import SpeechRecognitionConfig as Config
00009 
00010 
00011 class SpeechRecognitionClient(object):
00012     def __init__(self,
00013                  srv_name="/speech_recognition",
00014                  node_name="/speech_recognition",
00015                  timeout=10):
00016         self._sr_srv = rospy.ServiceProxy(srv_name, SpeechRecognition)
00017         self._sr_srv.wait_for_service(timeout=timeout)
00018         self._cfg = Client(node_name, timeout=timeout)
00019 
00020     @property
00021     def language(self):
00022         return self._cfg.config["language"]
00023 
00024     @language.setter
00025     def language(self, value):
00026         self._cfg.update_configuration({'language': value})
00027 
00028     @property
00029     def engine(self):
00030         return self._cfg.config["engine"]
00031 
00032     @engine.setter
00033     def engine(self, value):
00034         self._cfg.update_configuration({'engine': value})
00035 
00036     @property
00037     def energy_threshold(self):
00038         return self._cfg.config["energy_threshold"]
00039 
00040     @energy_threshold.setter
00041     def energy_threshold(self, value):
00042         if self.dynamic_energy_threshold:
00043             rospy.logerr("Dynamic energy thresholding is enabled")
00044         else:
00045             self._cfg.update_configuration({
00046                 "energy_threshold": value
00047             })
00048 
00049     @property
00050     def dynamic_energy_threshold(self):
00051         return self._cfg.config["dynamic_energy_threshold"]
00052 
00053     @dynamic_energy_threshold.setter
00054     def dynamic_energy_threshold(self, value):
00055         self._cfg.update_configuration({
00056             "dynamic_energy_threshold": value
00057         })
00058 
00059     def recognize(self, **args):
00060         return self._sr_srv(**args).result


ros_speech_recognition
Author(s): Yuki Furuta
autogenerated on Wed Jul 10 2019 03:24:13