Note: This tutorial assumes that you have completed the previous tutorials: A more advanced Publisher and Subscriber.
(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Using Tabpage Handlers (Teleop)

Description: How to use pre-built tabpage handlers in the ROSOSC stack. In particular, the teleoperation tabpage handler.

Tutorial Level: BEGINNER

Up until now, we have just explored the default tabpage handler in the ROSOSC stack. To realize the full potential of the ROSOSC stack, we can begin to use tabpage "handlers" that are included in the stack.

Tabpage Handler

A tabpage handler is a Python class designed to subscribe and publish to ROS topics based on user interaction with the TouchOSC app. Using a handler, you no longer have to interact via the ROS Publisher/Subscriber interface, but can get a direct hook into the workings of the OSC and ROS protocols.

The advantage of this is that you get a plugin architecture for creating and using pre-built handlers that dictate specific behavior of the touchosc_bridge.

Setting up a launch file for Handlers

We are going to build upon the launch files that we have used in the earlier tutorials to show the ease of adding a pre-built handler to your project.

To begin with, let's create a new launch file.

<launch>
    <param name="layout_path" value="$(find teleop_handler)/layouts" />
    <rosparam param="layouts">
        [ "teleop-ipod.touchosc", "teleop-ipad.touchosc" ]
    </rosparam>

    <node pkg="touchosc_bridge" type="touchosc_bridge.py" name="touchosc" >
        <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" />

        <rosparam param="handlers">[teleop]</rosparam>
        <rosparam command="load" file="$(find teleop_handler)/cfg/teleop.yaml"/>
    </node>

    <node pkg="pytouchosc" type="layoutserver_node" name="layoutserver"/>
</launch>

Notice that in addition to our previously specified paramaters, we have added two new ones. The first handlers specifies which handlers that the touchosc_bridge node needs to look for. The second loads a YAML file with configuration parameters for that specific handler. The cfg/teleop.cfg file looks like this.

teleop:
    # Required parameters
    # Package where the handler is located.
    pkg: teleop_handler
    # Python class name of the handler
    class: 'teleoptabpage/TeleopTabpageHandler'
    # Aliases of the 'teleop' tabpage
    tabpage_aliases: [ 'teleop-ipad', 'teleop-ipod' ]

    # Handler-specific parameters
    max_vx: 0.8
    max_vy: 0.8
    max_vw: 0.4
    max_run_vx: 1.2
    max_run_vy: 1.2
    max_run_vw: 1.0
    min_freq: 5

Handler Configuration File

The touchosc_bridge node reads in ROS parameters that are loaded with the rosparam command.

The launch file holds a handlers parameter that lists the configuration subsections for the node to look for. Note how the root configuration directive of the YAML file matches the name of the handler provided in the handlers parameter. This is also the base tabpage name that will be used for the handler.

Each handler must have a few parameters set in order to function properly.

pkg

  • The ROS package where the handler may be found.

class

  • In this example, the TeleopTabpageHandler class is in the teleoptabpage.py file in the teleop_handler/src/teleop_handler directory. While it is not necessary to follow this directory structure exactly, it prevents potential namespace clashes in Python.

tabpage_aliases

  • These are the other names that will be mapped to the same tabpage handler. In this example, two hardware-specific TouchOSC layouts are used, but they both interact with the same tabpage handler.

The other parameters are handler-specific, in this case, they are used to set maximum velocities, and the minimum publish frequency on /cmd_vel

Starting the Node

Once you have created the launch and YAML files, you can simply start the node with roslaunch

roslaunch rososc_tutorials teleop.launch

An interesting thing to note. If you have the layout already loaded and open, the XY pad and rotary knob will center when the node starts up. This is because the touchosc_bridge provides hooks for tabpage handler creators to "reset" a page to some default values when the node comes up.

Try interacting a bit with the teleop node. Some things to note:

  • To assume control, press the control button. This will lock out all other clients connected to ROS, and display the name of the current master on all devices.
  • When you navigate away from the teleop tabpage or close the app, control is lost on your device, /cmd_vel is set to zero.
  • If you have multiple clients connected to ROS, and once ROS recognizes that all clients are active (you have to switch to another tabpage and back, a limitation), then control movements on one display are synced to all others
  • Use rostopic echo /cmd_vel to display Published velocities.

  • Removing your finger from the screen acts as a dead-man. This utilities the Z messages sent by the controls.

More Fun

So, watching numbers come out on a console is fun and all, but let's do something that you really want to do: bang around the Willow Garage office using a PR2 driven by an iPad.

Provided you have all of the PR2 and Gazebo packages installed:

<launch>
    <param name="layout_path" value="$(find teleop_handler)/layouts" />
    <rosparam param="layouts">
        [ "teleop-ipod.touchosc", "teleop-ipad.touchosc" ]
    </rosparam>

    <node pkg="touchosc_bridge" type="touchosc_bridge.py" name="touchosc" >
        <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" />

        <rosparam param="handlers">[teleop]</rosparam>
        <rosparam command="load" file="$(find teleop_handler)/cfg/teleop.yaml"/>
        <remap from="cmd_vel" to="base_controller/command" />
    </node>

    <node pkg="pytouchosc" type="layoutserver_node" name="layoutserver"/>

    <include file="$(find pr2_gazebo)/pr2_wg_world.launch"/>
</launch>

Or simply run:

roslaunch rososc_tutorials teleoppr2.launch

And have fun!

Wiki: rososc_tutorials/Tutorials/Using Tabpage Handlers (last edited 2011-11-06 11:41:17 by MichaelCarroll)