Added type adaptation to Image Publisher raw transport #301
Add this suggestion to a batch that can be applied as a single commit.
This suggestion is invalid because no changes were made to the code.
Suggestions cannot be applied while the pull request is closed.
Suggestions cannot be applied while viewing a subset of changes.
Only one suggestion per line can be applied in a batch.
Add this suggestion to a batch that can be applied as a single commit.
Applying suggestions on deleted lines is not supported.
You must change the existing code in this line in order to create a valid suggestion.
Outdated suggestions cannot be applied.
This suggestion has been applied or marked resolved.
Suggestions cannot be applied from pending reviews.
Suggestions cannot be applied on multi-line comments.
Suggestions cannot be applied while the pull request is queued to merge.
Suggestion cannot be applied right now. Please check back later.
As the title suggests, we added type adaptation to the raw transport. To achieve this, there are a couple of modifications that were made:
Plugins don't mesh well with the idea of type-adaptation without knowing the type beforehand. So here the design decision was to collapse the raw publish plugin into an implicit part of the image_tranport publisher.
Since the publisher now needs to be templated for supporting different type-adapted types, a new higher level publisher is needed which is named
PublisherBase
with an alias created for backwards compatibilityusing Publisher = PublisherBase<sensor_msg::mgs::Image>;
Usage:
Type adaptation is only supported on the raw transport. Here is an example of a type for usage in type-adaptation:
And an alias for easier to read code:
using AdaptedType = rclcpp::TypeAdapter<std::string, sensor_msgs::msg::Image>;
We can create a type-adapted publisher with:
std::shared_ptr<PublisherBase<AdaptedType>> publisher; publisher = image_transport::create_type_adapted_publisher<AdaptedType>(node_.get(), "camera/image");
And publish the type-adapted message with:
A subscriber can be used the normal way without type-adaptation:
Or with type-adaptation:
As final notes, this PR takes a backwards compatible approach so that it does not break existing code, but I don't necessarily like the structure. For example, I don't like having 2
create
functions, I would rather have one, but that would break existing implementations as we would need to return a shared pointer (in line with usage of regular publishers). However, I do find it a good starting point for discussion on how to move forward.