SMACC2
Public Types | List of all members
rclcpp::TypeAdapter< CustomType, ROSMessageType, Enable > Struct Template Reference

Template structure used to adapt custom, user-defined types to ROS types. More...

#include <type_adapter.hpp>

Collaboration diagram for rclcpp::TypeAdapter< CustomType, ROSMessageType, Enable >:
Collaboration graph

Public Types

using is_specialized = std::false_type
 
using custom_type = CustomType
 
using ros_message_type = CustomType
 

Detailed Description

template<typename CustomType, typename ROSMessageType = void, class Enable = void>
struct rclcpp::TypeAdapter< CustomType, ROSMessageType, Enable >

Template structure used to adapt custom, user-defined types to ROS types.

Adapting a custom, user-defined type to a ROS type allows that custom type to be used when publishing and subscribing in ROS.

In order to adapt a custom type to a ROS type, the user must create a template specialization of this structure for the custom type. In that specialization they must:

The convert functions must convert from one type to the other.

For example, here is a theoretical example for adapting std::string to the std_msgs::msg::String ROS message type:

template<>
struct rclcpp::TypeAdapter<std::string, std_msgs::msg::String>
{
  using is_specialized = std::true_type;
  using custom_type = std::string;
  using ros_message_type = std_msgs::msg::String;

  static
  void
  convert_to_ros_message(
    const custom_type & source,
    ros_message_type & destination)
  {
    destination.data = source;
  }

  static
  void
  convert_to_custom(
    const ros_message_type & source,
    custom_type & destination)
  {
    destination = source.data;
  }
};

The adapter can then be used when creating a publisher or subscription, e.g.:

using MyAdaptedType = TypeAdapter<std::string, std_msgs::msg::String>;
auto pub = node->create_publisher<MyAdaptedType>("topic", 10);
auto sub = node->create_subscription<MyAdaptedType>(
  "topic",
  10,
  [](const std::string & msg) {...});

You can also be more declarative by using the adapt_type::as metafunctions, which are a bit less ambiguous to read:

using AdaptedType = rclcpp::adapt_type<std::string>::as<std_msgs::msg::String>;
auto pub = node->create_publisher<AdaptedType>(...);

If you wish, you may associate a custom type with a single ROS message type, allowing you to be a bit more brief when creating entities, e.g.:

// First you must declare the association, this is similar to how you
// would avoid using the namespace in C++ by doing `using std::vector;`.
RCLCPP_USING_CUSTOM_TYPE_AS_ROS_MESSAGE_TYPE(std::string, std_msgs::msg::String);

// Then you can create things with just the custom type, and the ROS
// message type is implied based on the previous statement.
auto pub = node->create_publisher<std::string>(...);

Definition at line 98 of file type_adapter.hpp.

Member Typedef Documentation

◆ custom_type

template<typename CustomType , typename ROSMessageType = void, class Enable = void>
using rclcpp::TypeAdapter< CustomType, ROSMessageType, Enable >::custom_type = CustomType

Definition at line 101 of file type_adapter.hpp.

◆ is_specialized

template<typename CustomType , typename ROSMessageType = void, class Enable = void>
using rclcpp::TypeAdapter< CustomType, ROSMessageType, Enable >::is_specialized = std::false_type

Definition at line 100 of file type_adapter.hpp.

◆ ros_message_type

template<typename CustomType , typename ROSMessageType = void, class Enable = void>
using rclcpp::TypeAdapter< CustomType, ROSMessageType, Enable >::ros_message_type = CustomType

Definition at line 104 of file type_adapter.hpp.


The documentation for this struct was generated from the following file: