Displays a TalkingHead. More...
#include <TalkingHead.h>
Public Slots | |
| void | updateOverlay () | 
Public Member Functions | |
| void | callbackResetAnimation (const std_msgs::String::ConstPtr &msg) | 
| void | callbackTextForEmotion (const std_msgs::String::ConstPtr &msg) | 
| void | callbackVisemes (const std_msgs::Empty::ConstPtr &msg) | 
| is called when a String-msg arrives and activates speech synth. / animation.   | |
| void | initOgreSystem (void) | 
| Creates Ogre::Scene and manages Renderingloop.   | |
| void | subscribeWithNodeHandle (ros::NodeHandle node_handle) | 
| subscribe to topics here   | |
| TalkingHead (QWidget *parent=0, std::string mesh_string="", std::vector< std::vector< float > > material_vector=std::vector< std::vector< float > >()) | |
| virtual | ~TalkingHead () | 
Protected Member Functions | |
| virtual void | moveEvent (QMoveEvent *event) | 
| virtual void | paintEvent (QPaintEvent *event) | 
| Qt related.   | |
| virtual void | resizeEvent (QResizeEvent *event) | 
| virtual void | showEvent (QShowEvent *event) | 
Private Member Functions | |
| void | changeMaterialColor () | 
| change material colors for each submesh   | |
| void | createAnimations (std::string mesh_file) | 
| Loads a Mesh with Poses/ShapeKeys and creates an Animation for the Poses.   | |
| std::map< float, Ogre::String > | createVisemeMap () | 
| std::map< float, Ogre::String > | createWordMap () | 
| virtual bool | frameRenderingQueued (const Ogre::FrameEvent &evt) | 
| Ogre::FrameListener.   | |
| void | initAnimationStates () | 
| initialises the AnimationState   | |
| void | initPhoneMap () | 
| initialises the map of phonemes with correspondent visemes.   | |
| void | playTalkAnimation () | 
| creates the Keyframes for Mouth and enables them for Animation   | |
| void | updatePoses (Ogre::String pose_name, float weight) | 
| updates the poses   | |
Private Attributes | |
| bool | afraid_ | 
| bool | angry_ | 
| Ogre::AnimationStateSet * | anim_set_ | 
| Ogre::Camera * | camera_ | 
| bool | disgusted_ | 
| ros::Subscriber | emotion_subscriber_ | 
| Ogre::AnimationState * | eyebrows_animation_state_ | 
| Ogre::String | eyebrows_animation_state_name_ | 
| Ogre::VertexPoseKeyFrame * | manual_key_frame_ | 
| Ogre::MaterialPtr | material_ | 
| std::vector< std::vector< float > > | material_vector_ | 
| Ogre::MeshPtr | mesh_ | 
| PoseAnimation.   | |
| std::string | mesh_string_ | 
| Ogre::AnimationState * | mouth_animation_state_ | 
| Ogre::String | mouth_animation_state_name_ | 
| int | num_sub_meshes_ | 
| std::map< Ogre::String,  Ogre::String >  | phonemes_ | 
| map of phonemes with correspondent visemes   | |
| std::vector< Ogre::String > | phones_ | 
| File Access.   | |
| Ogre::PoseList | pose_list_ | 
| QTimer * | redraw_timer_ | 
| bool | rest_ | 
| Ogre::Root * | root_ | 
| Ogre::Scene.   | |
| bool | sad_ | 
| Ogre::SceneManager * | scene_manager_ | 
| bool | shut_down_ | 
| bool | smile_ | 
| std::vector< std::string > | smileys_ | 
| Emotion related.   | |
| bool | surprised_ | 
| ros::Subscriber | talking_finished_subscriber_ | 
| std::string | text_for_emotion_ | 
| std::vector < Ogre::VertexAnimationTrack * >  | vertex_animation_tracks_ | 
| Ogre::Viewport * | viewport_ | 
| std::map< float, Ogre::String > | viseme_map_ | 
| ros::Subscriber | viseme_subscriber_ | 
| Define your custom ROS subscribers, callbacks and publishers here.   | |
| bool | visemes_arrived_ | 
| Ogre::RenderWindow * | window_ | 
| std::map< float, Ogre::String > | word_map_ | 
| std::vector< Ogre::String > | words_ | 
| bool | words_arrived_ | 
Displays a TalkingHead.
Definition at line 59 of file TalkingHead.h.
| TalkingHead::TalkingHead | ( | QWidget * | parent = 0,  | 
        
| std::string | mesh_string = "",  | 
        ||
| std::vector< std::vector< float > > | material_vector = std::vector< std::vector<float> >()  | 
        ||
| ) | 
QWidget Constructor
Definition at line 36 of file TalkingHead.cpp.
| TalkingHead::~TalkingHead | ( | ) |  [virtual] | 
        
Destructor
Definition at line 91 of file TalkingHead.cpp.
| void TalkingHead::callbackResetAnimation | ( | const std_msgs::String::ConstPtr & | msg | ) | 
Definition at line 1029 of file TalkingHead.cpp.
| void TalkingHead::callbackTextForEmotion | ( | const std_msgs::String::ConstPtr & | msg | ) | 
Definition at line 1021 of file TalkingHead.cpp.
| void TalkingHead::callbackVisemes | ( | const std_msgs::Empty::ConstPtr & | msg | ) | 
is called when a String-msg arrives and activates speech synth. / animation.
Definition at line 971 of file TalkingHead.cpp.
| void TalkingHead::changeMaterialColor | ( | ) |  [private] | 
        
change material colors for each submesh
Definition at line 467 of file TalkingHead.cpp.
| void TalkingHead::createAnimations | ( | std::string | mesh_file | ) |  [private] | 
        
Loads a Mesh with Poses/ShapeKeys and creates an Animation for the Poses.
Definition at line 406 of file TalkingHead.cpp.
| std::map< float, Ogre::String > TalkingHead::createVisemeMap | ( | ) |  [private] | 
        
Definition at line 577 of file TalkingHead.cpp.
| std::map< float, Ogre::String > TalkingHead::createWordMap | ( | ) |  [private] | 
        
Definition at line 603 of file TalkingHead.cpp.
| bool TalkingHead::frameRenderingQueued | ( | const Ogre::FrameEvent & | evt | ) |  [private, virtual] | 
        
Ogre::FrameListener.
Definition at line 344 of file TalkingHead.cpp.
| void TalkingHead::initAnimationStates | ( | ) |  [private] | 
        
initialises the AnimationState
Definition at line 505 of file TalkingHead.cpp.
| void TalkingHead::initOgreSystem | ( | void | ) | 
Creates Ogre::Scene and manages Renderingloop.
Definition at line 174 of file TalkingHead.cpp.
| void TalkingHead::initPhoneMap | ( | ) |  [private] | 
        
initialises the map of phonemes with correspondent visemes.
Definition at line 524 of file TalkingHead.cpp.
| void TalkingHead::moveEvent | ( | QMoveEvent * | event | ) |  [protected, virtual] | 
        
Definition at line 141 of file TalkingHead.cpp.
| void TalkingHead::paintEvent | ( | QPaintEvent * | event | ) |  [protected, virtual] | 
        
Qt related.
Definition at line 130 of file TalkingHead.cpp.
| void TalkingHead::playTalkAnimation | ( | ) |  [private] | 
        
creates the Keyframes for Mouth and enables them for Animation
Definition at line 625 of file TalkingHead.cpp.
| void TalkingHead::resizeEvent | ( | QResizeEvent * | event | ) |  [protected, virtual] | 
        
Definition at line 153 of file TalkingHead.cpp.
| void TalkingHead::showEvent | ( | QShowEvent * | event | ) |  [protected, virtual] | 
        
Definition at line 119 of file TalkingHead.cpp.
| void TalkingHead::subscribeWithNodeHandle | ( | ros::NodeHandle | node_handle | ) | 
subscribe to topics here
Definition at line 111 of file TalkingHead.cpp.
| void TalkingHead::updateOverlay | ( | ) |  [slot] | 
        
Definition at line 101 of file TalkingHead.cpp.
| void TalkingHead::updatePoses | ( | Ogre::String | pose_name, | 
| float | weight | ||
| ) |  [private] | 
        
updates the poses
Definition at line 950 of file TalkingHead.cpp.
bool TalkingHead::afraid_ [private] | 
        
Definition at line 145 of file TalkingHead.h.
bool TalkingHead::angry_ [private] | 
        
Definition at line 139 of file TalkingHead.h.
Ogre::AnimationStateSet* TalkingHead::anim_set_ [private] | 
        
Definition at line 115 of file TalkingHead.h.
Ogre::Camera* TalkingHead::camera_ [private] | 
        
Definition at line 102 of file TalkingHead.h.
bool TalkingHead::disgusted_ [private] | 
        
Definition at line 144 of file TalkingHead.h.
ros::Subscriber TalkingHead::emotion_subscriber_ [private] | 
        
Definition at line 134 of file TalkingHead.h.
Ogre::AnimationState* TalkingHead::eyebrows_animation_state_ [private] | 
        
Definition at line 118 of file TalkingHead.h.
Ogre::String TalkingHead::eyebrows_animation_state_name_ [private] | 
        
Definition at line 119 of file TalkingHead.h.
Ogre::VertexPoseKeyFrame* TalkingHead::manual_key_frame_ [private] | 
        
Definition at line 121 of file TalkingHead.h.
Ogre::MaterialPtr TalkingHead::material_ [private] | 
        
Definition at line 112 of file TalkingHead.h.
std::vector< std::vector<float> > TalkingHead::material_vector_ [private] | 
        
Definition at line 111 of file TalkingHead.h.
Ogre::MeshPtr TalkingHead::mesh_ [private] | 
        
PoseAnimation.
Definition at line 109 of file TalkingHead.h.
std::string TalkingHead::mesh_string_ [private] | 
        
Definition at line 110 of file TalkingHead.h.
Ogre::AnimationState* TalkingHead::mouth_animation_state_ [private] | 
        
Definition at line 116 of file TalkingHead.h.
Ogre::String TalkingHead::mouth_animation_state_name_ [private] | 
        
Definition at line 117 of file TalkingHead.h.
int TalkingHead::num_sub_meshes_ [private] | 
        
Definition at line 114 of file TalkingHead.h.
std::map<Ogre::String, Ogre::String> TalkingHead::phonemes_ [private] | 
        
map of phonemes with correspondent visemes
Definition at line 127 of file TalkingHead.h.
std::vector<Ogre::String> TalkingHead::phones_ [private] | 
        
File Access.
Definition at line 97 of file TalkingHead.h.
Ogre::PoseList TalkingHead::pose_list_ [private] | 
        
Definition at line 113 of file TalkingHead.h.
QTimer* TalkingHead::redraw_timer_ [private] | 
        
Definition at line 130 of file TalkingHead.h.
bool TalkingHead::rest_ [private] | 
        
Definition at line 142 of file TalkingHead.h.
Ogre::Root* TalkingHead::root_ [private] | 
        
Ogre::Scene.
Definition at line 101 of file TalkingHead.h.
bool TalkingHead::sad_ [private] | 
        
Definition at line 141 of file TalkingHead.h.
Ogre::SceneManager* TalkingHead::scene_manager_ [private] | 
        
Definition at line 104 of file TalkingHead.h.
bool TalkingHead::shut_down_ [private] | 
        
Definition at line 105 of file TalkingHead.h.
bool TalkingHead::smile_ [private] | 
        
Definition at line 140 of file TalkingHead.h.
std::vector<std::string> TalkingHead::smileys_ [private] | 
        
Emotion related.
Definition at line 138 of file TalkingHead.h.
bool TalkingHead::surprised_ [private] | 
        
Definition at line 143 of file TalkingHead.h.
ros::Subscriber TalkingHead::talking_finished_subscriber_ [private] | 
        
Definition at line 135 of file TalkingHead.h.
std::string TalkingHead::text_for_emotion_ [private] | 
        
Definition at line 128 of file TalkingHead.h.
std::vector<Ogre::VertexAnimationTrack*> TalkingHead::vertex_animation_tracks_ [private] | 
        
Definition at line 120 of file TalkingHead.h.
Ogre::Viewport* TalkingHead::viewport_ [private] | 
        
Definition at line 103 of file TalkingHead.h.
std::map<float, Ogre::String> TalkingHead::viseme_map_ [private] | 
        
Definition at line 125 of file TalkingHead.h.
ros::Subscriber TalkingHead::viseme_subscriber_ [private] | 
        
Define your custom ROS subscribers, callbacks and publishers here.
Definition at line 133 of file TalkingHead.h.
bool TalkingHead::visemes_arrived_ [private] | 
        
Definition at line 122 of file TalkingHead.h.
Ogre::RenderWindow* TalkingHead::window_ [private] | 
        
Definition at line 106 of file TalkingHead.h.
std::map<float, Ogre::String> TalkingHead::word_map_ [private] | 
        
Definition at line 124 of file TalkingHead.h.
std::vector<Ogre::String> TalkingHead::words_ [private] | 
        
Definition at line 98 of file TalkingHead.h.
bool TalkingHead::words_arrived_ [private] | 
        
Definition at line 123 of file TalkingHead.h.