Migration guide

For ROS Hydro Medusa, these packages have been changed and provide some form of migration notes or tutorials for users which depend on these packages:

Gazebo

As of Gazebo 1.9 and ROS Hydro, Gazebo no longer has any direct ROS dependencies and is now installed as an Ubuntu stand-alone package. Historically using Gazebo with ROS required a specific version of Gazebo be built with the legacy 'simulator_gazebo' stack.

To achieve ROS integration with stand-alone Gazebo, a new set of ROS packages named 'gazebo_ros_pkgs' has been created to provide wrappers around the stand-alone Gazebo. They provide the necessary interfaces to simulate a robot in Gazebo using ROS messages, services and dynamic reconfigure.

See Gazebo-ROS Overview and Migration Guide

PCL

In Hydro pcl has been upgraded to version 1.7.0, where one of the largest changes for ROS users is that pcl has removed any dependency on ROS message types. What this means is the pcl has created a set of classes which are almost identical to the corresponding ROS messages, in order to minimize API breakage for pcl users. For ROS users, when ever you previously passed a ROS message, like sensor_msgs::PointCloud2, into a pcl::* function you will now have to convert that to the pcl::* equivalent class. In the case of sensors_msgs::PointCloud2, the pcl::* equivalent is pcl::PCLPointCloud2. To help with converting between these types there is a new package called pcl_conversions:

pcl_conversions

This package provides two main things, first it provides a set of overloaded functions fromPCL and toPCL, which provide conversions between ROS message types and the PCL equivalents. In addition to those functions, which incur a copy of the data when converting, for some types there are destructive move functions, named moveFromPCL and moveToPCL. These functions will call std::vector::swap on the potentially large data fields which gives much better performance than copying, but at the cost of replacing the source object's data with the destination's which is often empty.

There is a version of pcl_conversions in Groovy now as well, which provides stubs for the aforementioned conversion functions. This is done so that users with code bases which support both Groovy and Hydro can depend on pcl_conversions and call the same [move]to/fromPCL functions in Groovy without having to do conditionals.

For instance, this is a common code pattern which will fail in Hydro:

pcl::PointCloud<pcl::PointXYZ> pcl_cloud;
sensor_msgs::PointCloud2 pc2;

pcl_cloud.header = pc2.header;

In Hydro the type of the headers do not match, so you need to modify your code like this:

#include <pcl_conversions/pcl_conversions.h>
...
pcl::PointCloud<pcl::PointXYZ> pcl_cloud;
sensor_msgs::PointCloud2 pc2;

pcl_cloud.header = pcl_conversions::toPCL(pc2.header);

In Hydro this function has this signature:

pcl::PCLHeader pcl_conversions::toPCL(const std_msgs::Header &header);

In Groovy the header types are the same and the pcl::PCLHeader type does not exist, so pcl_conversions provides same function, but with this signature and implementation:

std_msgs::Header pcl_conversions::toPCL(const std_msgs::Header &header) {return header;}

As you can see, this function doesn't really do anything, but this allows you to have one branch which supports both Hydro and Groovy more transparently. Note that moveTo/FromPCL functions are still destructive.

Sometimes when converting to PCL 1.7 a copy conversion is unavoidable, for instance in this code:

#include <pcl_conversions/pcl_conversions.h>
...
void foo(const sensor_msgs::PointCloud2 &pc)
{
  pcl::PCLPointCloud2 pcl_pc;
  pcl_conversions::toPCL(pc, pcl_pc);
  pcl::SomePCLFunction(pcl_pc);
  ...
}

This will work in Groovy and in Hydro, but invokes unnecessary copy in Groovy, so you can #if around this copy in Groovy like this:

#include <pcl_conversions/pcl_conversions.h>
...
void foo(const sensor_msgs::PointCloud2 &pc)
{
#if PCL_MAJOR_VERSION == 1 && PCL_MINOR_VERSION >= 7
  pcl::PCLPointCloud2 pcl_pc;
  pcl_conversions::toPCL(pc, pcl_pc);
  pcl::SomePCLFunction(pcl_pc);
#else
  pcl::SomePCLFunction(pc);
#endif
  ...
}

The other functionality provided by pcl_conversions are implementations of functions which previously existed in pcl, but that were renamed or the signatures changed. For example, by including #include <pcl_conversions/pcl_conversions.h> you get access to toROSMsg and fromROSMsg for some types. Additionally this package's header defines some custom serializers for some of the new types in pcl, which would allow you to publish them in place of the ROS equivalent message classes.

Also, pcl is no longer packaged by the ROS community as a catkin package, so any packages which directly depend on pcl should instead use the new rosdep rules libpcl-all and libpcl-all-dev and follow the PCL developer's guidelines for using PCL in your CMake. Generally this means that a package.xml will change like this:

https://github.com/ros-perception/pcl_conversions/commit/a868e1a16e442c135f66a9738619d290bc4ee896

And any where you find_package(catkin REQUIRED COMPONENTS ... pcl ...) should be changed to something like this:

find_package(PCL REQUIRED)
...
include_directories(${PCL_INCLUDE_DIRS})
...
target_link_libraries(<YOUR_TARGET> ${PCL_LIBRARIES})

Stage

The previous unary stack stage has now been split into two packages, stage and stage_ros. Previously the stage stack downloaded the Stage simulator, built it, and then built additional ROS wrappers on top of that. Now the stage package is a REP-0136 (http://ros.org/reps/rep-0136.html) compliant third party package, which is just a release of Stage v4.1.1. The ROS specific code and resources, including the stageros ROS node, are now in the stage_ros package.

If you previously depended on and used the stage unary stack then you will need to update you dependency to stage_ros and also update any launch files or other references to stage. For example, you may have had this in a launch file at one point:

<node pkg="stage" name="stageros" type="stageros" args="-g $(find stage)/world/willow-erratic.world"/>

Starting in Hydro this will fail as the stageros node is no longer in the stage package. Instead you need to do this:

<node pkg="stage_ros" name="stageros" type="stageros" args="-g $(find stage_ros)/world/willow-erratic.world"/>

The version of Stage in Hydro will be version v4.1.1, which can be located here:

https://github.com/rtv/Stage

The new stage_ros package is located here:

https://github.com/ros-simulation/stage_ros

This page describes the difference between tf and tf2. For a migration guide, look at the tf2 tutorials

tf and tf2

Since ROS Hydro, tf has been "deprecated" in favor of tf2. tf2 is an iteration on tf providing generally the same feature set more efficiently. As well as adding a few new features.

Major changes

Addition of /tf_static topic

For greater efficiency tf now has a static transform topic "/tf_static" This topic has the same format as "/tf" however it is expected that any transform on this topic can be considered true for all time. Internally any query for a static transform will return true.

It is expected that publishers on "/tf_static" publish using latched topics, the tf2_ros static_transform_publisher does this correctly. Note: avoid multiple latched static transform publishers on /tf_static in the same process, because with multiple latched publishers within the same node only one will latch correctly.

ROS Independent Core

The core functionality has been separated into a core library without any dependencies on ROS communications, enabling it's use in pure libraries. It does use the ROS message datatypes but is otherwise a pure C++ package. This functionality is provided by the BufferCore class.

New Templated API

The main way to interact with tf2 is through the Buffer class. This class includes much of the functionality of tf::Transformer and tf::Listener. The interface to Buffer is templated such that you can work with mixed datatypes. To enable this there is tf2::convert which is a templated conversion function. tf2_kdl, tf2_eigen, tf2_bullet, tf2_geometry_msgs provide the template instanciations which enable conversions between all the named types. To add a new type it simply requires the implementation of toMsg and fromMsg methods.

First class support for python

tf2 continues to use the C++ core library, but with the isolation of the BufferCore class only the very core algorithm is the wrapped C++ class. All communications for the python bindings are done in pure python avoiding many of the corner cases where pytf would have issues.

Similarly, the automatic conversions of datatypes has also be implemented in tf2_py and the new API follows the redesign of the C++ implementation.

Note: As noted in ros_comm bug #169, tf publishers in Python scripts may now act differently over wireless/unreliable network connections than they did previously.

Action Based Query

One of the challenges of using tf is that the Listener must be running before the data arrives which you want to query. Often this leads to small nodes which have a tf::Listener but only use the data occasionally. Instead of requiring every node to have it's own listener there is now a standard action based api which allows remote queries of tf servers. There are client and server implementation in both C++ and Python.

For an example of how to setup an action based buffer_server.

Clients can be written in either Python or C++ The clients implement the same buffer interface as usual methods.

Removal of support for tf_prefix

One feature which has never really worked was the tf_prefix parameter. tf_prefix was an attempt to parallel the namespacing capability of ROS but for tf frame_ids. However, without core support built in the tf_prefix languished and required a significant amount of work for all developers to implement it correctly. Only a small fraction of packages implemented tf_prefix correctly and for tf_prefix to work correctly it requires all packages interacting with the data to be fully implemented. Thus tf_prefix was only useful for very limited use cases.

tf2 does not support tf_prefix. To avoid confusion tf2 asserts that all frame_ids do not start with /. To make this work tf::resolve will still work to join a tf_prefix and a frame_id, but it will no longer support escaping a frame_id which starts with '/'. tf2 will treat all frame_ids as string literals. All pass throughs from tf to tf2 will strip the leading slash.

To support multiple homogeneous tf trees. As multiple master techniques develop for ROS it is expected that there will be tools developed which will expose subsets of tf data onto foreign masters.

tf_prefix backwards compatibility

So it should keep working in the cases where tf_prefix was previously used.

The basic premise of the migration is that people used to refer to "my_frame" which was resolved to "/my_frame" or "/my_prefix/my_frame" if the prefix was present

In tf2 whatever string you pass in is your frame_id. So "my_frame" is simply "my_frame" and "/my_frame" would be a different frame_id. To avoid silent failures tf2 does not accept frame_ids starting with "/" with an tf2::InvalidArgument exception.

Anyone using the tf::Transformer interface will have the "/" stripped from the frame_id before it is passed to tf2 under the hood.

To maintain backwards compatability with usages of tf_prefix, tf::resolve has been modified to always return frame_ids without a leading slash, but still does the prefixing. So tf::resolve "/map" resolves to "map" or "my_prefix/map" if a tf_prefix is set. This has the consequence that if you call tf::resolve multiple times it will get multiply prefixed. However calling tf::resolve multiple times is not known to be used in code and is not expected practice.

All communication on the wire is done by tf2 and the messages will be without the slash.

The longer term solution to replace tf_prefix is to provide methods for selectively republishing tf transforms, likely with a prefix from one robot to another, probably between masters as well. And at the same time rewriting any frame_ids transferred between the robots to have the prefixed frame_id. The development time for these tools unfortunately has not been found yet.

General Backwards compatibility

As tf2 is a major change the tf API has been maintained in its current form. Since tf2 has a superset of the tf features with a subset of the dependencies the tf implementation has been removed and replaced with calls to tf2 under the hood. This will mean that all users will be compatible with tf2. It is recommended for new work to use tf2 directly as it has a cleaner interface. However tf will continue to be supported for through at least J Turtle.

PR2

The core PR2 packages have been converted to catkin and moved to github.

RQT PR2 Dashboard

The PR2 dashboard has been ported from the old rx tools to the new RQT tools. The new PR2 dashboard can be run with:

rosrun rqt_pr2_dashboard rqt_pr2_dashboard

pr2_etherCAT => pr2_ethercat

Due to naming restrictions, pr2_etherCAT is now pr2_ethercat. This affects everything: package names, node names and topic names.

Topics

  • pr2_etherCAT/motors_halted is deprecated in favor of pr2_ethercat/motors_halted. The old topic name will exist in Hydro for compatibility with old version of the dashboard.

Services

  • /pr2_etherCAT/* services are now /pr2_ethercat/*. The old services may exist in Hydro and will be removed in a future release.

    • /pr2_ethercat/halt_motors

    • /pr2_ethercat/publish_trace

    • /pr2_ethercat/reset_motors

pr2_mechanism_model

pr2_mechanism_model has been updated for the new pluginlib; as a result, pr2_mechanism_model::Robot::getTransmission() now returns a boost::shared_ptr<Transmission> instead of a Transmission*

Controllers and RPath

Controllers should use RPath when linking to other dynamic libraries, since the realtime loop often does not have access to the LD_LIBRARY_PATH variable. This can be done with the pr2_enable_rpath() CMake function from pr2_hardware_interface (also available transitively through pr2_controller_interface, pr2_mechanism_model and ethercat_hardware).

For example:

find_package(catkin REQUIRED COMPONENTS pr2_controller_interface)
...
add_library(${PROJECT_NAME} ... )
pr2_enable_rpath(${PROJECT_NAME})

Arm Navigation

pr2_arm_navigation is no longer maintained, and there are no plans to release it into Hydro. Please use MoveIt instead.

Web interface

The web_interface stack is no longer maintained, and there are no plans to release it into Hydro. This means that the pr2_web_apps stack/package will not be moved forward into Hydro.

Kinematics

  • pr2_kinematics has been updated and re-based off of MoveIt! libraries and headers.

  • kinematics_msgs has been deprecated and its messages can be found instead inside the moveit_msgs package. http://wiki.ros.org/moin_static197/applets/FCKeditor/editor/skins/silver/images/toolbar.buttonarrow.gif

  • pr2_arm_kinematics_constraint_aware has been deprecated and is now obsolete due to non-use and no maintenance on its dependencies.

Package Location

The repositories for the code of the PR2 have slowly been collected and are moving to Github. At this time, the Non-ROS Debian source code future location is undetermined, but is residing at https://code.ros.org/trac/pr2debs/

Turtlebot

A few things changed from groovy to hydro.

Major Changes

Gazebo

Finally, simulations for kobuki and turtlebot. Thanks to the gazebo team and Marcus for resolving all of the tweaks and fiddles to get gazebo re-integrated with ros and turtlebot after all the DARPA changes.

Rocon App Platform

The old unsupported app platform has made way for the rocon app platform. At the moment, you shouldn't notice too many differences to the way it allowed you to work with android. The only really notable difference is that it uses a private/public master pair so that robot-android app pairing is properly sandboxed. Many of the other changes are under the hood, with the hope of being able to enable multi-turtlebot easily in the near future. Tutorials start with the app manager.

Android

Part of the overhaul for the app platform was to straighten out the android development environment so that it is just a matter of opening android studio and clicking to start your android app for pairing with the turtlebot. To do this, we've made some sweeping changes to the development environment - google's new android studio and android gradle plugin, aar's, a ros maven repository and rosjava debs. You can get started browsing the rosjava and android pages, and then go to town on the android turtlebot app tutorials.

Catkin

Absolutely everything is now catkinized.

Minor Changes

Kobuki C++ vs Kobuki Ros

Kobuki driver code is now split between two stacks - kobuki_core and kobuki. This dumps the pure c++ code into one stack and ros code into another which makes it easier for various exotic compiles.

Kobuki PID Configuration

Kobuki has a new 'experimental' firmware release that supports configuration of the robot's internal PID settings.

3d Sensing

Not much different here except that it now uses the improved openni_launch arg configurations rather than hacking our own openni_launch equivalent.

The costmap_2d package now features support for plugins which define "layers" of the costmap. (Thanks to David Lu!! for this new feature!) This changes the format of the (big) set of ros-params needed by the Costmap2DROS class, but backwards compatibility has been preserved for the most part by a function to translate the old parameter layout into the new.

The new Costmap2DROS wants a parameter called "plugins" which is an ordered list of plugin name/type pairs, like so:

local_costmap:
  # ... some other parameters for local_costmap ...
  plugins:
   - {name: static_map, type: "costmap_2d::StaticLayer"}
   - {name: obstacles,  type: "costmap_2d::VoxelLayer"}
   - {name: inflater,   type: "costmap_2d::InflationLayer"}

In this example the plugins get loaded into the local costmap (hence the namespace). The "plugins" parameter has to be inside the corresponding costmap namespace. For global_costmap it works accordingly. (See also: http://answers.ros.org/question/83031/move_base-and-costmap_layers/)

If the "plugins" parameter is not found, Costmap2DROS goes into backward-compatibility mode and creates and configures a set of plugins which should mimic the old version's behavior. If you find something where the new costmap in compatibility mode behaves differently from the old one, please submit a bug.

Backwards-compatibility mode is indicated by the message:

Loading from pre-hydro parameter style

One behavior which we know is different and which there is currently no compatibility mode for, is that static maps are not overwritten by new data. This means that if a door was closed when you made a map, then you open the door, the costmap will continue to show the door as closed. This has been a benefit for us, since we have had trouble with the robot planning paths through walls where stray sensor readings previously sometimes opened holes which should not have been there. If this is a big problem, a new layer plugin can be written which mimics the old behavior.

The big benefit of the layered scheme is it allows for custom cost functions to be written for special situations.

Regarding visualization in rviz: In Hydro costmaps are published as Map (in Groovy they were GridCells).

hokuyo_node

use_rep_117 parameter no longer supported.

urg_node available for ethernet and multi-echo hokuyos.

Rosserial

The rosserial meta-package (rosserial_python, rosserial_arduino, etc.) have been updated in hydro with a wire-level protocol change. Robustness is improved by check-summing the length field, but it requires that firmware for Arduino and any other devices that communicate with rosserial_python be upgraded by reloading with a build based on the hydro version of ros_lib. Firmware loads built from pre-hydro versions of ros_lib won't work, and will give a (hopefully informative) error message.

sicktoolbox_wrapper

sicktoolbox updated to latest version, forked, and catkinized

use_rep_117 parameter no longer supported.

TinyXML

With the conversion to Catkin, a new method for including the TinyXML XML parser is required. See the TinyXML Documentation.

Xacro

<include> tags have been deprecated. Use <xacro:include> instead.

Wiki: hydro/Migration (last edited 2015-05-08 16:00:59 by Kamiccolo)