Skip to content

Commit

Permalink
Merge pull request #1310 from knorth55/pr2-nav-speak
Browse files Browse the repository at this point in the history
  • Loading branch information
k-okada authored Dec 25, 2020
2 parents fd512f2 + 9c405c2 commit 484ebf1
Show file tree
Hide file tree
Showing 3 changed files with 22 additions and 13 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
</rosparam>
</node>

<node pkg="jsk_fetch_startup" name="nav_speak" type="nav_speak.py" respawn="true" >
<node pkg="jsk_robot_startup" name="nav_speak" type="nav_speak.py" respawn="true" >
<rosparam>
lang: japanese
</rosparam>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,5 +40,12 @@
args="$(find jsk_pr2_startup)/jsk_pr2_move_base/look-forward-in-nav.l"
machine="c2" respawn="true"
if="$(arg launch_look_forward)"/>

<!-- speak about move base -->
<node pkg="jsk_robot_startup" name="nav_speak" type="nav_speak.py" respawn="true" >
<rosparam>
lang: japanese
</rosparam>
</node>
</group>
</launch>
Original file line number Diff line number Diff line change
Expand Up @@ -4,10 +4,11 @@
import rospy
import time

from actionlib_msgs.msg import GoalStatus
from move_base_msgs.msg import MoveBaseActionGoal
from move_base_msgs.msg import MoveBaseActionResult
from sound_play.libsoundplay import SoundClient
from sound_play.msg import SoundRequestActionGoal
from move_base_msgs.msg import MoveBaseActionGoal, MoveBaseActionResult
from actionlib_msgs.msg import GoalStatus


def goal_status(status):
Expand All @@ -22,15 +23,21 @@ def goal_status(status):
GoalStatus.RECALLED: 'RECALLED',
GoalStatus.LOST: 'LOST'}[status]

class NavSpeak:

class NavSpeak(object):
def __init__(self):
self.move_base_goal_sub = rospy.Subscriber("/move_base/goal", MoveBaseActionGoal, self.move_base_goal_callback, queue_size = 1)
self.move_base_result_sub = rospy.Subscriber("/move_base/result", MoveBaseActionResult, self.move_base_result_callback, queue_size = 1)
self.move_base_goal_sub = rospy.Subscriber(
"/move_base/goal", MoveBaseActionGoal,
self.move_base_goal_callback, queue_size=1)
self.move_base_result_sub = rospy.Subscriber(
"/move_base/result", MoveBaseActionResult,
self.move_base_result_callback, queue_size=1)
self.sound = SoundClient()
self.lang = "japanese" # speak japanese by default
if rospy.has_param("/nav_speak/lang"):
self.lang = rospy.get_param("/nav_speak/lang")
self.pub = rospy.Publisher('/robotsound_jp/goal', SoundRequestActionGoal, queue_size=1)
self.pub = rospy.Publisher(
'/robotsound_jp/goal', SoundRequestActionGoal, queue_size=1)

def move_base_goal_callback(self, msg):
self.sound.play(2)
Expand All @@ -45,6 +52,7 @@ def move_base_result_callback(self, msg):
sound_goal.goal.sound_request.command = 1
sound_goal.goal.sound_request.volume = 1.0
sound_goal.goal.sound_request.arg2 = "jp"

if msg.status.status == GoalStatus.SUCCEEDED:
self.sound.play(1)
time.sleep(1)
Expand Down Expand Up @@ -75,12 +83,6 @@ def move_base_result_callback(self, msg):
self.sound.say(text)

if __name__ == "__main__":
global sound
rospy.init_node("nav_speak")
n = NavSpeak()
rospy.spin()





0 comments on commit 484ebf1

Please sign in to comment.