@@ -27,8 +27,24 @@ FFMPEGPublisher::~FFMPEGPublisher() {}
2727
2828void FFMPEGPublisher::packetReady (const FFMPEGPacketConstPtr & pkt) { (*publishFunction_)(*pkt); }
2929
30+ #if defined(IMAGE_TRANSPORT_API_V1) || defined(IMAGE_TRANSPORT_API_V2)
3031void FFMPEGPublisher::advertiseImpl (
3132 rclcpp::Node * node, const std::string & base_topic, rmw_qos_profile_t custom_qos)
33+ {
34+ auto qos = initialize (node, custom_qos);
35+ FFMPEGPublisherPlugin::advertiseImpl (node, base_topic, qos);
36+ }
37+ #else
38+ void FFMPEGPublisher::advertiseImpl (
39+ rclcpp::Node * node, const std::string & base_topic, rmw_qos_profile_t custom_qos,
40+ rclcpp::PublisherOptions opt)
41+ {
42+ auto qos = initialize (node, custom_qos);
43+ FFMPEGPublisherPlugin::advertiseImpl (node, base_topic, qos, opt);
44+ }
45+ #endif
46+
47+ rmw_qos_profile_t FFMPEGPublisher::initialize (rclcpp::Node * node, rmw_qos_profile_t custom_qos)
3248{
3349 encoder_.setParameters (node);
3450 const std::string ns = " ffmpeg_image_transport." ;
@@ -38,8 +54,7 @@ void FFMPEGPublisher::advertiseImpl(
3854
3955 // bump queue size to 2 * distance between keyframes
4056 custom_qos.depth = std::max (static_cast <int >(custom_qos.depth ), 2 * encoder_.getGOPSize ());
41-
42- FFMPEGPublisherPlugin::advertiseImpl (node, base_topic, custom_qos);
57+ return (custom_qos);
4358}
4459
4560void FFMPEGPublisher::publish (const Image & msg, const PublishFn & publish_fn) const
0 commit comments