HARK-ROS-IROS2018 Tutorials

 Retrieving HARK sound localization and separation information using Ros and Python.

HARK Is A Program Which Allows Advanced Signal Processing Like Sound Source Localization, Separation, And Acoustic Feature Extraction.
This Tutorial Will Focus On Sound Separation And How To Retrieve Such Information Using ROS And Python. It Will Also Demonstrate How This Information Could Be Useful For robotics by moving Turtlesim to the direction of located sound sources.

 Prerequisite

  • You will need to install the following programs:
  • Other:
    • HARK sound separation network file.
    • Multichannel audio file.
    • Transfer function
    • Desired python interface.
    • Turtlesim

We will offer you with HARK network file, multiple audio files, and a transfer function. Turtlesim comes included when you install install ROS.  Download Link

 Network File Main Sheet

 

  • RosNodeGenerator: Generates a master node.
  • Main_Loop: Appears after you create iterator sheet.

For more details regarding RosNodes please visit:  HARK-ROS Tutorials

 Network File Main_Loop Sheet

  • RosHarkMsgs Publisher: Publishes Hark-Ros messages to specified topics. For more details regarding Hark nodes please visit:  HARK Document

 Network File Test

Now that we have everything that we need, let’s begin by testing our network file.

Please extract and move your network file, audio files, transfer function which are located in a single folder named Hark_Tutorials to any desired destination.

cd ~/Downloads
tar zxvf Hark_Tutorials.tar.gz
mv Hark_Tutorials ~/

Now we will test our Network file.

Run the ROS core.

roscore

Then, in another terminal, execute the test network file.

cd ~/Hark_Tutorials
./Hark_Tutorial.n Deg+000.wav

A pop-up window will appear named Source Location. Once a sound source is located it will be posted on the Source Location screen. In this example using the Deg+000.wav file we found that a sound source was located at 0 degrees.

To visually see this network file using HARK GUI, run the following commands:

cd ~/Hark_Tutorials
cp ./Hark_Tutorial.n /usr/lib/hark-designer/userdata/networks

Then, in another terminal:

hark_designer

For hark2.4.0 + Firefox users please use the following command:

hark_designer f

A new web-browser window will appear. Please click on File. Select Hark_Tutorial.n, click on load next to the x. Please note that executing the network file in the GUI will not work. This is due to the fact that in the constant node, we have specified ARG1, which allows us to choose an input file using a Terminal. If you wish to execute the network file using the GUI please copy all the files contained in the Hark_Tutorials folder to /usr/lib/hark-designer/userdata/networks, double click on the constant node, change the value from subnet_param to string, and change the name from ARG1 to Deg+.wav. Now hit execute.

 HARK-ROS-MSG

We have successfully tested our Network file. Now, let’s find out what nodes are in charge of receiving information sent by HARK.

Let’s begin by moving to our Hark_Tutorials directory and initiating our network file.

cd ~/Hark_Tutorials
while true; do ./Hark_Tutorial.n Tutorial.wav; done

Now let’s run rostopic list to see all available topics.

rostopic list
@ubuntu:~/Hark_Tutorials$ rostopic list
/HarkSource
/rosout
/rosout_agg

As you can see we have a topic named /HarkSource.

Let’s see what type of message this node is receiving.

rostopic info /HarkSource
user@ubuntu:~/Hark_Tutorials$ rostopic list
/HarkSource
/rosout
/rosout_agg
user@ubuntu:~/Hark_Tutorials$ rostopic info /HarkSource 
Type: hark_msgs/HarkSource


Publishers: 

 * /HARK_MASTER_NODE (http://Tutorial:35547/)


Subscribers: None

From this we can see that hark_msgs/HarkSource is used to send messages to /HarkSource topic
Now let us see what this message is composed of by running rosmsg show:

rosmsg show hark_msgs/HarkSource
user@ubuntu:~/Hark_Tutorials$ rosmsg show hark_msgs/HarkSource
std_msgs/Header header
  uint32 seq
  time stamp
  string frame_id
int32 count
int32 exist_src_num
hark_msgs/HarkSourceVal[] src
  int32 id
  float32 power
  float32 x
  float32 and
  float32 from
  float32 azimuth
  float32 elevation

As you can see in the hark_msgs/HarkSource message. hark_msgs/HarkSourceVal[] is a list, consisting of located source information.
From this we know that we can extract source id, x, y, z, azimuth and elevation using hark_msgs/HarkSource message.

Please note:
There are other messages that will be published in the hark_msgs/HarkSource message. Like std_msgs/Header, seq, and time stamp.
In this tutorial we will demonstrate how to receive all the contents inside of hark_msgs/HarkSourceVal[] . But for this tutorial we will only utilize azimuth.

Now, you can close the terminal we used to run the infinite while loop before, and execute:

rostopic echo /HarkSource

If you get a “Cannot load messages … Are your messages built?!” error, remember to source the msgs environment (consider adding the following line to your ~/.bashrc):

source "/opt/ros/kinetic/msgs/setup.bash"

Now let’s use theDeg+000.wav file.

cd ~/Hark_Tutorials
./Hark_Tutorial.n Deg+000.wav

Like we mentioned previously, other messages will be published in hark_msgs/HarkSource,
Not just HarkSourceVal[]. Once ./Hark_Tutorial.n Deg+000.wav has finished executing, go back to the “rostopic echo” terminal and scroll the output up until you see the following.

src: 
  - 
    id: 0
    power: 29.6002502441
    x: 0.995999991894
    and: -0.0869999974966
    from: 0.600000023842
    azimuth: -4.99208068848
    elevation: 30.9690074921

Once HARK has found a source, it will publish all the information of the detected sources, in our case at azimuth -4.992 degrees.

In this segment we learned that the /HarkSource topic receives a hark_msgs/HarkSource message. This message contains information about the sound source localized by HARK like elevation and azimuth.

Now let’s continue the tutorial by learning how to control Turtlesim.

 Turtle Sim Control

In two new Terminals lets launch Turtlesim(Turtle Simulator) and turtle_teleop which allows us to control Turtlesim with our keyboard.

rosrun turtlesim turtlesim_node
rosrun turtlesim turtle_teleop_key

Since we already ran roscore, your environment should look similar to this.

Click on turtle_teleop_key terminal and move the Turtlesim with your arrow keys.

Now, let’s run rostopic list to see the current available rostopics.

rostopic list
user@ubuntu:~$ rostopic list
/rosout
/rosout_agg
/turtle1/cmd_vel
/turtle1/color_sensor
/turtle1/pose

From http://wiki.ros.org/turtlesim we know that /turtle1/cmd_vel topic is in charge of moving the Turtlesim. Let’s see what the /turtle1/cmd_vel is composed with the following command:

rostopic info /turtle1/cmd_vel
user@ubuntu:~$ rostopic info /turtle1/cmd_vel

Type: geometry_msgs/Twist

Publishers: 
 * /teleop_turtle (http://Tutorial:41481/)

Subscribers: 
 * /turtlesim (http://Tutorial:33182/)

Here we can see that teleop is indeed publishing to the /turtle1/cmd_vel using geometry_msgs/Twist ros message.

Let’s see what geometry_msgs/Twist is composed of by running rosmsg show in the same terminal.

rosmsg show geometry_msgs/Twist
user@ubuntu:~$ rosmsg show geometry_msgs/Twist
geometry_msgs/Vector3 linear
  float64 x
  float64 and
  float64 from
geometry_msgs/Vector3 angular
  float64 x
  float64 and
  float64 from

Now let’s see how exactly this message is being used by checking what is being published to the /turtle1/cmd_vel topic.

rostopic echo /turtle1/cmd_vel

Let’s begin by clicking on the turtle_teleop_key Terminal and pressing the forward key.

We can see that by pressing the forward key the teleop publishes Linear x: 2.0 to the /turtle1/cmd_vel topic.

In this segment we learned how to control the Turtlesim and, what message is used to do so.

Let’s take everything we learned from the previous two segments and combine them.

 HARK-ROS and Turtlesim

Let’s begin by opening HarkRosTutorial with your text editor.

#!/usr/bin/env python
import rospy
from hark_msgs.msg import HarkSource
from geometry_msgs.msg import Twist 

def callback(msg):
    for i in msg.src:
        id_, power, x, y, z = i.id, i.power, i.x, i.y, i.z
        azimuth, elevation = i.azimuth, i.elevation

        if azimuth > -10 and azimuth < 10: #Forward
            publish(1.5, 0)
        elif azimuth > -100 and azimuth < -80 : #Right
            publish(1.5, -1.5)
        elif azimuth > 70 and azimuth < 100: #left
            publish(1.5, 1.5)
        elif azimuth > -200 and azimuth < -170: #Back
            publish(-1.5, 0)
        else:
            print 'azimuth not in range:{}'.format(azimuth)

def publish(lin_speed, ang_speed):
    cmd_vel = rospy.Publisher('/turtle1/cmd_vel', Twist, queue_size=10)
    rospy.Rate(10);
    move_cmd = Twist()
    move_cmd.linear.x = lin_speed
    move_cmd.angular.z = ang_speed
    cmd_vel.publish(move_cmd)

def main ():
    rospy.init_node('Hark_Tutorial',anonymous=True)
    rospy.Subscriber("/HarkSource", HarkSource, callback)
    rospy.spin()

if __name__ == '__main__':
    main()

From the previous segments we learned which messages are used to control Turtlesim and what messages are used to receive source information from HARK.
We will begin by importing Ros python, HarkSource message, and Twist message.

#!/usr/bin/env python
import rospy
from hark_msgs.msg import HarkSource
from geometry_msgs.msg import Twist

rospy.init_node initializes our node named Hark_Tutorial.
rospy.Subscriber will subscribe to /HarkSource topic, and will receive HarkSource messages.
rospy.spin() keeps python from exiting until Hark_Tutorial node is stopped.

def main ():
    rospy.init_node('Hark_Tutorial',anonymous=True)
    rospy.Subscriber("/HarkSource", HarkSource, callback)
    rospy.spin()

if __name__ == '__main__':
    main()

Now we will receive all the messages published to /HarkSource topic.

The messages received in the callback can be accessed in the msg.src list.

def callback(msg):
    for i in msg.src:
        id_, power, x, y, z = i.id, i.power, i.x, i.y, i.z
        azimuth, elevation = i.azimuth, i.elevation

Like we saw in the HARK-ROS-MSG section, Deg+000.wav file gave an azimuth of -4.9. We will use different azimuth ranges for each direction. If the azimuth falls in a certain range we will move the Turtlesim accordingly.
publish(lin_speed, ang_speed) sets lin_speed and ang_speed according to the azimuth range.

for i in y:
    id_, power, x, y, z = i.id, i.power, i.x, i.y, i.z
    azimuth, elevation = i.azimuth, i.elevation

    if azimuth > -10 and azimuth < 10: #Forward
        publish(1.5, 0)
    elif azimuth > -100 and azimuth < -80 : #Right
        publish(1.5, -1.5)
    elif azimuth > 70 and azimuth < 100: #left
        publish(1.5, 1.5)
    elif azimuth > -200 and azimuth < -170: #Back
        publish(-1.5, 0)
    else:
        print 'azimuth not in range:{}'.format(azimuth)

rospy.publisher() will publish geometry_msgs/Twist messages to the /turtle1/cmd_vel topic.
move_cmd.linear.x and move_cmd.angular.z choose the direction and speed, like we saw in the Turtlesim Control segment.
Finally, cmd_vel.publish(move_cmd) publishes the message.

def publish(lin_speed, ang_speed):
    cmd_vel = rospy.Publisher('/turtle1/cmd_vel', Twist, queue_size=10)
    rospy.Rate(10);
    move_cmd = Twist()
    move_cmd.linear.x = lin_speed
    move_cmd.angular.z = ang_speed
    cmd_vel.publish(move_cmd)

Let’s test our script. Please close all terminals used so far and open three new terminals.We will run Turtlesim, our python script, and our network file separately.

roscore
rosrun turtlesim turtlesim_node
cd ~/Hark_Tutorials
python HarkRosTutorial.py

Finally all we need to do now, is run our network file.
There are 4 source .wav files. We will use Deg+180.wav file for our next test. When executing the next command, our Turtlesim should move backwards.

cd ~/Hark_Tutorials
./Hark_Tutorial.n Deg+180.wav

If everything went well you should see something like this.

You could now test the other source .wav files to move the Turtlesim as you wish.

In this case we used HARK source localization to manipulate Turtlesim.

We look forward to see you you implement HARK in your projects.

If you would like to have source localization in real time, you can use AudioSteamFromMic instead of AudioSteamFromWave.

For more node information please visit:

For compatible microphones please visit:

If you have any question regarding HARK or this tutorial please visit our support page at:  HARK FORUM

 Visualizing Located Sound Sources.

In this section we will demonstrate how turtlesim can move a place sound source by using  HARK – ROS – MESSAGES.

#! /usr /bin /env python
import rospy
from math import pi
from hark_msgs.msg import HarkSource
from geometry_msgs.msg import Twist
from turtlesim.srv import TeleportAbsolute
from turtlesim.srv import Spawn
from collections import Counter
import std_srvs.srv

spawn = rospy.ServiceProxy ('spawn', Spawn)
max_val_x, max_val_y, min_val_x, min_val_y = 11.08, 11.08, 0, 0
spawn_max_val_x, spawn_max_val_y, spawn_min_val_x, spawn_min_val_y = 10.3, 10.3, 0.7, 0.7
class SpawnSource:
    def __init __ (self):
        self.currentPos_x = 0
        self.currentPos_y = 0
        self.currentPos_theta = 0
        self.name = "karl"
        self.reset = rospy.ServiceProxy ('reset', std_srvs.srv.Empty)
        self.move_theta = rospy.ServiceProxy ('/turtle1 /teleport_absolute', TeleportAbsolute)
    def callback (self, x, y, theta, theta 2):
        if x! = self.currentPos_x or y! = self.currentPos_y or theta! = self.currentPos_theta:
            self.currentPos_x = x 
            self.currentPos_y = y
            self.currentPos_theta = theta
            self.reset ()
            self.move_theta (max_val_x / 2, max_val_y / 2, theta 2)
            spawn (self.currentPos_x, self.currentPos_y, self.currentPos_theta, self.name)

class FindSource:
    def __init __ (self):
        self.Hark = rospy.Subscriber ("/HarkSource", HarkSource, self.callback, queue_size = 1)
        self.Source = SpawnSource ()

    def callback (self, azi):
        y = azi.src
        for i in y:
            azimuth = i.azimuth
            print azimuth
            if azimuth> -10 and azimuth <10: # Forward
                self.Source.callback (spawn_max_val_x, max_val_y / 2, pi, 0)
                print azimuth
                Move (i, 0)
            elif azimuth> -100 and azimuth <-80: # Right
                self.Source.callback (max_val_x / 2, spawn_min_val_y, pi / 2, pi * 1.5)
                Move (i, -90)
            elif azimuth> 70 and azimuth <100: #left
                self.Source.callback (max_val_x / 2, spawn_max_val_y, pi * 1.5, pi / 2)
                Move (i, 90)
            elif azimuth> -200 and azimuth <-170: #Back
                self.Source.callback (spawn_min_val_x, max_val_y / 2, 0, pi)
                Move (i, -180)
            else:
                print 'azimuth not in range: {}'. format (azimuth)

def Move (msg, ref):
    cmd_vel = rospy.Publisher ('/turtle1 /cmd_vel', Twist, queue_size = 1) 
    move_cmd = Twist ()
    speed = 0.8
    move_cmd.linear.x = speed
    move_cmd.angular.z = float (ref - msg.azimuth) / 180 * pi
    cmd_vel.publish (move_cmd)

if __name__ == '__main__':
    rospy.init_node ('Hark_Tutorial', anonymous = False)
    spawn = rospy.ServiceProxy ('spawn', Spawn)
    reset = rospy.ServiceProxy ('reset', std_srvs.srv.Empty)
    reset ()
    test = FindSource ()
    rospy.spin ()

. Max_val_x, Max_val_y Are The Maximum And Minimum Values Of X And Y In Our Turtlesim Window
Spawn_max_val_x, Spawn_max_val_y Are The Maximum And Minimum Values Of Spawn Source Turtle.
SpawnSource Class: Spawns A Turtle That Represents The Direction Of The Sound Source Input To HARK. . Every Time A Different Source Is Located It Will Reset Our Turtlesim And Spawn A New Turtle In The Direction Of The Sound Source
FindSource Class:. Receives Hark-Ros-Messages And Extracts The Azimuth This Tells Us The Direction Of The Located Sound Source. It will relay this information to the SpawnSource class and call the Move function.
Move function: Every time FindSource received a HARK message it will tell the Move function to move the turtle forward.

When this program is initialized it will reset our turtlesim. While also initializing FindSource class.

It is important to note that that Hark does not estimate the distance of located
tutorial, the new turtles representing the sound sources are always spawned at the same distance from the center turtle.

Let us begin by stopping any previous process (if you executed the previous tutorials) and then run roscore and turtlesim in separate terminals.

roscore
rosrun turtlesim turtlesim_node

Let Us Run Now Our Program.
Please Move To The Hark_Tutorials Folder Destination And Run Move_Towards_Source.Py.

cd ~ /Hark_Tutorials
python Move_Towards_Source.py

Now in another terminal run.

cd ~ /Hark_Tutorials
./Hark_Tutorial.n Deg+180.wav

As you can see our turtle will move towards the located sound. In this case HARK located a sound source at 180 degrees.

Let us try with it next with Deg-090.wav

./Hark_Tutorial.n Deg-090.wav

This demonstrates how turtlesim will move towards a located sound source represented by a spawned turtle.
It also helps visualize our azimuth value extracted from HARK-ROS-MESSAGES.

 Hark-Ros and Turtlesim Realistic Example.

In this section we will demonstrate a more realistic scenario. Instead of resetting the turtlesim position at every new sound source, the turtlesim will move towards any located sound sources located by HARK from its last position.

#!/usr/bin/env python
import rospy
from math import pow,atan2,sqrt,pi
from hark_msgs.msg import HarkSource
from geometry_msgs.msg import Twist
from turtlesim.srv import TeleportAbsolute
from turtlesim.srv import Kill
from turtlesim.srv import Spawn
from turtlesim.msg import Pose
import std_srvs.srv

spawn = rospy.ServiceProxy('spawn', Spawn)
kill = rospy.ServiceProxy('kill', Kill)
max_val_x, max_val_y, min_val_x, min_val_y = 11.08, 11.08, 0, 0
spawn_max_val_x, spawn_max_val_y, spawn_min_val_x, spawn_min_val_y = 10.3, 10.3, 0.7, 0.7
class SpawnSource:
    def __init__(self):
        self.currentPos_x = 0
        self.currentPos_y = 0
        self.currentPos_theta = 0
        self.name = "karl"

    def callback(self, x , y , theta):
        if x != self.currentPos_x or y != self.currentPos_y or theta != self.currentPos_theta:
            kill('karl')
            self.currentPos_x = x 
            self.currentPos_y = y
            self.currentPos_theta = theta
            spawn( self.currentPos_x,  self.currentPos_y,  self.currentPos_theta, self.name)

class FindSource:
    def __init__(self):
        self.Hark = rospy.Subscriber("/HarkSource", HarkSource, self.callback, queue_size=1)
        self.Source = SpawnSource()
        self.Move_Turtle = Move_Turtle()

    def callback(self, azi):
        
        y = azi.src
        for i in y:
            azimuth = i.azimuth
            if azimuth > -10 and azimuth < 10:  #Forward
                self.Source.callback(spawn_max_val_x, max_val_y/2, pi)
                self.Move_Turtle.Move(spawn_max_val_x, max_val_y/2)
            elif azimuth > -100 and azimuth < -80: #Right
                self.Source.callback(max_val_x/2, spawn_min_val_y, pi/2)
                self.Move_Turtle.Move(max_val_x/2, spawn_min_val_y)
            elif azimuth > 70 and azimuth < 100: #left
                self.Source.callback(max_val_x/2, spawn_max_val_y, -pi/2)
                self.Move_Turtle.Move(max_val_x/2, spawn_max_val_y)
            elif azimuth > -200 and azimuth < -170: #Back
                self.Source.callback(spawn_min_val_x, max_val_y/2, 0)
                self.Move_Turtle.Move(spawn_min_val_x, max_val_y/2)
            else:
                print 'azimuth not in range:{}'.format(azimuth)

class Move_Turtle:
    def __init__(self):
        self.Hark = rospy.Subscriber('/turtle1/pose', Pose, self.callback, queue_size=10)
        self.Move_x = 0
        self.Move_y = 0
        self.Move_theta = 0
        self.cmd_vel = rospy.Publisher('/turtle1/cmd_vel', Twist, queue_size=10)

    def callback(self, msg):
        self.Move_x = msg.x 
        self.Move_y = msg.y
        self.Move_theta = msg.theta

    def Move(self, x, y,):
        move_cmd = Twist()
        move_cmd.linear.x = .25 * sqrt(pow((x - self.Move_x), 2) + pow((y - self.Move_y), 2))
        move_cmd.angular.z =  2. * (atan2(y - self.Move_y, x - self.Move_x) - self.Move_theta)
        self.cmd_vel.publish(move_cmd)

if __name__ == '__main__':
    rospy.init_node('Hark_Tutorial',anonymous=False)
    spawn = rospy.ServiceProxy('spawn', Spawn)
    reset = rospy.ServiceProxy('reset', std_srvs.srv.Empty)
    reset()
    x = max_val_x/2
    y = max_val_y / 2
    theta = 0 
    name = "karl"
    spawn(x,y,theta,name)
    test = FindSource()
    rospy.spin()

max_val_x, max_val_y are the maximum and minimum values of x and y in our turtlesim window.
spawn_max_val_x, spawn_max_val_y are the maximum and minimum values of spawn source turtle.
SpawnSource class: Spawns a turtle that represents the direction of the sound source input to HARK. It will also delete any previously spawned turtles.
FindSource Class: Receives Hark-Ros-Messages and extracts the azimuth. This tells us the direction of the located sound source. It will relay this information to the SpawnSource class and call the Move_Turtle object methods to move the turtlesim towards the direction of the sound source.

Move_Turtle class: We will calculate the angle in which the turtle should face.
Once it is near the sound source it will begin to slow down.

Again it is important to note that Hark does not estimate the distance of located sound sources.
For the purposes of this tutorial, we gave designated distances to our located sound sources represented by a newly spawned turtle.

When this program is initialized it will reset our turtlesim, spawn a new turtle and initialize the FindSource class.

Please move to the Hark_Tutorials folder destination and run Move_Towards_Source_Realistic.py.

cd ~/Hark_Tutorials
python Move_Towards_Source_Realistic.py

Now in another terminal run.

cd ~/Hark_Tutorials
./Hark_Tutorial.n Deg+000.wav

The turtlesim should move forward towards the located sound source at 0 degrees.

In the same terminal let’s run our network file with Deg+090.wav.

./Hark_Tutorial.n Deg+090.wav

HARK has detected a source at 90 degrees. The turtlesim will turn and move towards the located sound source.

Finally let’s try Deg-090.wav file.

./Hark_Tutorial.n Deg-090.wav

Hark-Ros-Messages, extract its information, and use it to guide turtlesim towards located sound sources.

For more node information please visit:

For compatible microphones please visit:

If you have any question regarding HARK or this tutorial please visit our support page at:  HARK FORUM

Back to Top