SpatialDetectionConverter.hpp
Go to the documentation of this file.
1 #pragma once
2 
4 
5 #include "depthai/depthai.hpp"
6 #ifdef IS_ROS2
7  #include <depthai_ros_msgs/msg/spatial_detection_array.hpp>
8 
9  #include "rclcpp/rclcpp.hpp"
10 #else
11  #include <depthai_ros_msgs/SpatialDetectionArray.h>
12  #include <ros/ros.h>
13 
14  #include <boost/make_shared.hpp>
15  #include <boost/shared_ptr.hpp>
16 #endif
17 
18 namespace dai {
19 
20 namespace ros {
21 
22 #ifdef IS_ROS2
23 namespace SpatialMessages = depthai_ros_msgs::msg;
24 using SpatialDetectionArrayPtr = SpatialMessages::SpatialDetectionArray::SharedPtr;
25 #else
26 namespace SpatialMessages = depthai_ros_msgs;
27 using SpatialDetectionArrayPtr = SpatialMessages::SpatialDetectionArray::Ptr;
28 #endif
30  public:
31  // DetectionConverter() = default;
32  SpatialDetectionConverter(std::string frameName, int width, int height, bool normalized = false);
33 
34  void toRosMsg(std::shared_ptr<dai::SpatialImgDetections> inNetData, std::deque<SpatialMessages::SpatialDetectionArray>& opDetectionMsg);
35 
36  SpatialDetectionArrayPtr toRosMsgPtr(std::shared_ptr<dai::SpatialImgDetections> inNetData);
37 
38  private:
40  const std::string _frameName;
42 };
43 
52 } // namespace ros
53 
54 namespace rosBridge = ros;
55 
56 } // namespace dai
void toRosMsg(std::shared_ptr< dai::SpatialImgDetections > inNetData, std::deque< SpatialMessages::SpatialDetectionArray > &opDetectionMsg)
SpatialDetectionArrayPtr toRosMsgPtr(std::shared_ptr< dai::SpatialImgDetections > inNetData)
SpatialDetectionConverter(std::string frameName, int width, int height, bool normalized=false)
SpatialMessages::SpatialDetectionArray::Ptr SpatialDetectionArrayPtr


depthai_bridge
Author(s): Sachin Guruswamy
autogenerated on Tue May 10 2022 03:01:27