Note: This tutorial assumes that you have completed the previous tutorials: Using the Default Handler.

A More Advanced Publisher/Subscriber

Description: A tutorial to show how to change control values via ROS Publishers and Subscribers

Tutorial Level: INTERMEDIATE

Next Tutorial: rososc_tutorials/Tutorials/Using Tabpage Handlers

For this tutorial, we will be creating a ROS Node to Publish and Subscribe to TouchOSC control topics.

Here's a YouTube video of the finished product.

Creating a Layout

To begin with, let's create a layout with a multifader taking up the entire screen. Set the number of faders to 50 for the iPad, and 30 for the iPod. Make the tabpage name 1 and the control name multifader. Additionally, make sure that the minimum is set to -1 and the maximum +1.

If you are short on time, these layouts are included in the layouts directory of the rososc_tutorials stack.

The Code

For this example, we are going to read the y-axis acceleration off of the iOS device and "plot" it to the multifader control.

To accomplish this, we will use a ROS Subscriber on the /touchosc/accel topic, and a ROS Publisher on the /touchosc/1/multifader topic. Additionally, we will create a circular buffer from some example code on the internet (Credit given!).

You can adjust the length of the RingBuffer to fit your layout.

   1 #!/usr/bin/env python
   2 
   3 import roslib; roslib.load_manifest('rososc_tutorials')
   4 import rospy
   5 
   6 from sensor_msgs.msg import Imu
   7 from touchosc_msgs.msg import MultiFader
   8 
   9 # Ring Buffer from:
  10 # http://www.saltycrane.com/blog/2007/11/python-circular-buffer/
  11 class RingBuffer:
  12     def __init__(self, size):
  13         self.data = [0.0 for i in xrange(size)]
  14 
  15     def append(self, x):
  16         self.data.pop(0)
  17         self.data.append(x)
  18 
  19     def get(self):
  20         return self.data
  21 
  22 class PubSub(object):
  23     def __init__(self):
  24         rospy.init_node('pubsub')
  25 
  26         self.accel_sub = rospy.Subscriber('/touchosc/accel',
  27                                           Imu,self.imu_cb)
  28         self.fader_pub = rospy.Publisher('/touchosc/1/multifader',
  29                                          MultiFader)
  30         self.ringBuffer = RingBuffer(50)
  31 
  32     def imu_cb(self, msg):
  33         # Scale the data by 20, good range for gravity.
  34         self.ringBuffer.append(float(msg.linear_acceleration.y)/20)
  35         newMsg = MultiFader()
  36         newMsg.values = self.ringBuffer.data
  37         self.fader_pub.publish(newMsg)
  38 
  39 if __name__ == '__main__':
  40     try:
  41         a = PubSub()
  42         rospy.spin()
  43     except rospy.ROSInterruptException: pass

Running the Example

Create a launch file that can launch your newly-created node along with the rest of touchosc_bridge

<launch>
    <param name="layout_file" value="$(find rososc_tutorials)/layouts/slider-ipad.touchosc" />

    <node pkg="touchosc_bridge" type="touchosc_bridge.py" name="touchosc" output="screen">
        <param name="osc_name" value="ROS OSC Default" />
        <param name="port" value="9000"/>
        <param name="print_fallback" value="True" />
        <param name="load_default" value="True" />
        <param name="publish_accel" value="True" />
        <param name="publish_diag" value="True" />
        <param name="vibrate" value="True" />
        <param name="tabpage_sub" value="True" />
    </node>

    <node pkg="pytouchosc" type="layoutserver_node" name="layoutserver"/>
    <node pkg="rososc_tutorials" type="accelpub.py" name="accelpub"/>
</launch>

And then start the program with:

roslaunch rososc_tutorials pubsub.launch

Action Shots

Now, impress your roommates and coworkers by displaying acceleration data on the screen of your iPad with ROS!

Accel Data on iPad

Wiki: rososc_tutorials/Tutorials/A more advanced Publisher and Subscriber (last edited 2011-11-06 23:58:05 by MichaelCarroll)