Using ROS 2? Check out the ROS 2 tf2 tutorials.

(!) 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.

Create Data Conversion Package (C++)

Description: This tutorial will teach you how to create the methods required to convert C++ datatypes using the tf2 convert methods.

Tutorial Level: INTERMEDIATE

Background

To use the tf2::convert methods and templated transform methods it is necessary to write a header file which defines the following functions. After including these header files in your compilation unit the template logic will support converting between your supported datatype and any other datatype with the same paired message.

Automatically converted and transformed datatypes must be Stamped datatypes which include the ROS Header with timestamp and frame_id. For messages they must have the std_msgs::Header named header. And the custom datatypes, T must be encapsulated as tf2::Stamped<T>.

Required Methods for Automatic Conversion

For the conversions to work you must define

toMsg and fromMsg with specific prototypes.

Assuming template variables MT the message type, and `DT the datatype.

inline MT toMsg(const DT& in)

inline void fromMsg(const MT& msg, DT& out)

Required Methods for Transforming Custom Datatypes

To support transforming custom datatypes you must provide a template specialization of the method doTransform defined in tf2/convert.h

template <class T>
  void doTransform(const T& data_in, T& data_out, const geometry_msgs::TransformStamped& transform);

For example in tf2_kdl it looks like this:

template <>
inline
  void doTransform(const tf2::Stamped<KDL::Vector>& t_in, tf2::Stamped<KDL::Vector>& t_out, const geometry_msgs::TransformStamped& transform)
  {
    t_out = tf2::Stamped<KDL::Vector>(transformToKDL(transform) * t_in, transform.header.stamp, transform.header.frame_id);
  }

Use in code

With these methods defined you can use tf2::convert to go between a message and any datatype with these methods defined. And using slightly more logic it can actually convert between any two datatypes with a mutual message datatype intermediary.

The other place that this can be leveraged is that the tf2_ros API is entirely templated such that you can pass any supported datatype as an input and ask for any datatype with the above conditions as an output and it will work.

Recommendations for Implementers

This approach has been chosen to allow the core package to remain with as few dependencies as necessary. It is recommended to create standalone packages to support these conversions which have the minimum dependencies of the message package, the package with the definition of the datatype, and if necessary the minimum libraries necessary to implement the transform.

The convention for these packages is tf2_MESSAGE_DATATYPE_PACKAGE_NAME such as tf2_kdl, tf2_eigen, and tf2_bullet. These are also good example implementation packages for reference.

Wiki: tf2/Tutorials/Create Data Conversion Package (C++) (last edited 2022-10-06 16:49:46 by ShaneLoretz)