$search

edu::tum::cs::ias::knowrob::mod_dialog::SpeechRecognitionNode Class Reference

List of all members.

Public Member Functions

void execute () throws IOException, GrammarException
 SpeechRecognitionNode () throws IOException, PropertyException, InstantiationException

Static Public Member Functions

static void main (String[] args)

Static Protected Member Functions

static void initRos ()

Package Functions

String sphinxToKnowrob (String q)

Static Package Attributes

static NodeHandle n
static Publisher
< ros.pkg.std_msgs.msg.String > 
pub
static Ros ros
static Boolean rosInitialized = false

Private Member Functions

boolean isExit (RuleParse ruleParse)
void loadAndRecognize (String grammarName) throws IOException, GrammarException
void recognizeAndReport () throws GrammarException

Private Attributes

JSGFGrammar jsgfGrammarManager
Microphone microphone
Recognizer recognizer

Detailed Description

Speech recognition node written by slightly modifying the Sphinx SpeechRecognitionNode.

Definition at line 44 of file SpeechRecognitionNode.java.


Constructor & Destructor Documentation

edu::tum::cs::ias::knowrob::mod_dialog::SpeechRecognitionNode::SpeechRecognitionNode (  )  throws IOException, PropertyException, InstantiationException [inline]

Creates a new SpeechRecognitionNode.

Exceptions:
IOException if an I/O error occurs
PropertyException if a property configuration occurs
InstantiationException if a problem occurs while creating any of the recognizer components.

Definition at line 65 of file SpeechRecognitionNode.java.


Member Function Documentation

void edu::tum::cs::ias::knowrob::mod_dialog::SpeechRecognitionNode::execute (  )  throws IOException, GrammarException [inline]

Executes the recognition node

Definition at line 94 of file SpeechRecognitionNode.java.

static void edu::tum::cs::ias::knowrob::mod_dialog::SpeechRecognitionNode::initRos (  )  [inline, static, protected]

Thread-safe ROS initialization

Definition at line 119 of file SpeechRecognitionNode.java.

boolean edu::tum::cs::ias::knowrob::mod_dialog::SpeechRecognitionNode::isExit ( RuleParse  ruleParse  )  [inline, private]

Searches through the tags of the rule parse for an 'exit' tag.

Returns:
true if an 'exit' tag is found

Definition at line 202 of file SpeechRecognitionNode.java.

void edu::tum::cs::ias::knowrob::mod_dialog::SpeechRecognitionNode::loadAndRecognize ( String  grammarName  )  throws IOException, GrammarException [inline, private]

Load the grammar with the given grammar name and start recognizing speech using the grammar. Spoken utterances will be echoed to the terminal. This method will return when the speaker utters the exit phrase for the grammar. The exit phrase is a phrase in the grammar with the word 'exit' as a tag.

Exceptions:
IOException if an I/O error occurs
GrammarException if a grammar format error is detected

Definition at line 140 of file SpeechRecognitionNode.java.

static void edu::tum::cs::ias::knowrob::mod_dialog::SpeechRecognitionNode::main ( String[]  args  )  [inline, static]

Main method for running the jsgf demo.

Parameters:
args program arguments (none)

Definition at line 218 of file SpeechRecognitionNode.java.

void edu::tum::cs::ias::knowrob::mod_dialog::SpeechRecognitionNode::recognizeAndReport (  )  throws GrammarException [inline, private]

Performs recognition with the currently loaded grammar. Recognition for potentially multiple utterances until an 'exit' tag is returned.

GrammarException if an error in the JSGF grammar is encountered

Definition at line 154 of file SpeechRecognitionNode.java.

String edu::tum::cs::ias::knowrob::mod_dialog::SpeechRecognitionNode::sphinxToKnowrob ( String  q  )  [inline, package]

Map a string to the KnowRob syntax (e.g. replace number words by their numeric values)

Parameters:
q The string coming from the speech recognition
Returns:
String modified to be used for the DialogModule

Definition at line 181 of file SpeechRecognitionNode.java.


Member Data Documentation

Definition at line 46 of file SpeechRecognitionNode.java.

Definition at line 47 of file SpeechRecognitionNode.java.

Definition at line 54 of file SpeechRecognitionNode.java.

Publisher<ros.pkg.std_msgs.msg.String> edu::tum::cs::ias::knowrob::mod_dialog::SpeechRecognitionNode::pub [static, package]

Definition at line 55 of file SpeechRecognitionNode.java.

Definition at line 45 of file SpeechRecognitionNode.java.

Definition at line 53 of file SpeechRecognitionNode.java.

Definition at line 52 of file SpeechRecognitionNode.java.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


mod_dialog
Author(s): Moritz Tenorth
autogenerated on Mon Dec 3 21:33:44 2012