Go to the documentation of this file.00001 #include "tibi_dabo_tts_client_alg_node.h"
00002
00003 TibiDaboTtsClientAlgNode::TibiDaboTtsClientAlgNode(void) :
00004 algorithm_base::IriBaseAlgorithm<TibiDaboTtsClientAlgorithm>()
00005 {
00006
00007 this->loop_rate_ = 100;
00008
00009
00010 facial_expression_publisher_ = public_node_handle_.advertise<std_msgs::String>("facial_expression", 100);
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020 this->tts_.client=new TtsClient("tts", true),
00021 this->tts_.active=false;
00022 this->tts_.succeeded=false;
00023 this->tts_.loaded=false;
00024 this->tts_.percentage=0.0;
00025
00026 tts_connected_ = false;
00027 }
00028
00029 TibiDaboTtsClientAlgNode::~TibiDaboTtsClientAlgNode(void)
00030 {
00031
00032 alg_.lock();
00033 this->cancelCurrentGoals();
00034 delete this->tts_.client;
00035 alg_.unlock();
00036 }
00037
00038 void TibiDaboTtsClientAlgNode::cancelCurrentGoals(void)
00039 {
00040 alg_.lock();
00041 if(this->tts_.client->isServerConnected() && this->tts_.loaded && this->tts_.active )
00042 this->tts_.client->cancelGoal();
00043 alg_.unlock();
00044 }
00045
00046 void TibiDaboTtsClientAlgNode::speak(void)
00047 {
00048 static int count = 0;
00049 std_msgs::String msg;
00050
00051 if(count==0)
00052 {
00053 count=rand() % 200 + 200;
00054 msg.data = "speak";
00055 facial_expression_publisher_.publish(msg);
00056 }
00057 else
00058 {
00059 count-=10;
00060 if(count<0) count=0;
00061 }
00062 }
00063
00064 void TibiDaboTtsClientAlgNode::mainNodeThread(void)
00065 {
00066 iri_common_drivers_msgs::ttsGoal tts_goal;
00067
00068 tts_connected_ = true;
00069
00070
00071 tts_.client->waitForServer(ros::Duration(1.0));
00072 if(!this->tts_.client->isServerConnected())
00073 {
00074 tts_connected_ = false;
00075 }
00076
00077 if( tts_connected_ )
00078 {
00079 if(this->tts_.active)
00080 this->speak();
00081 else
00082 {
00083 tts_goal.msg = this->readInput();
00084 if(tts_goal.msg.size())
00085 {
00086 ttsMakeActionRequest(tts_goal);
00087 this->tts_.loaded=true;
00088 }
00089 }
00090 }
00091
00092
00093
00094
00095
00096
00097
00098
00099
00100
00101 }
00102
00103
00104
00105
00106
00107
00108
00109
00110
00112
00114
00115 void TibiDaboTtsClientAlgNode::ttsDone(const actionlib::SimpleClientGoalState& state,
00116 const iri_common_drivers_msgs::ttsResultConstPtr& result)
00117 {
00118 std_msgs::String expression;
00119
00120 alg_.lock();
00121
00122 ROS_INFO("TibiDaboTtsClientAlgNode::ttsDone: Goal Achieved!");
00123 ROS_INFO("TibiDaboTtsClientAlgNode::ttsDone: state=%s", state.toString().c_str());
00124
00125 if( state.state_ == actionlib::SimpleClientGoalState::SUCCEEDED )
00126 this->tts_.succeeded=true;
00127 else
00128 this->tts_.succeeded=false;
00129
00130 this->tts_.active=false;
00131 expression.data="stand_by";
00132 this->facial_expression_publisher_.publish(expression);
00133
00134 alg_.unlock();
00135 }
00136
00137 void TibiDaboTtsClientAlgNode::ttsActive(void)
00138 {
00139 ROS_INFO("TibiDaboTtsClientAlgNode::ttsActive: Goal just went active!");
00140 }
00141
00142 void TibiDaboTtsClientAlgNode::ttsFeedback(const iri_common_drivers_msgs::ttsFeedbackConstPtr& feedback)
00143 {
00144
00145 alg_.lock();
00146 if(feedback->busy)
00147 this->tts_.percentage=0.0;
00148 else
00149 this->tts_.percentage=100.0;
00150 alg_.unlock();
00151 ROS_INFO("TibiDaboTtsClientAlgNode::ttsFeedback: busy=%d", feedback->busy);
00152 }
00153
00154 void TibiDaboTtsClientAlgNode::ttsMakeActionRequest(const iri_common_drivers_msgs::ttsGoal & tts_goal)
00155 {
00156 ROS_INFO("TibiDaboTtsClientAlgNode::ttsMakeActionRequest: Starting New Request!");
00157
00158
00159
00160 this->tts_.client->waitForServer();
00161 ROS_DEBUG("TibiDaboTtsClientAlgNode::ttsMakeActionRequest: TTS Server is Available!");
00162
00163
00164 tts_.client->sendGoal(tts_goal,
00165 boost::bind(&TibiDaboTtsClientAlgNode::ttsDone, this, _1, _2),
00166 boost::bind(&TibiDaboTtsClientAlgNode::ttsActive, this),
00167 boost::bind(&TibiDaboTtsClientAlgNode::ttsFeedback, this, _1));
00168
00169 this->tts_.active=true;
00170 }
00171
00172 std::string TibiDaboTtsClientAlgNode::readInput()
00173 {
00174 ROS_INFO("Enter sentence: ");
00175 std::string input;
00176 getline( std::cin, input );
00177 ROS_INFO("You have entered: %s", input.c_str());
00178 return input;
00179 }
00180
00181 void TibiDaboTtsClientAlgNode::node_config_update(Config &config, uint32_t level)
00182 {
00183 this->alg_.lock();
00184
00185 this->alg_.unlock();
00186 }
00187
00188 void TibiDaboTtsClientAlgNode::addNodeDiagnostics(void)
00189 {
00190 }
00191
00192
00193 int main(int argc,char *argv[])
00194 {
00195 return algorithm_base::main<TibiDaboTtsClientAlgNode>(argc, argv, "tibi_dabo_tts_client_alg_node");
00196 }