00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022 #include "TalkingHead.h"
00023
00024 #if defined(Q_WS_WIN)
00025 #include <windows.h>
00026 #else
00027 #include <Qt/qx11info_x11.h>
00028 #include <X11/Xlib.h>
00029 #endif
00030
00031 #include <map>
00032 #include <string>
00033 #include <utility>
00034 #include <vector>
00035
00036 TalkingHead::TalkingHead( QWidget* parent, std::string mesh_string, std::vector< std::vector<float> > material_vector ) :
00037 QWidget( parent ),
00038 phones_( 0 ),
00039 words_( 0 ),
00040 root_( 0 ),
00041 camera_( 0 ),
00042 viewport_( 0 ),
00043 scene_manager_( 0 ),
00044 shut_down_( false ),
00045 window_( 0 ),
00046 mesh_( 0 ),
00047 material_( 0 ),
00048 pose_list_( 0 ),
00049 num_sub_meshes_( 0 ),
00050 anim_set_( 0 ),
00051 mouth_animation_state_( 0 ),
00052 mouth_animation_state_name_( "mouthAnimationState" ),
00053 eyebrows_animation_state_( 0 ),
00054 eyebrows_animation_state_name_( "eyebrowsAnimationState" ),
00055 vertex_animation_tracks_( 0 ),
00056 manual_key_frame_( 0 ),
00057 visemes_arrived_( false ),
00058 words_arrived_( false ),
00059 text_for_emotion_( " " ),
00060 angry_(false),
00061 smile_(false),
00062 sad_(false),
00063 rest_(false),
00064 surprised_(false),
00065 disgusted_(false),
00066 afraid_(false)
00067 {
00068 setMinimumSize( 100, 100 );
00069 redraw_timer_ = new QTimer ( this );
00070 connect ( redraw_timer_, SIGNAL ( timeout() ), SLOT ( updateOverlay() ) );
00071 redraw_timer_->start( 1000.0 / 25 );
00072
00073 initPhoneMap();
00074 srand( ( unsigned )time( 0 ) );
00075
00076 smileys_.push_back( ">:" );
00077 smileys_.push_back(":O");
00078 smileys_.push_back(":o");
00079 smileys_.push_back(":!");
00080 smileys_.push_back( ":)" );
00081 smileys_.push_back( ":(" );
00082 smileys_.push_back( "." );
00083 smileys_.push_back( ":&" );
00084
00085
00086 mesh_string_ = mesh_string;
00087 material_vector_ = material_vector;
00088 }
00089
00090
00091 TalkingHead::~TalkingHead()
00092 {
00093 remove( "phonemes.txt" );
00094 remove( "words.txt" );
00095 Ogre::WindowEventUtilities::removeWindowEventListener( window_, this );
00096 windowClosed( window_ );
00097 if( root_ ) delete root_;
00098 }
00099
00100
00101 void TalkingHead::updateOverlay()
00102 {
00103 Ogre::Root::getSingleton()._fireFrameStarted();
00104 window_->update();
00105 Ogre::Root::getSingleton()._fireFrameRenderingQueued();
00106 Ogre::Root::getSingleton()._fireFrameEnded();
00107
00108 update();
00109 }
00110
00111 void TalkingHead::subscribeWithNodeHandle( ros::NodeHandle node_handle )
00112 {
00113 viseme_subscriber_ = node_handle.subscribe( "robot_face/festival_phonemes", 1, &TalkingHead::callbackVisemes, this );
00114 emotion_subscriber_ = node_handle.subscribe( "robot_face/text_out", 1, &TalkingHead::callbackTextForEmotion, this );
00115 talking_finished_subscriber_ = node_handle.subscribe( "robot_face/talking_finished", 1, &TalkingHead::callbackResetAnimation, this);
00116 }
00117
00118
00119 void TalkingHead::showEvent( QShowEvent *event )
00120 {
00121 if ( !root_ )
00122 {
00123 initOgreSystem();
00124 }
00125
00126 QWidget::showEvent( event );
00127 }
00128
00129
00130 void TalkingHead::paintEvent( QPaintEvent *event )
00131 {
00132 Ogre::Root::getSingleton()._fireFrameStarted();
00133 window_->update();
00134 Ogre::Root::getSingleton()._fireFrameRenderingQueued();
00135 Ogre::Root::getSingleton()._fireFrameEnded();
00136
00137 update();
00138 }
00139
00140
00141 void TalkingHead::moveEvent( QMoveEvent * event )
00142 {
00143 QWidget::moveEvent( event );
00144
00145 if( event->isAccepted() && window_ )
00146 {
00147 window_->windowMovedOrResized();
00148 update();
00149 }
00150 }
00151
00152
00153 void TalkingHead::resizeEvent( QResizeEvent *event )
00154 {
00155 QWidget::resizeEvent( event );
00156
00157 if( event->isAccepted() )
00158 {
00159 const QSize &newSize = event->size();
00160 if( window_ )
00161 {
00162 window_->resize( newSize.width(), newSize.height() );
00163 window_->windowMovedOrResized();
00164 }
00165 if( camera_ )
00166 {
00167 Ogre::Real aspectRatio = Ogre::Real( newSize.width() ) / Ogre::Real( newSize.height() );
00168 camera_->setAspectRatio( aspectRatio );
00169 }
00170 }
00171 }
00172
00173
00174 void TalkingHead::initOgreSystem( void )
00175 {
00176 try
00177 {
00178 Ogre::LogManager* log_manager = new Ogre::LogManager();
00179 log_manager->createLog( "Ogre.log", true, false, true );
00180
00181 std::string plugin_prefix;
00182 #ifdef OGRE_PLUGIN_PATH
00183 plugin_prefix = OGRE_PLUGIN_PATH + std::string( "/" );
00184 #endif
00185
00186 root_ = new Ogre::Root();
00187 root_->loadPlugin( plugin_prefix + "RenderSystem_GL" );
00188
00189
00190 Ogre::RenderSystem* render_system = NULL;
00191 #if OGRE_VERSION_MAJOR >=1 && OGRE_VERSION_MINOR >= 7
00192 Ogre::RenderSystemList rs_list = root_->getAvailableRenderers();
00193 Ogre::RenderSystemList::iterator render_it = rs_list.begin();
00194 Ogre::RenderSystemList::iterator render_end_it = rs_list.end();
00195 #else
00196 Ogre::RenderSystemList* rs_list = root_->getAvailableRenderers();
00197 Ogre::RenderSystemList::iterator render_it = rs_list->begin();
00198 Ogre::RenderSystemList::iterator render_end_it = rs_list->end();
00199 #endif
00200 for ( ; render_it != render_end_it; ++render_it )
00201 {
00202 render_system = *render_it;
00203
00204 if ( render_system->getName() == "OpenGL Rendering Subsystem" )
00205 {
00206 break;
00207 }
00208 }
00209
00210 if ( render_system == NULL )
00211 {
00212 throw std::runtime_error( "Could not find the opengl rendering subsystem!\n" );
00213 }
00214
00215 render_system->setConfigOption( "Full Screen", "No" );
00216 render_system->setConfigOption( "FSAA", "2" );
00217 render_system->setConfigOption( "RTT Preferred Mode", "FBO" );
00218 render_system->setConfigOption( "VSync", "Yes" );
00219 render_system->setConfigOption( "sRGB Gamma Conversion", "No" );
00220
00221 root_->setRenderSystem( render_system );
00222
00223 root_->initialise( false );
00224
00225 std::string ogre_tools_path = ros::package::getPath( ROS_PACKAGE_NAME );
00226
00227 Ogre::ResourceGroupManager::getSingleton().addResourceLocation( ogre_tools_path + "/mesh", "FileSystem", mesh_string_ );
00228 }
00229 catch( const std::exception& e )
00230 {
00231 printf( "Failed to initialize Ogre: %s\n", e.what() );
00232 throw;
00233 }
00234
00235 root_->restoreConfig();
00236
00237 Ogre::NameValuePairList viewConfig;
00238 Ogre::String winHandle;
00239
00240 QX11Info xInfo = x11Info();
00241
00242 viewConfig[ "monitorIndex" ] = "2";
00243 winHandle = Ogre::StringConverter::toString ( (unsigned long)xInfo.display() ) +
00244 ":" + Ogre::StringConverter::toString ( (unsigned int)xInfo.screen() ) +
00245 ":" + Ogre::StringConverter::toString ( (unsigned long)nativeParentWidget()->effectiveWinId() );
00246
00247 viewConfig[ "externalWindowHandle" ] = winHandle;
00248 viewConfig[ "FSAA" ] = "2";
00249 viewConfig[ "vsync" ] = "true";
00250 viewConfig[ "border" ] = "none";
00251 window_ = root_->createRenderWindow( "RobotFace", width(), height(), false, &viewConfig );
00252 window_->setActive( true );
00253 WId ogreWinId = 0x0;
00254 window_->getCustomAttribute( "WINDOW", &ogreWinId );
00255
00256 assert( ogreWinId );
00257
00258 QWidget::create( ogreWinId );
00259 setAttribute( Qt::WA_PaintOnScreen, true );
00260 setAttribute( Qt::WA_OpaquePaintEvent );
00261
00262
00263 scene_manager_ = root_->createSceneManager( Ogre::ST_GENERIC );
00264
00265
00266 camera_ = scene_manager_->createCamera( "Camera" );
00267
00268 camera_->setPosition( Ogre::Vector3( 0, 0, 12 ) );
00269 camera_->lookAt( Ogre::Vector3( 0, 0, 1 ) );
00270 camera_->setNearClipDistance( 1 );
00271
00272
00273 viewport_ = window_->addViewport( camera_ );
00274 viewport_->setBackgroundColour( Ogre::ColourValue ( 0, 0, 0 ) );
00275
00276
00277 camera_->setAspectRatio( Ogre::Real( width() / height() ) );
00278
00279
00280 Ogre::ResourceGroupManager::getSingleton().initialiseResourceGroup( mesh_string_ );
00281
00282
00283 createAnimations( mesh_string_ + ".mesh" );
00284
00285
00286 Ogre::Entity* head = scene_manager_->createEntity( "Head", mesh_string_ + ".mesh" );
00287 Ogre::SceneNode* headNode = scene_manager_->getRootSceneNode()->createChildSceneNode( "HeadNode", Ogre::Vector3( 0.0f, 0.0f, 0.0f ) );
00288 headNode->attachObject( head );
00289
00290
00291 anim_set_ = head->getAllAnimationStates();
00292
00293 mouth_animation_state_ = head->getAnimationState( mouth_animation_state_name_ );
00294
00295 eyebrows_animation_state_ = head->getAnimationState( eyebrows_animation_state_name_ );
00296
00297 initAnimationStates();
00298
00299
00300 scene_manager_->setAmbientLight( Ogre::ColourValue( 0.5, 0.5, 0.5 ) );
00301
00302
00303 Ogre::Light* spotLight = scene_manager_->createLight("spotLight");
00304 spotLight->setType(Ogre::Light::LT_SPOTLIGHT);
00305
00306 spotLight->setDirection(0, 0, -1);
00307 spotLight->setPosition(Ogre::Vector3(0, 0, 10));
00308
00309 spotLight->setSpotlightRange(Ogre::Degree(10), Ogre::Degree(20));
00310
00311
00312 Ogre::Light* light = scene_manager_->createLight( "Light" );
00313 light->setPosition( 20, 80, 50 );
00314
00315 windowResized( window_ );
00316
00317 Ogre::WindowEventUtilities::addWindowEventListener( window_, this );
00318
00319 root_->addFrameListener( this );
00320
00321 while( ros::ok() )
00322 {
00323
00324 if( !root_->renderOneFrame() )
00325 {
00326 root_->getRenderSystem()->shutdown();
00327 ros::shutdown();
00328 }
00329
00330 if( window_->isClosed() )
00331 {
00332 root_->getRenderSystem()->shutdown();
00333 ros::shutdown();
00334 }
00335
00336 window_->update();
00337
00338 }
00339
00340 return;
00341 }
00342
00343
00344 bool TalkingHead::frameRenderingQueued( const Ogre::FrameEvent& evt )
00345 {
00346 bool ret = Ogre::FrameListener::frameRenderingQueued( evt );
00347
00348 if( window_->isClosed() )
00349 return false;
00350
00351 if( shut_down_ )
00352 return false;
00353
00354 Ogre::AnimationStateIterator animations_it = anim_set_->getAnimationStateIterator();
00355
00356 while (animations_it.hasMoreElements())
00357 {
00358 Ogre::AnimationState *animationState = animations_it.getNext();
00359 if( (visemes_arrived_) && animationState->getAnimationName() == mouth_animation_state_name_ )
00360 {
00361 animationState->addTime( evt.timeSinceLastFrame );
00362
00363 updatePoses( "mouth", 0 );
00364 }
00365
00366 if( (visemes_arrived_) && animationState->getAnimationName() == eyebrows_animation_state_name_ )
00367 {
00368 animationState->addTime( evt.timeSinceLastFrame );
00369
00370 updatePoses( "eyebrows", 0 );
00371 }
00372
00373 if( animationState->getAnimationName() == "breathe" )
00374 {
00375
00376 animationState->addTime( evt.timeSinceLastFrame );
00377 }
00378
00379 if( animationState->getAnimationName() == "blink" )
00380 {
00381
00382 animationState->addTime( evt.timeSinceLastFrame );
00383
00384 if ( root_->getTimer()->getMilliseconds() / 1000 % (rand()/RAND_MAX * (6 - 4 + 1) + 4) == 0 )
00385 {
00386 animationState->setTimePosition( 0 );
00387 }
00388 }
00389
00390 if( animationState->getAnimationName() == "rotate" )
00391 {
00392
00393 animationState->addTime( evt.timeSinceLastFrame );
00394
00395 if( root_->getTimer()->getMilliseconds() / 1000 % (rand()/RAND_MAX * (22 - 12 + 1) + 12) == 0 )
00396 {
00397 animationState->setTimePosition( 0 );
00398 }
00399 }
00400 }
00401
00402 return ret;
00403 }
00404
00405
00406 void TalkingHead::createAnimations( std::string mesh_file )
00407 {
00408 if( !material_vector_.empty() )
00409 {
00410 changeMaterialColor();
00411 }
00412
00413 mesh_ = Ogre::MeshManager::getSingleton().load( mesh_file, mesh_string_ );
00414
00415 try
00416 {
00417 bool needVertexAnimation = true;
00418 bool needSkeletalAnimation = false;
00419
00420 bool mouth = false;
00421 bool eyebrows = false;
00422
00423 pose_list_ = mesh_->getPoseList();
00424
00425 num_sub_meshes_ = mesh_->getNumSubMeshes();
00426
00427 Ogre::Animation* mouthAnimation = mesh_->createAnimation( mouth_animation_state_name_, 0 );
00428 Ogre::Animation* eyebrowsAnimation = mesh_->createAnimation( eyebrows_animation_state_name_, 0 );
00429
00430 for( int curSubMesh = 1; curSubMesh <= num_sub_meshes_; curSubMesh++ )
00431 {
00432 Ogre::VertexData* vertexData = mesh_->getVertexDataByTrackHandle( curSubMesh );
00433 Ogre::VertexDeclaration* newDeclaration = vertexData->vertexDeclaration->getAutoOrganisedDeclaration( needSkeletalAnimation, needVertexAnimation );
00434 vertexData->reorganiseBuffers( newDeclaration );
00435
00436 for( unsigned int curPoseIndex = 0; curPoseIndex < mesh_->getPoseCount(); curPoseIndex++ )
00437 {
00438 if( atof( Ogre::StringUtil::split( mesh_->getPose( curPoseIndex )->getName(), "-", 3 ).at( 2 ).c_str() ) == curSubMesh-1
00439 && Ogre::StringUtil::startsWith( mesh_->getPose( curPoseIndex )->getName(), "mouth", true )
00440 && mouth == false )
00441 {
00442 Ogre::VertexAnimationTrack* vat = mouthAnimation->createVertexTrack( curSubMesh, Ogre::VAT_POSE );
00443 mouth = true;
00444 vertex_animation_tracks_.push_back( vat );
00445 }
00446 if( atof( Ogre::StringUtil::split( mesh_->getPose( curPoseIndex )->getName(), "-", 3 ).at( 2 ).c_str() ) == curSubMesh-1
00447 && Ogre::StringUtil::startsWith( mesh_->getPose( curPoseIndex )->getName(), "eyebrows", true )
00448 && eyebrows == false )
00449 {
00450 Ogre::VertexAnimationTrack* vat = eyebrowsAnimation->createVertexTrack( curSubMesh, Ogre::VAT_POSE );
00451 eyebrows = true;
00452 vertex_animation_tracks_.push_back( vat );
00453 }
00454 }
00455 }
00456 }
00457 catch( std::runtime_error err )
00458 {
00459 std::string error = "ERROR: ";
00460 error.append( __FILE__ );
00461 error.append( err.what() );
00462 Ogre::LogManager::getSingleton().logMessage( error );
00463 }
00464 }
00465
00466
00467 void TalkingHead::changeMaterialColor()
00468 {
00469 std::vector<float> head_color = material_vector_.at(0);
00470 std::vector<float> iris_color = material_vector_.at(1);
00471 std::vector<float> outline_color = material_vector_.at(2);
00472
00473 material_ = Ogre::MaterialManager::getSingleton().load("Head", mesh_string_);
00474 Ogre::Technique* tech = material_->createTechnique();
00475 Ogre::Pass* pass = tech->createPass();
00476 pass = material_->getTechnique(0)->getPass(0);
00477 pass->setDiffuse(Ogre::ColourValue(head_color.at(0), head_color.at(1), head_color.at(2), 1.0));
00478
00479 material_ = Ogre::MaterialManager::getSingleton().load("Iris", mesh_string_);
00480 tech = material_->createTechnique();
00481 pass = tech->createPass();
00482 pass = material_->getTechnique(0)->getPass(0);
00483 pass->setDiffuse(Ogre::ColourValue(iris_color.at(0), iris_color.at(1), iris_color.at(2), 1.0));
00484
00485 material_ = Ogre::MaterialManager::getSingleton().load("Mouth", mesh_string_);
00486 tech = material_->createTechnique();
00487 pass = tech->createPass();
00488 pass = material_->getTechnique(0)->getPass(0);
00489 pass->setDiffuse(Ogre::ColourValue(outline_color.at(0), outline_color.at(1), outline_color.at(2), 1.0));
00490
00491 material_ = Ogre::MaterialManager::getSingleton().load("EyeBrows", mesh_string_);
00492 tech = material_->createTechnique();
00493 pass = tech->createPass();
00494 pass = material_->getTechnique(0)->getPass(0);
00495 pass->setDiffuse(Ogre::ColourValue(outline_color.at(0), outline_color.at(1), outline_color.at(2), 1.0));
00496
00497 material_ = Ogre::MaterialManager::getSingleton().load("Eyes", mesh_string_);
00498 tech = material_->createTechnique();
00499 pass = tech->createPass();
00500 pass = material_->getTechnique(0)->getPass(0);
00501 pass->setDiffuse(Ogre::ColourValue(outline_color.at(0), outline_color.at(1), outline_color.at(2), 1.0));
00502 }
00503
00504
00505 void TalkingHead::initAnimationStates()
00506 {
00507 Ogre::AnimationStateIterator animations_it = anim_set_->getAnimationStateIterator();
00508
00509
00510 while (animations_it.hasMoreElements())
00511 {
00512 Ogre::AnimationState *a = animations_it.getNext();
00513 a->setEnabled( true );
00514 a->setLoop( false );
00515 if( a->getAnimationName() == "breathe" )
00516 {
00517 a->setLoop( true );
00518 }
00519 a->setTimePosition( 0 );
00520 }
00521 }
00522
00523
00524 void TalkingHead::initPhoneMap()
00525 {
00526 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "aa", "narrow" ) );
00527 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "ae", "wide" ) );
00528 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "ah", "wide" ) );
00529 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "ao", "narrow" ) );
00530 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "aw", "narrow" ) );
00531 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "ax", "open" ) );
00532 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "axr", "open" ));
00533 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "ay", "wide" ) );
00534 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "b", "close" ) );
00535 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "ch", "open" ) );
00536 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "d", "open" ) );
00537 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "dh", "open" ) );
00538 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "dx", "open" ) );
00539 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "eh", "wide" ) );
00540 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "el", "wide" ) );
00541 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "em", "wide" ) );
00542 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "en", "wide" ) );
00543 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "er", "open" ) );
00544 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "ey", "wide" ) );
00545 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "f", "close" ) );
00546 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "g", "open" ) );
00547 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "hh", "open" ) );
00548 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "hv", "open" ) );
00549 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "ih", "open" ) );
00550 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "iy", "wide" ) );
00551 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "jh", "open" ) );
00552 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "k", "open" ) );
00553 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "l", "open" ) );
00554 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "m", "close" ));
00555 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "n", "open" ) );
00556 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "nx", "open" ) );
00557 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "ng", "open" ) );
00558 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "ow", "narrow" ) );
00559 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "oy", "narrow" ) );
00560 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "p", "close" ) );
00561 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "r", "open" ) );
00562 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "s", "open" ) );
00563 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "sh", "open" ));
00564 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "t", "open" ) );
00565 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "th", "open" ) );
00566 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "uh", "narrow" ) );
00567 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "uw", "narrow" ) );
00568 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "v", "close" ) );
00569 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "w", "close" ) );
00570 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "y", "open" ) );
00571 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "z", "open" ) );
00572 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "zh", "open" ) );
00573 phonemes_.insert( std::pair<Ogre::String, Ogre::String>( "pau", "pau" ) );
00574 }
00575
00576
00577 std::map<float, Ogre::String> TalkingHead::createVisemeMap()
00578 {
00579 std::map<Ogre::String, Ogre::String>::iterator phoneme_it = phonemes_.begin();
00580
00581 std::map<float, Ogre::String> visemes;
00582
00583 Ogre::String l;
00584 Ogre::String phone = "";
00585 float timeStamp;
00586
00587 for(unsigned int i = 1; i < phones_.size(); i++)
00588 {
00589 l = phones_.at(i);
00590
00591 timeStamp = atof( Ogre::StringUtil::split( l, " ", 3 ).at( 0 ).c_str() );
00592 phone = Ogre::StringUtil::split( l, " ", 3 ).at( 2 );
00593
00594 phoneme_it = phonemes_.find( phone );
00595
00596 visemes.insert( std::pair<float, Ogre::String>( timeStamp, phoneme_it->second ) );
00597 }
00598
00599 return visemes;
00600 }
00601
00602
00603 std::map<float, Ogre::String> TalkingHead::createWordMap()
00604 {
00605 std::map<float, Ogre::String> words;
00606
00607 Ogre::String l;
00608 Ogre::String word = "";
00609 float timeStamp;
00610
00611 for(unsigned int i = 1; i < words_.size(); i++)
00612 {
00613 l = words_.at(i);
00614
00615 timeStamp = atof( Ogre::StringUtil::split( l, " ", 3 ).at( 0 ).c_str() );
00616 word = Ogre::StringUtil::split( l, " ", 3 ).at( 2 );
00617
00618 words.insert( std::pair<float, Ogre::String>( timeStamp, word ) );
00619 }
00620
00621 return words;
00622 }
00623
00624
00625 void TalkingHead::playTalkAnimation()
00626 {
00627 std::map<float, Ogre::String>::iterator words_it = word_map_.begin();
00628
00629 if( visemes_arrived_ )
00630 {
00631 for( unsigned int curVAT = 0; curVAT < vertex_animation_tracks_.size(); curVAT++ )
00632 {
00633 vertex_animation_tracks_[ curVAT ]->removeAllKeyFrames();
00634 }
00635 visemes_arrived_ = false;
00636 }
00637
00638 for( std::map<float, Ogre::String>::iterator visemes_it = viseme_map_.begin(); visemes_it != viseme_map_.end(); ++visemes_it)
00639 {
00640 mouth_animation_state_->setTimePosition( 0 );
00641 mouth_animation_state_->setLength( visemes_it->first );
00642 eyebrows_animation_state_->setTimePosition( 0 );
00643 eyebrows_animation_state_->setLength( visemes_it->first );
00644
00645 if( words_it->first == visemes_it->first )
00646 {
00647 std::vector<std::string> spaces;
00648 spaces.push_back("");
00649 spaces.push_back(" ");
00650
00651 size_t i_smiley = std::string::npos;
00652
00653 for( unsigned int i = 0; i < spaces.size(); i++)
00654 {
00655 for( unsigned int j = 0; j < smileys_.size(); j++ )
00656 {
00657 i_smiley = text_for_emotion_.find( words_it->second + spaces.at(i) + smileys_.at( j ), 0 );
00658 if( i_smiley != std::string::npos && (smileys_.at( j ) == ":)") )
00659 {
00660 afraid_ = false;
00661 disgusted_ = false;
00662 surprised_ = false;
00663 smile_ = true;
00664 angry_ = false;
00665 sad_ = false;
00666 rest_ = false;
00667 }
00668 else if( i_smiley != std::string::npos && (smileys_.at( j ) == ":(" ) )
00669 {
00670 afraid_ = false;
00671 disgusted_ = false;
00672 surprised_ = false;
00673 sad_ = true;
00674 angry_ = false;
00675 smile_ = false;
00676 rest_ = false;
00677 }
00678 else if( i_smiley != std::string::npos && (smileys_.at( j ) == ">:" ) )
00679 {
00680 afraid_ = false;
00681 disgusted_ = false;
00682 surprised_ = false;
00683 angry_ = true;
00684 sad_ = false;
00685 smile_ = false;
00686 rest_ = false;
00687 }
00688 else if( i_smiley != std::string::npos && (smileys_.at( j ) == "." ) )
00689 {
00690 afraid_ = false;
00691 disgusted_ = false;
00692 surprised_ = false;
00693 rest_ = true;
00694 sad_ = false;
00695 smile_ = false;
00696 angry_ = false;
00697 }
00698 else if( i_smiley != std::string::npos && (smileys_.at( j ) == ":O" || smileys_.at( j ) == ":o") )
00699 {
00700 afraid_ = false;
00701 disgusted_ = false;
00702 surprised_ = true;
00703 rest_ = false;
00704 sad_ = false;
00705 smile_ = false;
00706 angry_ = false;
00707 }
00708 else if( i_smiley != std::string::npos && (smileys_.at( j ) == ":!") )
00709 {
00710 afraid_ = false;
00711 disgusted_ = true;
00712 surprised_ = false;
00713 rest_ = false;
00714 sad_ = false;
00715 smile_ = false;
00716 angry_ = false;
00717 }
00718 else if( i_smiley != std::string::npos && (smileys_.at( j ) == ":&") )
00719 {
00720 afraid_ = true;
00721 disgusted_ = false;
00722 surprised_ = false;
00723 rest_ = false;
00724 sad_ = false;
00725 smile_ = false;
00726 angry_ = false;
00727 }
00728 i_smiley = text_for_emotion_.find( smileys_.at( j ) + spaces.at(i) + words_it->second, 0 );
00729 if( i_smiley != std::string::npos && (smileys_.at( j ) == ":)") )
00730 {
00731 afraid_ = false;
00732 disgusted_ = false;
00733 surprised_ = false;
00734 smile_ = true;
00735 angry_ = false;
00736 sad_ = false;
00737 rest_ = false;
00738 }
00739 else if( i_smiley != std::string::npos && (smileys_.at( j ) == ":(" ) )
00740 {
00741 afraid_ = false;
00742 disgusted_ = false;
00743 surprised_ = false;
00744 sad_ = true;
00745 angry_ = false;
00746 smile_ = false;
00747 rest_ = false;
00748 }
00749 else if( i_smiley != std::string::npos && (smileys_.at( j ) == ">:" ) )
00750 {
00751 afraid_ = false;
00752 disgusted_ = false;
00753 surprised_ = false;
00754 angry_ = true;
00755 sad_ = false;
00756 smile_ = false;
00757 rest_ = false;
00758 }
00759 else if( i_smiley != std::string::npos && (smileys_.at( j ) == "." ) )
00760 {
00761 afraid_ = false;
00762 disgusted_ = false;
00763 surprised_ = false;
00764 rest_ = true;
00765 sad_ = false;
00766 smile_ = false;
00767 angry_ = false;
00768 }
00769 else if( i_smiley != std::string::npos && (smileys_.at( j ) == ":O" || smileys_.at( j ) == ":o") )
00770 {
00771 afraid_ = false;
00772 disgusted_ = false;
00773 surprised_ = true;
00774 rest_ = false;
00775 sad_ = false;
00776 smile_ = false;
00777 angry_ = false;
00778 }
00779 else if( i_smiley != std::string::npos && (smileys_.at( j ) == ":!") )
00780 {
00781 afraid_ = false;
00782 disgusted_ = true;
00783 surprised_ = false;
00784 rest_ = false;
00785 sad_ = false;
00786 smile_ = false;
00787 angry_ = false;
00788 }
00789 else if( i_smiley != std::string::npos && (smileys_.at( j ) == ":&") )
00790 {
00791 afraid_ = true;
00792 disgusted_ = false;
00793 surprised_ = false;
00794 rest_ = false;
00795 sad_ = false;
00796 smile_ = false;
00797 angry_ = false;
00798 }
00799 }
00800 }
00801
00802 text_for_emotion_.erase(0, (words_it->second).length());
00803
00804 if( words_it != word_map_.end() )
00805 words_it++;
00806 }
00807
00808 for( unsigned int curVAT = 0; curVAT < vertex_animation_tracks_.size(); curVAT++ )
00809 {
00810 if( vertex_animation_tracks_[ curVAT ]->getParent()->getName() == mouth_animation_state_name_ )
00811 {
00812 vertex_animation_tracks_[ curVAT ]->getParent()->setLength( visemes_it->first );
00813
00814 if( (words_it->first == visemes_it->first) && (smile_ || sad_ || angry_ || rest_ || surprised_ || disgusted_))
00815 {
00816 manual_key_frame_ = vertex_animation_tracks_[ curVAT ]->createVertexPoseKeyFrame( visemes_it->first - 0.5 );
00817 }
00818 else
00819 {
00820 manual_key_frame_ = vertex_animation_tracks_[ curVAT ]->createVertexPoseKeyFrame( visemes_it->first );
00821 }
00822
00823 for( unsigned int curPoseIndex = 0; curPoseIndex < mesh_->getPoseCount(); curPoseIndex++ )
00824 {
00825 float influence = static_cast<float>(rand()) / static_cast<float>((RAND_MAX * (1.0 - 0.75 + 1) + 0.75));
00826
00827 if( visemes_it->second == "wide" && Ogre::StringUtil::startsWith( pose_list_[ curPoseIndex ]->getName(), "mouth-wide", true ) )
00828 {
00829 manual_key_frame_->addPoseReference( curPoseIndex, influence );
00830 }
00831 if( visemes_it->second == "narrow" && Ogre::StringUtil::startsWith( pose_list_[ curPoseIndex ]->getName(), "mouth-narrow", true ) )
00832 {
00833 manual_key_frame_->addPoseReference( curPoseIndex, influence );
00834 }
00835 if( visemes_it->second == "open" && Ogre::StringUtil::startsWith( pose_list_[ curPoseIndex ]->getName(), "mouth-open", true ) )
00836 {
00837 manual_key_frame_->addPoseReference( curPoseIndex, influence );
00838 }
00839 if( visemes_it->second == "close" && Ogre::StringUtil::startsWith( pose_list_[ curPoseIndex ]->getName(), "mouth-close", true ) )
00840 {
00841 manual_key_frame_->addPoseReference( curPoseIndex, influence );
00842 }
00843 if( smile_ && Ogre::StringUtil::startsWith( pose_list_[ curPoseIndex ]->getName(), "mouth-smile", true ) )
00844 {
00845 manual_key_frame_->addPoseReference( curPoseIndex, 0.85 );
00846 }
00847 if( sad_ && Ogre::StringUtil::startsWith( pose_list_[ curPoseIndex ]->getName(), "mouth-sad", true ) )
00848 {
00849 manual_key_frame_->addPoseReference( curPoseIndex, 0.85 );
00850 }
00851 if( angry_ && Ogre::StringUtil::startsWith( pose_list_[ curPoseIndex ]->getName(), "mouth-sad", true ) )
00852 {
00853 manual_key_frame_->addPoseReference( curPoseIndex, 0.85 );
00854 }
00855 if( rest_ && Ogre::StringUtil::startsWith( pose_list_[ curPoseIndex ]->getName(), "mouth-rest", true ) )
00856 {
00857 manual_key_frame_->addPoseReference( curPoseIndex, 1.0 );
00858 }
00859 if( surprised_ && Ogre::StringUtil::startsWith( pose_list_[ curPoseIndex ]->getName(), "mouth-narrow", true ) )
00860 {
00861 manual_key_frame_->addPoseReference( curPoseIndex, 0.5 );
00862 }
00863 if( surprised_ && Ogre::StringUtil::startsWith( pose_list_[ curPoseIndex ]->getName(), "mouth-open", true ) )
00864 {
00865 manual_key_frame_->addPoseReference( curPoseIndex, 0.5 );
00866 }
00867 if( disgusted_ && Ogre::StringUtil::startsWith( pose_list_[ curPoseIndex ]->getName(), "mouth-disgusted", true ) )
00868 {
00869 manual_key_frame_->addPoseReference( curPoseIndex, 1.0 );
00870 }
00871 if( afraid_ && Ogre::StringUtil::startsWith( pose_list_[ curPoseIndex ]->getName(), "mouth-open", true ) )
00872 {
00873 manual_key_frame_->addPoseReference( curPoseIndex, 0.9 );
00874 }
00875 if( afraid_ && Ogre::StringUtil::startsWith( pose_list_[ curPoseIndex ]->getName(), "mouth-afraid", true ) )
00876 {
00877 manual_key_frame_->addPoseReference( curPoseIndex, 1.0 );
00878 }
00879 if( visemes_it->second == "pau" && Ogre::StringUtil::startsWith( pose_list_[ curPoseIndex ]->getName(), "mouth-rest", true ) )
00880 {
00881 manual_key_frame_->addPoseReference( curPoseIndex, influence );
00882 }
00883 }
00884 }
00885 if( vertex_animation_tracks_[ curVAT ]->getParent()->getName() == eyebrows_animation_state_name_ )
00886 {
00887 vertex_animation_tracks_[ curVAT ]->getParent()->setLength( visemes_it->first );
00888
00889 if( (words_it->first == visemes_it->first) && (smile_ || sad_ || angry_ || rest_ || surprised_ || disgusted_ ))
00890 {
00891 manual_key_frame_ = vertex_animation_tracks_[ curVAT ]->createVertexPoseKeyFrame( visemes_it->first - 0.5 );
00892 }
00893 else
00894 {
00895 manual_key_frame_ = vertex_animation_tracks_[ curVAT ]->createVertexPoseKeyFrame( visemes_it->first );
00896 }
00897
00898 for( unsigned int curPoseIndex = 0; curPoseIndex < mesh_->getPoseCount(); curPoseIndex++ )
00899 {
00900 float influence = 0.9;
00901
00902 if( rest_ && Ogre::StringUtil::startsWith( pose_list_[ curPoseIndex ]->getName(), "eyebrows-rest", true ) )
00903 {
00904 manual_key_frame_->addPoseReference( curPoseIndex, influence );
00905 }
00906 if( visemes_it->second == "pau" && Ogre::StringUtil::startsWith( pose_list_[ curPoseIndex ]->getName(), "eyebrows-rest", true ) )
00907 {
00908 manual_key_frame_->addPoseReference( curPoseIndex, influence );
00909 }
00910 if( smile_ && Ogre::StringUtil::startsWith( pose_list_[ curPoseIndex ]->getName(), "eyebrows-up", true ) )
00911 {
00912 manual_key_frame_->addPoseReference( curPoseIndex, influence );
00913 }
00914 if( sad_ && Ogre::StringUtil::startsWith( pose_list_[ curPoseIndex ]->getName(), "eyebrows-sad", true ) )
00915 {
00916 manual_key_frame_->addPoseReference( curPoseIndex, influence );
00917 }
00918 if( angry_ && Ogre::StringUtil::startsWith( pose_list_[ curPoseIndex ]->getName(), "eyebrows-down", true ) )
00919 {
00920 manual_key_frame_->addPoseReference( curPoseIndex, influence );
00921 }
00922 if( surprised_ && Ogre::StringUtil::startsWith( pose_list_[ curPoseIndex ]->getName(), "eyebrows-up", true ) )
00923 {
00924 manual_key_frame_->addPoseReference( curPoseIndex, influence );
00925 }
00926 if( disgusted_ && Ogre::StringUtil::startsWith( pose_list_[ curPoseIndex ]->getName(), "eyebrows-frown", true ) )
00927 {
00928 manual_key_frame_->addPoseReference( curPoseIndex, influence );
00929 }
00930 if( afraid_ && Ogre::StringUtil::startsWith( pose_list_[ curPoseIndex ]->getName(), "eyebrows-up", true ) )
00931 {
00932 manual_key_frame_->addPoseReference( curPoseIndex, influence );
00933 }
00934 if( afraid_ && Ogre::StringUtil::startsWith( pose_list_[ curPoseIndex ]->getName(), "eyebrows-frown", true ) )
00935 {
00936 manual_key_frame_->addPoseReference( curPoseIndex, influence );
00937 }
00938 if( Ogre::StringUtil::startsWith( pose_list_[ curPoseIndex ]->getName(), "eyebrows-rest", true ) )
00939 manual_key_frame_->addPoseReference( curPoseIndex, influence );
00940 }
00941
00942 }
00943 }
00944 }
00945
00946 visemes_arrived_ = true;
00947 }
00948
00949
00950 void TalkingHead::updatePoses( Ogre::String pose_name, float weight )
00951 {
00952 int curPoseIndex = 0;
00953
00954 for( int curSubMesh = 1; curSubMesh <= num_sub_meshes_; curSubMesh++ )
00955 {
00956 while( pose_list_[ curPoseIndex ]->getTarget() == curSubMesh-1 )
00957 {
00958 if( Ogre::StringUtil::startsWith( pose_list_[ curPoseIndex ]->getName(), pose_name, true ) )
00959 {
00960 if(manual_key_frame_)
00961 {
00962 manual_key_frame_->updatePoseReference( curPoseIndex, weight );
00963 }
00964 }
00965 curPoseIndex++;
00966 }
00967 }
00968 }
00969
00970
00971 void TalkingHead::callbackVisemes( const std_msgs::Empty::ConstPtr& msg )
00972 {
00973 words_.clear();
00974 phones_.clear();
00975
00976 std::ifstream wordsfile( "words.txt" );
00977
00978 if( wordsfile )
00979 {
00980 Ogre::String line;
00981
00982 while( getline( wordsfile, line ) )
00983 {
00984 words_.push_back( line );
00985 }
00986
00987 wordsfile.close();
00988 remove( "words.txt" );
00989
00990 word_map_ = createWordMap();
00991 }
00992
00993 std::ifstream phonemesfile( "phonemes.txt" );
00994
00995 if( phonemesfile )
00996 {
00997 Ogre::String line;
00998
00999 while( getline( phonemesfile, line ) )
01000 {
01001 phones_.push_back( line );
01002 }
01003
01004 phonemesfile.close();
01005 remove( "phonemes.txt" );
01006
01007 viseme_map_ = createVisemeMap();
01008
01009 playTalkAnimation();
01010 }
01011
01012 if(word_map_.empty() && viseme_map_.empty())
01013 {
01014 word_map_.insert( std::pair<float, Ogre::String>( 0, "" ) );
01015 viseme_map_.insert( std::pair<float, Ogre::String>( 0, "" ) );
01016 playTalkAnimation();
01017 }
01018 }
01019
01020
01021 void TalkingHead::callbackTextForEmotion(const std_msgs::String::ConstPtr &msg)
01022 {
01023 text_for_emotion_ = msg->data;
01024 word_map_.clear();
01025 viseme_map_.clear();
01026 }
01027
01028
01029 void TalkingHead::callbackResetAnimation( const std_msgs::String::ConstPtr& msg)
01030 {
01031 word_map_.clear();
01032 viseme_map_.clear();
01033 }