Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
7 changes: 2 additions & 5 deletions src/TopicPublisherROS2/generic_publisher.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,8 @@ class GenericPublisher : public rclcpp::PublisherBase
const rosidl_message_type_support_t& type_support)
// The rclcpp::PublisherBase constructor grew event-callback parameters after Humble (rclcpp 16.x).
#if RCLCPP_VERSION_GTE(17, 0, 0)
: rclcpp::PublisherBase(node_base, topic_name, type_support, rcl_publisher_get_default_options(), callbacks_, true)
: rclcpp::PublisherBase(node_base, topic_name, type_support, rcl_publisher_get_default_options(),
rclcpp::PublisherEventCallbacks{}, true)
#else
: rclcpp::PublisherBase(node_base, topic_name, type_support, rcl_publisher_get_default_options())
#endif
Expand All @@ -57,10 +58,6 @@ class GenericPublisher : public rclcpp::PublisherBase

return std::make_shared<GenericPublisher>(node.get_node_base_interface().get(), topic_name, *type_support);
}

#if RCLCPP_VERSION_GTE(17, 0, 0)
rclcpp::PublisherEventCallbacks callbacks_;
#endif
};

#endif // GENERIC_PUBLISHER_H
17 changes: 8 additions & 9 deletions src/TopicPublisherROS2/publisher_ros2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -111,15 +111,6 @@ void TopicPublisherROS2::setEnabled(bool to_enable)

updatePublishers();

if (!_tf_broadcaster)
{
_tf_broadcaster = std::make_unique<tf2_ros::TransformBroadcaster>(*_node);
}
if (!_tf_static_broadcaster)
{
_tf_static_broadcaster = std::make_unique<tf2_ros::StaticTransformBroadcaster>(*_node);
}

_previous_play_index = std::numeric_limits<int>::max();
}
else
Expand Down Expand Up @@ -293,10 +284,18 @@ void TopicPublisherROS2::broadcastTF(double current_time)
}
if (transforms_ptr == &transforms)
{
if (!_tf_broadcaster)
{
_tf_broadcaster = std::make_shared<tf2_ros::TransformBroadcaster>(*_node);
}
_tf_broadcaster->sendTransform(transforms_vector);
}
else
{
if (!_tf_static_broadcaster)
{
_tf_static_broadcaster = std::make_shared<tf2_ros::StaticTransformBroadcaster>(*_node);
}
_tf_static_broadcaster->sendTransform(transforms_vector);
}
}
Expand Down
Loading