Usage

To set up communication between RTT and ROS:

Generate the RTT typekit

You need to generate an Orocos typekit for the ROS messages you want to use. Here is the option you have to use an existing typekit, or to generate yours :

  • rtt_ros_integration_std_msgs is such a typekit for std_msgs - other typekits for the most commonly used ROS messages are included as well.

  • other typekits can be generated using the rtt_create_msgs script, available in rtt_ros_integration. Lets say you have a ROS package named MyPkg in which a custom message is defined. To create the typekit for MyPkg:

rosrun rtt_ros_integration create_rtt_msgs MyPkg

This will create the package rtt_MyPkg with typekits for your custom ROS messages.

Use the typekit in your C++ code

Imagine the Orocos package in which you want to add the message is OrocosPkg, and you want to use the messages MsgName from you MyPkg package.

You have to edit OrocosPkg/manifest.xml to add the following line :

  <depend package="rtt_MyPkg"/>

In doing so, you will depend indirectly on rtt_ros_integration.

In order to use MsgName in your component, include the message headers to your OrocosPkg C++ code :

#include <MyPkg/typekit/MsgName.h>

Then, you may fill in or read out the ROS Message in your components.

Adapt your deployment files

Deploying OROCOS components can be done either using .xml or .ops file formats

.ops deployment script

  • Import the ROS plugin :

import("OrocosPkg")
  • Add a ConnPolicy structure to your RTT deployer configuration for each topic you want to suscribe :

var ConnPolicy cp;
cp.transport = 3; // ROS == 3
cp.name_id = "/topic_name"; // ros topic
  • Link you RTT Components Port to the ConnPolicy structure you just set up:

stream("YourComponentName.YourRTTPortName", cp ) 

.xml deployment script

  • Import the ROS plugin and add a ConnPolicy structure to your RTT deployer configuration

<simple name="Import" type="string"><value>rtt_ros_integration</value></simple>
<struct name="ROSConMsg" type="ConnPolicy">
  <simple name="transport" type="short"><value>3</value></simple><!-- 3 means ROS --/>
  <simple name="name_id" type="string"><value>topic_name</value></simple>
</struct>
  • Link you RTT Components Port to the ConnPolicy structure you just set up:

<struct name="Ports" type="PropertyBag">
  <simple name="YourRTTPortName" type="string"><value> RosConMsg </value></simple>
</struct>

Done, your RTT component can now connects its ports to ROS topics! To test, start a ROS::master, deploy your component and investigate the published nodes with rxgraph

Example

The rtt_ros_integration_example package contains an example RTT component to demonstrate the use of this package.

Wiki: rtt_ros_integration/diamondback (last edited 2015-10-02 07:46:41 by WilliamWoodall)