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
Original file line number Diff line number Diff line change
Expand Up @@ -89,8 +89,6 @@ class ImagePublisher {
std::shared_ptr<dai::node::VideoEncoder> createEncoder(std::shared_ptr<dai::Pipeline> pipeline, const utils::VideoEncoderConfig& encoderConfig);

private:
bool detectSubscription(const rclcpp::Publisher<sensor_msgs::msg::Image>::SharedPtr& pub,
const rclcpp::Publisher<sensor_msgs::msg::CameraInfo>::SharedPtr& infoPub);
std::shared_ptr<rclcpp::Node> node;
utils::VideoEncoderConfig encConfig;
utils::ImgPublisherConfig pubConfig;
Expand All @@ -100,7 +98,6 @@ class ImagePublisher {
std::shared_ptr<dai::node::XLinkOut> xout;
std::shared_ptr<dai::node::VideoEncoder> encoder;
std::function<void(dai::Node::Input in)> linkCB;
rclcpp::Publisher<sensor_msgs::msg::Image>::SharedPtr imgPub;
rclcpp::Publisher<sensor_msgs::msg::CameraInfo>::SharedPtr infoPub;
rclcpp::Publisher<ffmpeg_image_transport_msgs::msg::FFMPEGPacket>::SharedPtr ffmpegPub;
rclcpp::Publisher<sensor_msgs::msg::CompressedImage>::SharedPtr compressedImgPub;
Expand Down
17 changes: 2 additions & 15 deletions depthai_ros_driver/src/dai_nodes/sensors/img_pub.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,10 +70,6 @@ void ImagePublisher::setup(std::shared_ptr<dai::Device> device, const utils::Img
}
infoPub =
node->create_publisher<sensor_msgs::msg::CameraInfo>(pubConfig.topicName + pubConfig.infoSuffix + "/camera_info", rclcpp::QoS(10), pubOptions);
} else if(ipcEnabled) {
imgPub = node->create_publisher<sensor_msgs::msg::Image>(pubConfig.topicName + pubConfig.topicSuffix, rclcpp::QoS(10), pubOptions);
infoPub =
node->create_publisher<sensor_msgs::msg::CameraInfo>(pubConfig.topicName + pubConfig.infoSuffix + "/camera_info", rclcpp::QoS(10), pubOptions);
} else {
imgPubIT = image_transport::create_camera_publisher(node.get(), pubConfig.topicName + pubConfig.topicSuffix);
}
Expand Down Expand Up @@ -201,11 +197,8 @@ void ImagePublisher::publish(std::shared_ptr<Image> img) {
}
infoPub->publish(std::move(img->info));
} else {
if(ipcEnabled && (!pubConfig.lazyPub || detectSubscription(imgPub, infoPub))) {
imgPub->publish(std::move(img->image));
infoPub->publish(std::move(img->info));
} else {
if(!pubConfig.lazyPub || imgPubIT.getNumSubscribers() > 0) imgPubIT.publish(*img->image, *img->info);
if(!pubConfig.lazyPub || imgPubIT.getNumSubscribers() > 0) {
imgPubIT.publish(*img->image, *img->info);
}
}
}
Expand All @@ -229,12 +222,6 @@ void ImagePublisher::publish(const std::shared_ptr<dai::ADatatype>& data) {
publish(img);
}
}

bool ImagePublisher::detectSubscription(const rclcpp::Publisher<sensor_msgs::msg::Image>::SharedPtr& pub,
const rclcpp::Publisher<sensor_msgs::msg::CameraInfo>::SharedPtr& infoPub) {
return (pub->get_subscription_count() > 0 || pub->get_intra_process_subscription_count() > 0 || infoPub->get_subscription_count() > 0
|| infoPub->get_intra_process_subscription_count() > 0);
}
} // namespace sensor_helpers
} // namespace dai_nodes
} // namespace depthai_ros_driver
Loading