.. _program_listing_file__tmp_ws_src_depthai-ros_depthai_filters_include_depthai_filters_detection2d_overlay.hpp: Program Listing for File detection2d_overlay.hpp ================================================ |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/depthai-ros/depthai_filters/include/depthai_filters/detection2d_overlay.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp #pragma once #include "message_filters/subscriber.h" #include "message_filters/sync_policies/approximate_time.h" #include "message_filters/synchronizer.h" #include "rclcpp/rclcpp.hpp" #include "sensor_msgs/msg/camera_info.hpp" #include "sensor_msgs/msg/image.hpp" #include "vision_msgs/msg/detection2_d_array.hpp" namespace depthai_filters { class Detection2DOverlay : public rclcpp::Node { public: explicit Detection2DOverlay(const rclcpp::NodeOptions& options); void onInit(); void overlayCB(const sensor_msgs::msg::Image::ConstSharedPtr& preview, const vision_msgs::msg::Detection2DArray::ConstSharedPtr& detections); message_filters::Subscriber previewSub; message_filters::Subscriber detSub; typedef message_filters::sync_policies::ApproximateTime syncPolicy; std::unique_ptr> sync; rclcpp::Publisher::SharedPtr overlayPub; std::vector labelMap = {"background", "aeroplane", "bicycle", "bird", "boat", "bottle", "bus", "car", "cat", "chair", "cow", "diningtable", "dog", "horse", "motorbike", "person", "pottedplant", "sheep", "sofa", "train", "tvmonitor"}; }; } // namespace depthai_filters