.. _program_listing_file__tmp_ws_src_depthai-ros_depthai_ros_driver_include_depthai_ros_driver_dai_nodes_nn_detection.hpp: Program Listing for File detection.hpp ====================================== |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/depthai-ros/depthai_ros_driver/include/depthai_ros_driver/dai_nodes/nn/detection.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp #pragma once #include #include #include #include "camera_info_manager/camera_info_manager.hpp" #include "depthai-shared/common/CameraBoardSocket.hpp" #include "depthai/device/DataQueue.hpp" #include "depthai/device/Device.hpp" #include "depthai/pipeline/Pipeline.hpp" #include "depthai/pipeline/node/DetectionNetwork.hpp" #include "depthai/pipeline/node/ImageManip.hpp" #include "depthai/pipeline/node/XLinkOut.hpp" #include "depthai_bridge/ImageConverter.hpp" #include "depthai_bridge/ImgDetectionConverter.hpp" #include "depthai_ros_driver/dai_nodes/base_node.hpp" #include "depthai_ros_driver/dai_nodes/sensors/sensor_helpers.hpp" #include "depthai_ros_driver/param_handlers/nn_param_handler.hpp" #include "depthai_ros_driver/utils.hpp" #include "image_transport/camera_publisher.hpp" #include "image_transport/image_transport.hpp" #include "rclcpp/node.hpp" namespace depthai_ros_driver { namespace dai_nodes { namespace nn { template class Detection : public BaseNode { public: Detection(const std::string& daiNodeName, rclcpp::Node* node, std::shared_ptr pipeline, const dai::CameraBoardSocket& socket = dai::CameraBoardSocket::CAM_A) : BaseNode(daiNodeName, node, pipeline) { RCLCPP_DEBUG(node->get_logger(), "Creating node %s", daiNodeName.c_str()); setNames(); detectionNode = pipeline->create(); imageManip = pipeline->create(); ph = std::make_unique(node, daiNodeName, socket); ph->declareParams(detectionNode, imageManip); RCLCPP_DEBUG(node->get_logger(), "Node %s created", daiNodeName.c_str()); imageManip->out.link(detectionNode->input); setXinXout(pipeline); } ~Detection() = default; void setupQueues(std::shared_ptr device) override { nnQ = device->getOutputQueue(nnQName, ph->getParam("i_max_q_size"), false); std::string socketName = utils::getSocketName(static_cast(ph->getParam("i_board_socket_id"))); auto tfPrefix = getTFPrefix(socketName); int width; int height; if(ph->getParam("i_disable_resize")) { width = ph->getOtherNodeParam(socketName, "i_preview_width"); height = ph->getOtherNodeParam(socketName, "i_preview_height"); } else { width = imageManip->initialConfig.getResizeConfig().width; height = imageManip->initialConfig.getResizeConfig().height; } detConverter = std::make_unique( tfPrefix + "_camera_optical_frame", width, height, false, ph->getParam("i_get_base_device_timestamp")); detConverter->setUpdateRosBaseTimeOnToRosMsg(ph->getParam("i_update_ros_base_time_on_ros_msg")); rclcpp::PublisherOptions options; options.qos_overriding_options = rclcpp::QosOverridingOptions(); detPub = getROSNode()->template create_publisher("~/" + getName() + "/detections", 10, options); nnQ->addCallback(std::bind(&Detection::detectionCB, this, std::placeholders::_1, std::placeholders::_2)); if(ph->getParam("i_enable_passthrough")) { ptQ = device->getOutputQueue(ptQName, ph->getParam("i_max_q_size"), false); imageConverter = std::make_unique(tfPrefix + "_camera_optical_frame", false); imageConverter->setUpdateRosBaseTimeOnToRosMsg(ph->getParam("i_update_ros_base_time_on_ros_msg")); infoManager = std::make_shared( getROSNode()->create_sub_node(std::string(getROSNode()->get_name()) + "/" + getName()).get(), "/" + getName()); infoManager->setCameraInfo(sensor_helpers::getCalibInfo(getROSNode()->get_logger(), *imageConverter, device, static_cast(ph->getParam("i_board_socket_id")), width, height)); ptPub = image_transport::create_camera_publisher(getROSNode(), "~/" + getName() + "/passthrough/image_raw"); ptQ->addCallback(std::bind(sensor_helpers::basicCameraPub, std::placeholders::_1, std::placeholders::_2, *imageConverter, ptPub, infoManager)); } }; void link(dai::Node::Input in, int /*linkType*/) override { detectionNode->out.link(in); }; dai::Node::Input getInput(int /*linkType*/) override { if(ph->getParam("i_disable_resize")) { return detectionNode->input; } return imageManip->inputImage; }; void setNames() override { nnQName = getName() + "_nn"; ptQName = getName() + "_pt"; }; void setXinXout(std::shared_ptr pipeline) override { xoutNN = pipeline->create(); xoutNN->setStreamName(nnQName); detectionNode->out.link(xoutNN->input); if(ph->getParam("i_enable_passthrough")) { xoutPT = pipeline->create(); xoutPT->setStreamName(ptQName); detectionNode->passthrough.link(xoutPT->input); } }; void closeQueues() override { nnQ->close(); if(ph->getParam("i_enable_passthrough")) { ptQ->close(); } }; void updateParams(const std::vector& params) override { ph->setRuntimeParams(params); }; private: void detectionCB(const std::string& /*name*/, const std::shared_ptr& data) { auto inDet = std::dynamic_pointer_cast(data); std::deque deq; detConverter->toRosMsg(inDet, deq); while(deq.size() > 0) { auto currMsg = deq.front(); detPub->publish(currMsg); deq.pop_front(); } }; std::unique_ptr detConverter; std::vector labelNames; rclcpp::Publisher::SharedPtr detPub; std::unique_ptr imageConverter; image_transport::CameraPublisher ptPub; std::shared_ptr infoManager; std::shared_ptr detectionNode; std::shared_ptr imageManip; std::unique_ptr ph; std::shared_ptr nnQ, ptQ; std::shared_ptr xoutNN, xoutPT; std::string nnQName, ptQName; }; } // namespace nn } // namespace dai_nodes } // namespace depthai_ros_driver