Public Member Functions | |
void | as_cb_say_ (const cob_sound::SayGoalConstPtr &goal) |
void | as_goal_cb_play_ () |
void | as_preempt_cb_play_ () |
bool | fade_in () |
bool | fade_out () |
bool | init () |
bool | play (std::string filename, std::string &message) |
void | publish_diagnostics (unsigned char level, std::string message) |
void | publish_marker (std::string data) |
bool | say (std::string data, std::string &message) |
bool | service_cb_mute (std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res) |
bool | service_cb_play (cob_srvs::SetString::Request &req, cob_srvs::SetString::Response &res) |
bool | service_cb_say (cob_srvs::SetString::Request &req, cob_srvs::SetString::Response &res) |
bool | service_cb_stop (std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res) |
bool | service_cb_unmute (std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res) |
SoundAction () | |
void | timer_cb (const ros::TimerEvent &) |
void | timer_play_feedback_cb (const ros::TimerEvent &) |
void | topic_cb_play (const std_msgs::String::ConstPtr &msg) |
void | topic_cb_say (const std_msgs::String::ConstPtr &msg) |
~SoundAction (void) | |
Public Attributes | |
diagnostic_msgs::DiagnosticArray | diagnostics_ |
ros::Publisher | diagnostics_pub_ |
ros::Timer | diagnostics_timer_ |
ros::Publisher | pubMarker_ |
Protected Attributes | |
actionlib::SimpleActionServer < cob_sound::PlayAction > | as_play_ |
actionlib::SimpleActionServer < cob_sound::SayAction > | as_say_ |
double | fade_duration_ |
bool | fade_volume_ |
bool | mute_ |
ros::NodeHandle | nh_ |
ros::Timer | play_feedback_timer_ |
ros::ServiceServer | srvServer_mute_ |
ros::ServiceServer | srvServer_play_ |
ros::ServiceServer | srvServer_say_ |
ros::ServiceServer | srvServer_stop_ |
ros::ServiceServer | srvServer_unmute_ |
ros::Subscriber | sub_play_ |
ros::Subscriber | sub_say_ |
libvlc_instance_t * | vlc_inst_ |
libvlc_media_t * | vlc_media_ |
libvlc_media_player_t * | vlc_player_ |
SoundAction::SoundAction | ( | ) | [inline] |
SoundAction::~SoundAction | ( | void | ) | [inline] |
void SoundAction::as_cb_say_ | ( | const cob_sound::SayGoalConstPtr & | goal | ) | [inline] |
void SoundAction::as_goal_cb_play_ | ( | ) | [inline] |
void SoundAction::as_preempt_cb_play_ | ( | ) | [inline] |
bool SoundAction::fade_in | ( | ) | [inline] |
bool SoundAction::fade_out | ( | ) | [inline] |
bool SoundAction::init | ( | ) | [inline] |
bool SoundAction::play | ( | std::string | filename, |
std::string & | message | ||
) | [inline] |
void SoundAction::publish_diagnostics | ( | unsigned char | level, |
std::string | message | ||
) | [inline] |
void SoundAction::publish_marker | ( | std::string | data | ) | [inline] |
bool SoundAction::say | ( | std::string | data, |
std::string & | message | ||
) | [inline] |
bool SoundAction::service_cb_mute | ( | std_srvs::Trigger::Request & | req, |
std_srvs::Trigger::Response & | res | ||
) | [inline] |
bool SoundAction::service_cb_play | ( | cob_srvs::SetString::Request & | req, |
cob_srvs::SetString::Response & | res | ||
) | [inline] |
bool SoundAction::service_cb_say | ( | cob_srvs::SetString::Request & | req, |
cob_srvs::SetString::Response & | res | ||
) | [inline] |
bool SoundAction::service_cb_stop | ( | std_srvs::Trigger::Request & | req, |
std_srvs::Trigger::Response & | res | ||
) | [inline] |
bool SoundAction::service_cb_unmute | ( | std_srvs::Trigger::Request & | req, |
std_srvs::Trigger::Response & | res | ||
) | [inline] |
void SoundAction::timer_cb | ( | const ros::TimerEvent & | ) | [inline] |
void SoundAction::timer_play_feedback_cb | ( | const ros::TimerEvent & | ) | [inline] |
void SoundAction::topic_cb_play | ( | const std_msgs::String::ConstPtr & | msg | ) | [inline] |
void SoundAction::topic_cb_say | ( | const std_msgs::String::ConstPtr & | msg | ) | [inline] |
actionlib::SimpleActionServer<cob_sound::PlayAction> SoundAction::as_play_ [protected] |
actionlib::SimpleActionServer<cob_sound::SayAction> SoundAction::as_say_ [protected] |
diagnostic_msgs::DiagnosticArray SoundAction::diagnostics_ |
double SoundAction::fade_duration_ [protected] |
bool SoundAction::fade_volume_ [protected] |
bool SoundAction::mute_ [protected] |
ros::NodeHandle SoundAction::nh_ [protected] |
ros::Timer SoundAction::play_feedback_timer_ [protected] |
ros::ServiceServer SoundAction::srvServer_mute_ [protected] |
ros::ServiceServer SoundAction::srvServer_play_ [protected] |
ros::ServiceServer SoundAction::srvServer_say_ [protected] |
ros::ServiceServer SoundAction::srvServer_stop_ [protected] |
ros::ServiceServer SoundAction::srvServer_unmute_ [protected] |
ros::Subscriber SoundAction::sub_play_ [protected] |
ros::Subscriber SoundAction::sub_say_ [protected] |
libvlc_instance_t* SoundAction::vlc_inst_ [protected] |
libvlc_media_t* SoundAction::vlc_media_ [protected] |
libvlc_media_player_t* SoundAction::vlc_player_ [protected] |