Skip to content

Commit

Permalink
fade volume on play and between tracks
Browse files Browse the repository at this point in the history
  • Loading branch information
benmaidel committed Sep 28, 2016
1 parent 3696747 commit 6e18b2a
Showing 1 changed file with 52 additions and 1 deletion.
53 changes: 52 additions & 1 deletion cob_sound/ros/src/sound.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,8 @@ class SoundAction
ros::Subscriber sub_play_;
ros::Timer play_feedback_timer_;
bool mute_;
double fade_duration_;
bool fade_volume_;

libvlc_instance_t* vlc_inst_;
libvlc_media_player_t* vlc_player_;
Expand Down Expand Up @@ -55,6 +57,9 @@ class SoundAction
diagnostics_timer_ = nh_.createTimer(ros::Duration(1.0), &SoundAction::timer_cb, this);
play_feedback_timer_ = nh_.createTimer(ros::Duration(0.25), &SoundAction::timer_play_feedback_cb, this, false, false);
pubMarker_ = nh_.advertise<visualization_msgs::Marker>("marker",1); //Advertise visualization marker topic
fade_volume_ = nh_.param<bool>("fade_volume", true);
fade_duration_ = nh_.param<double>("fade_duration", 0.5);

mute_ = false;

vlc_inst_ = libvlc_new(0,NULL);
Expand Down Expand Up @@ -92,6 +97,7 @@ class SoundAction
{
if(as_play_.isActive())
{
fade_out();
play_feedback_timer_.stop();
libvlc_media_player_stop(vlc_player_);
}
Expand Down Expand Up @@ -136,6 +142,7 @@ class SoundAction
bool service_cb_stop(std_srvs::Trigger::Request &req,
std_srvs::Trigger::Response &res )
{
fade_out();
if(as_play_.isActive())
{
play_feedback_timer_.stop();
Expand Down Expand Up @@ -259,7 +266,8 @@ class SoundAction
{
libvlc_media_player_set_media(vlc_player_, vlc_media_);
libvlc_media_release(vlc_media_);
if(libvlc_media_player_play(vlc_player_) >= 0)
fade_out();
if(fade_in())
{
ret = true;
message = "Play successfull";
Expand Down Expand Up @@ -353,6 +361,49 @@ class SoundAction
pubMarker_.publish(marker);
}

bool fade_in()
{
if(libvlc_media_player_play(vlc_player_) >= 0)
{
if(fade_volume_)
{
while(libvlc_audio_set_volume(vlc_player_,0) != 0)
ros::Duration(0.05).sleep();
for(int i = 0; i < 100; i+=5)
{
libvlc_audio_set_volume(vlc_player_,i);
ros::Duration(fade_duration_/20.0).sleep();
}
}
else
{
while(libvlc_audio_set_volume(vlc_player_,100) != 0)
ros::Duration(0.05).sleep();

}
}
else
return false;
return true;
}

bool fade_out()
{
int volume = libvlc_audio_get_volume(vlc_player_);
if(libvlc_media_player_is_playing(vlc_player_))
{
if(fade_volume_)
{
for(int i = volume - (volume%5); i >=0; i-=5)
{
libvlc_audio_set_volume(vlc_player_,i);
ros::Duration(fade_duration_/20.0).sleep();
}
}
}
return true;
}

};


Expand Down

0 comments on commit 6e18b2a

Please sign in to comment.