Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[jsk_fetch_startup] Do not replace sound when other node is speaking #1366

Merged
merged 4 commits into from
Sep 12, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions jsk_fetch_robot/jsk_fetch.rosinstall.melodic
Original file line number Diff line number Diff line change
Expand Up @@ -71,6 +71,7 @@
local-name: mikeferguson/robot_calibration
uri: https://github.com/mikeferguson/robot_calibration.git
version: 0.5.5
# https://github.com/ros-drivers/audio_common/pull/173
- git:
local-name: ros-drivers/audio_common
uri: https://github.com/ros-drivers/audio_common.git
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@
</node>
<node if="$(arg boot_sound)" pkg="jsk_robot_startup" name="boot_sound" type="boot_sound.py" >
<param name="wav_file" value="$(find jsk_fetch_startup)/data/boot_sound.wav" />
<param name="preferred_interface" value="wlan0" />
</node>

<!-- look at human for Fetch -->
Expand Down
26 changes: 9 additions & 17 deletions jsk_fetch_robot/jsk_fetch_startup/scripts/battery_warning.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,19 +3,15 @@

import actionlib
import rospy
from sound_play.libsoundplay import SoundClient

from power_msgs.msg import BatteryState
from sound_play.msg import SoundRequest
from sound_play.msg import SoundRequestAction
from sound_play.msg import SoundRequestGoal


class BatteryWarning(object):
def __init__(self):
self.client_en = actionlib.SimpleActionClient(
'/sound_play', SoundRequestAction)
self.client_jp = actionlib.SimpleActionClient(
'/robotsound_jp', SoundRequestAction)
self.client_en = SoundClient(sound_action='/sound_play', blocking=True)
self.client_jp = SoundClient(sound_action='/robotsound_jp', blocking=True)
self.duration = rospy.get_param('~duration', 180.0)
self.threshold = rospy.get_param('~charge_level_threshold', 40.0)
self.step = rospy.get_param('~charge_level_step', 10.0)
Expand All @@ -28,17 +24,13 @@ def __init__(self):
self.is_charging = False

def _speak(self, client, speech_text, lang=None):
client.wait_for_server(timeout=rospy.Duration(1.0))
sound_goal = SoundRequestGoal()
sound_goal.sound_request.sound = -3
sound_goal.sound_request.command = 1
sound_goal.sound_request.volume = self.volume
client.actionclient.wait_for_server(timeout=rospy.Duration(1.0))
if lang is not None:
sound_goal.sound_request.arg2 = lang
sound_goal.sound_request.arg = speech_text
client.send_goal(sound_goal)
client.wait_for_result()
return client.get_result()
client.say(speech_text, voice=lang, volume=self.volume, replace=False)
else:
client.say(speech_text, volume=self.volume, replace=False)
client.actionclient.wait_for_result()
return client.actionclient.get_result()

def _warn(self):
if self.charge_level < self.threshold and not self.is_charging:
Expand Down
36 changes: 15 additions & 21 deletions jsk_robot_common/jsk_robot_startup/scripts/boot_sound.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,14 +3,10 @@
# https://www.youtube.com/watch?v=HM-xG0qXaeA&&
# ffmpeg -i R2D2\ all\ Sounds\ -\ Star\ Wars\ free\ sounds.mp4 -ss 48 -t 10 R2D2.wav

import rospy
import time, socket, os
import netifaces as ni
import rospkg
import rospy

from sound_play.libsoundplay import SoundClient
import actionlib
from sound_play.msg import SoundRequestAction

if __name__ == "__main__":
rospy.init_node("boot_sound")
Expand All @@ -19,32 +15,30 @@
else:
wav_file = "/usr/share/sounds/alsa/Front_Center.wav"

sound = SoundClient()
time.sleep(1) # ???
ac = actionlib.SimpleActionClient('sound_play', SoundRequestAction)
ac.wait_for_server()
sound = SoundClient(sound_action='sound_play', blocking=True)
sound.actionclient.wait_for_server()

interfaces = [x for x in ni.interfaces() if x[0:3] in ['eth', 'enp', 'wla', 'wlp'] and
2 in ni.ifaddresses(x).keys()]

interfaces = [x for x in ni.interfaces() if x[0:3] in ['eth', 'enp', 'wla', 'wlp'] and
2 in ni.ifaddresses(x).keys()]
if len(interfaces) > 0 :
# If preferred interface is given, it is placed at the top of the interfaces list
if rospy.has_param("~preferred_interface"):
preferred_interface = rospy.get_param("~preferred_interface")
if preferred_interface in interfaces:
interfaces.remove(preferred_interface)
interfaces.insert(0, preferred_interface)

if len(interfaces) > 0:
ip = ni.ifaddresses(interfaces[0])[2][0]['addr']
else:
ip = None

# play sound
rospy.loginfo("Playing {}".format(wav_file))
sound.playWave(wav_file)
time.sleep(10) # make sure to topic is going out
sound.playWave(wav_file, replace=False)

# notify ip address
ip_text = "My internet address is {}".format(ip)
rospy.loginfo(ip_text)
ip_text = ip_text.replace('.', ', ')
sound.say(ip_text)
time.sleep(1) # make sure to topic is going out





sound.say(ip_text, replace=False)