Skip to content

Commit

Permalink
use new rclcpp::get_message_type_support_handle() and check in Publisher
Browse files Browse the repository at this point in the history
Signed-off-by: William Woodall <william@osrfoundation.org>
  • Loading branch information
wjwwood committed May 4, 2021
1 parent e7ec97c commit 47dd8cd
Showing 1 changed file with 7 additions and 1 deletion.
8 changes: 7 additions & 1 deletion rclcpp/include/rclcpp/publisher.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,8 @@
#include "rclcpp/allocator/allocator_deleter.hpp"
#include "rclcpp/detail/resolve_use_intra_process.hpp"
#include "rclcpp/experimental/intra_process_manager.hpp"
#include "rclcpp/get_message_type_support_handle.hpp"
#include "rclcpp/is_ros_compatible_type.hpp"
#include "rclcpp/loaned_message.hpp"
#include "rclcpp/macros.hpp"
#include "rclcpp/node_interfaces/node_base_interface.hpp"
Expand Down Expand Up @@ -79,11 +81,15 @@ class Publisher : public PublisherBase
: PublisherBase(
node_base,
topic,
*rosidl_typesupport_cpp::get_message_type_support_handle<MessageT>(),
rclcpp::get_message_type_support_handle<MessageT>(),
options.template to_rcl_publisher_options<MessageT>(qos)),
options_(options),
message_allocator_(new MessageAllocator(*options.get_allocator().get()))
{
static_assert(
rclcpp::is_ros_compatible_type<MessageT>::value,
"given message type is not compatible with ROS and cannot be used with a Publisher");

allocator::set_allocator_for_deleter(&message_deleter_, message_allocator_.get());

if (options_.event_callbacks.deadline_callback) {
Expand Down

0 comments on commit 47dd8cd

Please sign in to comment.