Skip to content

Commit

Permalink
Add release note for type adaptation (#1686) (#1690)
Browse files Browse the repository at this point in the history
* Add release note for type adaptation

Signed-off-by: Audrow Nash <[email protected]>

* Add examples and demos

Signed-off-by: Audrow Nash <[email protected]>
(cherry picked from commit 41ecc64)

Co-authored-by: Audrow Nash <[email protected]>
  • Loading branch information
mergify[bot] and audrow authored Jun 17, 2021
1 parent 34eebfd commit 1be265e
Showing 1 changed file with 62 additions and 0 deletions.
62 changes: 62 additions & 0 deletions source/Releases/Release-Humble-Hawksbill.rst
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,68 @@ To come.
Changes since the Galactic release
----------------------------------

rclcpp
^^^^^^

Support Type Adaption for Publishers and Subscriptions
""""""""""""""""""""""""""""""""""""""""""""""""""""""

After defining a type adapter, custom data structures can be used directly by publishers and subscribers, which helps to avoid additional work for the programmer and potential sources of errors.
This is especially useful when working with complex data types, such as when converting OpenCV's ``cv::Map`` to ROS's ``sensor_msgs/msg/Image`` type.

Here is an example of a type adapter that converts ``std_msgs::msg::String`` to ``std::string``:

.. code-block:: cpp
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;
}
};
And an example of how the type adapter can be used:

.. code-block:: cpp
using MyAdaptedType = TypeAdapter<std::string, std_msgs::msg::String>;
// Publish a std::string
auto pub = node->create_publisher<MyAdaptedType>(...);
std::string custom_msg = "My std::string"
pub->publish(custom_msg);
// Pass a std::string to a subscription's callback
auto sub = node->create_subscription<MyAdaptedType>(
"topic",
10,
[](const std::string & msg) {...});
To learn more, see the `publisher <https://github.com/ros2/examples/blob/b83b18598b198b4a5ba44f9266c1bb39a393fa17/rclcpp/topics/minimal_publisher/member_function_with_type_adapter.cpp>`_ and `subscription <https://github.com/ros2/examples/blob/b83b18598b198b4a5ba44f9266c1bb39a393fa17/rclcpp/topics/minimal_subscriber/member_function_with_type_adapter.cpp>`_) examples, as well as a more complex `demo <https://github.com/ros2/demos/pull/482>`_.
For more details, see `REP 2007 <https://ros.org/reps/rep-2007.html>`_.

ros2cli
^^^^^^^

Expand Down

0 comments on commit 1be265e

Please sign in to comment.