TalkingHead.h
Go to the documentation of this file.
00001 /*******************************************************************************
00002  *  TalkingHead - A talking head for robots
00003  *  Copyright (C) 2012 AG Aktives Sehen <agas@uni-koblenz.de>
00004  *                     Universitaet Koblenz-Landau
00005  *
00006  *  This program is free software: you can redistribute it and/or modify
00007  *  it under the terms of the GNU General Public License as published by
00008  *  the Free Software Foundation, either version 3 of the License, or
00009  *  (at your option) any later version.
00010  *
00011  *  This program is distributed in the hope that it will be useful,
00012  *  but WITHOUT ANY WARRANTY; without even the implied warranty of
00013  *  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
00014  *  Library General Public License for more details.
00015  *
00016  *  You should have received a copy of the GNU Library General Public
00017  *  License along with this library; if not, write to the Free Software
00018  *  Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
00019  *  MA 02110-1301  USA or see <http://www.gnu.org/licenses/>.
00020  *******************************************************************************/
00021 
00022 #ifndef TALKING_HEAD_INCLUDE_TALKINGHEAD_H_
00023 #define TALKING_HEAD_INCLUDE_TALKINGHEAD_H_
00024 
00025 #include <OgreAnimation.h>
00026 #include <OgreCamera.h>
00027 #include <OgreConfigFile.h>
00028 #include <OgreEntity.h>
00029 #include <OgreLogManager.h>
00030 #include <OgreMaterialManager.h>
00031 #include <OgreMeshManager.h>
00032 #include <OgreRenderWindow.h>
00033 #include <OgreRoot.h>
00034 #include <OgreSceneManager.h>
00035 #include <OgreViewport.h>
00036 #include <OgreWindowEventUtilities.h>
00037 
00038 #include <QtGui>
00039 
00040 #include <ros/callback_queue.h>
00041 #include <ros/package.h>
00042 #include <ros/ros.h>
00043 #include <std_msgs/Empty.h>
00044 #include <std_msgs/String.h>
00045 
00046 #include <iostream>
00047 #include <istream>
00048 #include <map>
00049 #include <string>
00050 #include <vector>
00051 
00052 
00059 class TalkingHead : public QWidget, public Ogre::FrameListener, public Ogre::WindowEventListener
00060 {
00061     Q_OBJECT
00062 
00063     public:
00064 
00066         TalkingHead( QWidget *parent = 0, std::string mesh_string = "", std::vector< std::vector<float> > material_vector = std::vector< std::vector<float> >() );
00067         
00069         virtual ~TalkingHead();
00070         
00072         void initOgreSystem( void );
00073         
00075         void callbackVisemes( const std_msgs::Empty::ConstPtr& msg );
00076         void callbackTextForEmotion( const std_msgs::String::ConstPtr& msg );
00077         void callbackResetAnimation( const std_msgs::String::ConstPtr& msg);
00078 
00080         void subscribeWithNodeHandle( ros::NodeHandle node_handle );
00081 
00082     public slots:
00083 
00084         void updateOverlay();
00085 
00086     protected:
00087 
00089         virtual void paintEvent( QPaintEvent* event );
00090         virtual void resizeEvent( QResizeEvent* event );
00091         virtual void showEvent( QShowEvent* event );
00092         virtual void moveEvent( QMoveEvent* event );
00093 
00094     private:
00095 
00097         std::vector<Ogre::String>                               phones_;
00098         std::vector<Ogre::String>                               words_;
00099 
00101         Ogre::Root*                                             root_;
00102         Ogre::Camera*                                           camera_;
00103         Ogre::Viewport*                                         viewport_;
00104         Ogre::SceneManager*                                     scene_manager_;
00105         bool                                                    shut_down_;
00106         Ogre::RenderWindow*                                     window_;
00107 
00109         Ogre::MeshPtr                                           mesh_;
00110         std::string                                             mesh_string_;
00111         std::vector< std::vector<float> >                       material_vector_;
00112         Ogre::MaterialPtr                                       material_;
00113         Ogre::PoseList                                          pose_list_;
00114         int                                                     num_sub_meshes_;
00115         Ogre::AnimationStateSet*                                anim_set_;
00116         Ogre::AnimationState*                                   mouth_animation_state_;
00117         Ogre::String                                            mouth_animation_state_name_;
00118         Ogre::AnimationState*                                   eyebrows_animation_state_;
00119         Ogre::String                                            eyebrows_animation_state_name_;
00120         std::vector<Ogre::VertexAnimationTrack*>                vertex_animation_tracks_;
00121         Ogre::VertexPoseKeyFrame*                               manual_key_frame_;
00122         bool                                                    visemes_arrived_;
00123         bool                                                    words_arrived_;
00124         std::map<float, Ogre::String>                           word_map_;
00125         std::map<float, Ogre::String>                           viseme_map_;
00127         std::map<Ogre::String, Ogre::String>                    phonemes_;
00128         std::string                                             text_for_emotion_;
00129 
00130         QTimer*                                                 redraw_timer_;
00131 
00133         ros::Subscriber                                         viseme_subscriber_;
00134         ros::Subscriber                                         emotion_subscriber_;
00135         ros::Subscriber                                         talking_finished_subscriber_;
00136 
00138         std::vector<std::string>                                smileys_;
00139         bool                                                    angry_;
00140         bool                                                    smile_;
00141         bool                                                    sad_;
00142         bool                                                    rest_;
00143         bool                                                    surprised_;
00144         bool                                                    disgusted_;
00145         bool                                                    afraid_;
00146 
00148         virtual bool frameRenderingQueued( const Ogre::FrameEvent& evt );
00149 
00151         void createAnimations( std::string mesh_file );
00152 
00154         void initAnimationStates();
00155 
00157         void initPhoneMap();
00158 
00160         std::map<float, Ogre::String> createVisemeMap();
00161 
00163         std::map<float, Ogre::String> createWordMap();
00164 
00166         void playTalkAnimation();
00167 
00169         void updatePoses( Ogre::String pose_name, float weight );
00170 
00172         void changeMaterialColor();
00173 
00174 };
00175 
00176 #endif // TALKING_HEAD_INCLUDE_TALKINGHEAD_H_


robot_face
Author(s): AGAS, Julian Giesen, David Gossow
autogenerated on Mon Oct 6 2014 04:10:26