Displays the currently spoken sentence. More...
#include <TextOutDisplay.h>
Public Slots | |
void | clearText () |
void | setText (std::string text) |
use setText("") for a delayed text reset | |
Public Member Functions | |
void | callbackTalkingFinished (const std_msgs::String::ConstPtr &msg) |
void | callbackText (const std_msgs::String::ConstPtr &msg) |
void | subscribeWithNodeHandle (ros::NodeHandle node_handle) |
subscribe to topics here | |
TextOutDisplay (int min_height=0, int font_size=15, bool user_input=false, QWidget *parent=0) | |
~TextOutDisplay () | |
Private Member Functions | |
std::string | clearSmileys (std::string text) |
std::string | prepareText (std::string text) |
std::string | trimSpaces (std::string text) |
Private Attributes | |
ros::CallbackQueue | callback_queue_ |
QFont | font_ |
QTimer * | reset_timer_ |
std::vector< std::string > | smileys_ |
ros::Subscriber | talking_finished_subscriber_ |
std::string | text_ |
QLabel * | text_out_label_ |
ros::Subscriber | text_out_subscriber_ |
Define your custom ROS subscribers, callbacks and publishers here. | |
bool | user_input_ |
ros::Subscriber | user_input_subscriber_ |
Displays the currently spoken sentence.
Definition at line 41 of file TextOutDisplay.h.
TextOutDisplay::TextOutDisplay | ( | int | min_height = 0 , |
int | font_size = 15 , |
||
bool | user_input = false , |
||
QWidget * | parent = 0 |
||
) |
Constructor
Definition at line 30 of file TextOutDisplay.cpp.
Destructor
Definition at line 69 of file TextOutDisplay.cpp.
void TextOutDisplay::callbackTalkingFinished | ( | const std_msgs::String::ConstPtr & | msg | ) |
Definition at line 145 of file TextOutDisplay.cpp.
void TextOutDisplay::callbackText | ( | const std_msgs::String::ConstPtr & | msg | ) |
Definition at line 136 of file TextOutDisplay.cpp.
std::string TextOutDisplay::clearSmileys | ( | std::string | text | ) | [private] |
Definition at line 167 of file TextOutDisplay.cpp.
void TextOutDisplay::clearText | ( | ) | [slot] |
Definition at line 73 of file TextOutDisplay.cpp.
std::string TextOutDisplay::prepareText | ( | std::string | text | ) | [private] |
Definition at line 150 of file TextOutDisplay.cpp.
void TextOutDisplay::setText | ( | std::string | text | ) | [slot] |
use setText("") for a delayed text reset
Definition at line 88 of file TextOutDisplay.cpp.
void TextOutDisplay::subscribeWithNodeHandle | ( | ros::NodeHandle | node_handle | ) |
subscribe to topics here
Definition at line 123 of file TextOutDisplay.cpp.
std::string TextOutDisplay::trimSpaces | ( | std::string | text | ) | [private] |
Definition at line 188 of file TextOutDisplay.cpp.
Definition at line 86 of file TextOutDisplay.h.
QFont TextOutDisplay::font_ [private] |
Definition at line 73 of file TextOutDisplay.h.
QTimer* TextOutDisplay::reset_timer_ [private] |
Definition at line 75 of file TextOutDisplay.h.
std::vector<std::string> TextOutDisplay::smileys_ [private] |
Definition at line 77 of file TextOutDisplay.h.
Definition at line 84 of file TextOutDisplay.h.
std::string TextOutDisplay::text_ [private] |
Definition at line 70 of file TextOutDisplay.h.
QLabel* TextOutDisplay::text_out_label_ [private] |
Definition at line 72 of file TextOutDisplay.h.
Define your custom ROS subscribers, callbacks and publishers here.
Definition at line 82 of file TextOutDisplay.h.
bool TextOutDisplay::user_input_ [private] |
Definition at line 79 of file TextOutDisplay.h.
Definition at line 83 of file TextOutDisplay.h.