Public Member Functions | Public Attributes | Protected Attributes | List of all members
SoundAction Class Reference

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_
 

Detailed Description

Definition at line 32 of file sound.cpp.

Constructor & Destructor Documentation

SoundAction::SoundAction ( )
inline

Definition at line 61 of file sound.cpp.

SoundAction::~SoundAction ( void  )
inline

Definition at line 68 of file sound.cpp.

Member Function Documentation

void SoundAction::as_cb_say_ ( const cob_sound::SayGoalConstPtr &  goal)
inline

Definition at line 136 of file sound.cpp.

void SoundAction::as_goal_cb_play_ ( )
inline

Definition at line 105 of file sound.cpp.

void SoundAction::as_preempt_cb_play_ ( )
inline

Definition at line 122 of file sound.cpp.

bool SoundAction::fade_in ( )
inline

Definition at line 402 of file sound.cpp.

bool SoundAction::fade_out ( )
inline

Definition at line 430 of file sound.cpp.

bool SoundAction::init ( )
inline

Definition at line 75 of file sound.cpp.

bool SoundAction::play ( std::string  filename,
std::string &  message 
)
inline

Definition at line 278 of file sound.cpp.

void SoundAction::publish_diagnostics ( unsigned char  level,
std::string  message 
)
inline

Definition at line 387 of file sound.cpp.

void SoundAction::publish_marker ( std::string  data)
inline

Definition at line 359 of file sound.cpp.

bool SoundAction::say ( std::string  data,
std::string &  message 
)
inline

Definition at line 236 of file sound.cpp.

bool SoundAction::service_cb_mute ( std_srvs::Trigger::Request &  req,
std_srvs::Trigger::Response &  res 
)
inline

Definition at line 206 of file sound.cpp.

bool SoundAction::service_cb_play ( cob_srvs::SetString::Request &  req,
cob_srvs::SetString::Response &  res 
)
inline

Definition at line 161 of file sound.cpp.

bool SoundAction::service_cb_say ( cob_srvs::SetString::Request &  req,
cob_srvs::SetString::Response &  res 
)
inline

Definition at line 154 of file sound.cpp.

bool SoundAction::service_cb_stop ( std_srvs::Trigger::Request &  req,
std_srvs::Trigger::Response &  res 
)
inline

Definition at line 174 of file sound.cpp.

bool SoundAction::service_cb_unmute ( std_srvs::Trigger::Request &  req,
std_srvs::Trigger::Response &  res 
)
inline

Definition at line 215 of file sound.cpp.

void SoundAction::timer_cb ( const ros::TimerEvent )
inline

Definition at line 330 of file sound.cpp.

void SoundAction::timer_play_feedback_cb ( const ros::TimerEvent )
inline

Definition at line 335 of file sound.cpp.

void SoundAction::topic_cb_play ( const std_msgs::String::ConstPtr &  msg)
inline

Definition at line 230 of file sound.cpp.

void SoundAction::topic_cb_say ( const std_msgs::String::ConstPtr &  msg)
inline

Definition at line 224 of file sound.cpp.

Member Data Documentation

actionlib::SimpleActionServer<cob_sound::PlayAction> SoundAction::as_play_
protected

Definition at line 38 of file sound.cpp.

actionlib::SimpleActionServer<cob_sound::SayAction> SoundAction::as_say_
protected

Definition at line 37 of file sound.cpp.

diagnostic_msgs::DiagnosticArray SoundAction::diagnostics_

Definition at line 56 of file sound.cpp.

ros::Publisher SoundAction::diagnostics_pub_

Definition at line 57 of file sound.cpp.

ros::Timer SoundAction::diagnostics_timer_

Definition at line 58 of file sound.cpp.

double SoundAction::fade_duration_
protected

Definition at line 48 of file sound.cpp.

bool SoundAction::fade_volume_
protected

Definition at line 49 of file sound.cpp.

bool SoundAction::mute_
protected

Definition at line 47 of file sound.cpp.

ros::NodeHandle SoundAction::nh_
protected

Definition at line 36 of file sound.cpp.

ros::Timer SoundAction::play_feedback_timer_
protected

Definition at line 46 of file sound.cpp.

ros::Publisher SoundAction::pubMarker_

Definition at line 59 of file sound.cpp.

ros::ServiceServer SoundAction::srvServer_mute_
protected

Definition at line 42 of file sound.cpp.

ros::ServiceServer SoundAction::srvServer_play_
protected

Definition at line 40 of file sound.cpp.

ros::ServiceServer SoundAction::srvServer_say_
protected

Definition at line 39 of file sound.cpp.

ros::ServiceServer SoundAction::srvServer_stop_
protected

Definition at line 41 of file sound.cpp.

ros::ServiceServer SoundAction::srvServer_unmute_
protected

Definition at line 43 of file sound.cpp.

ros::Subscriber SoundAction::sub_play_
protected

Definition at line 45 of file sound.cpp.

ros::Subscriber SoundAction::sub_say_
protected

Definition at line 44 of file sound.cpp.

libvlc_instance_t* SoundAction::vlc_inst_
protected

Definition at line 51 of file sound.cpp.

libvlc_media_t* SoundAction::vlc_media_
protected

Definition at line 53 of file sound.cpp.

libvlc_media_player_t* SoundAction::vlc_player_
protected

Definition at line 52 of file sound.cpp.


The documentation for this class was generated from the following file:


cob_sound
Author(s): Florian Weisshardt, Benjamin Maidel
autogenerated on Wed Apr 7 2021 02:11:51