loquendo_tts_driver_node.cpp
Go to the documentation of this file.
00001 #include "loquendo_tts_driver_node.h"
00002 
00003 LoquendoTtsDriverNode::LoquendoTtsDriverNode(ros::NodeHandle &nh) : iri_base_driver::IriBaseNodeDriver<LoquendoTtsDriver>(nh),
00004   tts_aserver_(this->public_node_handle_, "tts")
00005 {
00006   //init class attributes if necessary
00007   //this->loop_rate_ = 2;//in [Hz]
00008 
00009   // [init publishers]
00010   
00011   // [init subscribers]
00012   
00013   // [init services]
00014   
00015   // [init clients]
00016   
00017   // [init action servers]
00018   tts_aserver_.registerStartCallback(boost::bind(&LoquendoTtsDriverNode::startCallback, this, _1));
00019   tts_aserver_.registerStopCallback(boost::bind(&LoquendoTtsDriverNode::stopCallback, this));
00020   tts_aserver_.registerIsFinishedCallback(boost::bind(&LoquendoTtsDriverNode::isFinishedCallback, this));
00021   tts_aserver_.registerHasSucceedCallback(boost::bind(&LoquendoTtsDriverNode::hasSucceedCallback, this));
00022   tts_aserver_.registerGetResultCallback(boost::bind(&LoquendoTtsDriverNode::getResultCallback, this, _1));
00023   tts_aserver_.registerGetFeedbackCallback(boost::bind(&LoquendoTtsDriverNode::getFeedbackCallback, this, _1));
00024   
00025   // [init action clients]
00026 }
00027 
00028 void LoquendoTtsDriverNode::startCallback(const iri_common_drivers_msgs::ttsGoalConstPtr& goal)
00029 {
00030   //lock access to driver if necessary
00031   this->driver_.lock();
00032 
00033   if( driver_.isRunning() )
00034     driver_.playSpeech(goal->msg);
00035 
00036   //unlock access to driver if necessary
00037   this->driver_.unlock();
00038   
00039 //   return accept_goal;
00040 }
00041 
00042 void LoquendoTtsDriverNode::stopCallback(void)
00043 {
00044   //lock access to driver if necessary
00045   this->driver_.lock();
00046 
00047   if( driver_.isRunning() )
00048     driver_.stopSpeech();
00049   
00050   //lock access to driver if necessary
00051   this->driver_.unlock();
00052 }
00053 
00054 bool LoquendoTtsDriverNode::isFinishedCallback(void)
00055 {
00056   bool ret = false;
00057   
00058   //lock access to driver if necessary
00059   this->driver_.lock();
00060 
00061   if( driver_.isRunning() )
00062     ret = !driver_.isBusy();
00063   
00064   //lock access to driver if necessary
00065   this->driver_.unlock();
00066 
00067   return ret;
00068 }
00069 
00070 bool LoquendoTtsDriverNode::hasSucceedCallback(void)
00071 {
00072   bool ret = false;
00073     
00074   //lock access to driver if necessary
00075   this->driver_.lock();
00076 
00077   if( driver_.isRunning() )
00078     ret = true;
00079   
00080   //lock access to driver if necessary
00081   this->driver_.unlock();
00082   
00083   return ret;
00084 }
00085 
00086 void LoquendoTtsDriverNode::getResultCallback(iri_common_drivers_msgs::ttsResultPtr& result)
00087 {
00088   if( driver_.isRunning() )
00089     result->ok = hasSucceedCallback();
00090   else
00091     result->ok = false;
00092 }
00093 
00094 void LoquendoTtsDriverNode::getFeedbackCallback(iri_common_drivers_msgs::ttsFeedbackPtr& feedback)
00095 {
00096   //lock access to driver if necessary
00097   this->driver_.lock();
00098 
00099   if( driver_.isRunning() )
00100     feedback->busy = driver_.isBusy();
00101   
00102   //lock access to driver if necessary
00103   this->driver_.unlock();
00104 }
00105 
00106 void LoquendoTtsDriverNode::mainNodeThread(void)
00107 {
00108   //lock access to driver if necessary
00109   this->driver_.lock();
00110 
00111   // [fill msg Header if necessary]
00112   //<publisher_name>.header.stamp = ros::Time::now();
00113   //<publisher_name>.header.frame_id = "<publisher_topic_name>";
00114 
00115   // [fill msg structures]
00116   
00117   // [fill srv structure and make request to the server]
00118   
00119   // [fill action structure and make request to the action server]
00120 
00121   // [publish messages]
00122 //   ROS_INFO("TTS Loquendo: Busy=%d",driver_.isBusy());
00123 
00124   //unlock access to driver if previously blocked
00125   this->driver_.unlock();
00126 }
00127 
00128 /*  [subscriber callbacks] */
00129 
00130 /*  [service callbacks] */
00131 
00132 /*  [action callbacks] */
00133 
00134 /*  [action requests] */
00135 
00136 void LoquendoTtsDriverNode::postNodeOpenHook(void)
00137 {
00138   tts_aserver_.start();
00139   ROS_INFO("LoquendoTtsDriverNode:: Server Started!"); 
00140 }
00141 
00142 void LoquendoTtsDriverNode::addNodeDiagnostics(void)
00143 {
00144 }
00145 
00146 void LoquendoTtsDriverNode::addNodeOpenedTests(void)
00147 {
00148 }
00149 
00150 void LoquendoTtsDriverNode::addNodeStoppedTests(void)
00151 {
00152 }
00153 
00154 void LoquendoTtsDriverNode::addNodeRunningTests(void)
00155 {
00156 }
00157 
00158 void LoquendoTtsDriverNode::reconfigureNodeHook(int level)
00159 {
00160 }
00161 
00162 LoquendoTtsDriverNode::~LoquendoTtsDriverNode()
00163 {
00164   // [free dynamic memory]
00165 }
00166 
00167 /* main function */
00168 int main(int argc,char *argv[])
00169 {
00170   return driver_base::main<LoquendoTtsDriverNode>(argc, argv, "loquendo_server");
00171 }


iri_loquendo_tts
Author(s): Joan Perez, jnperez at iri.upc.edu
autogenerated on Fri Dec 6 2013 22:13:38