Program Listing for File ImgDetectionConverter.hpp
↰ Return to documentation for file (/tmp/ws/src/depthai-ros/depthai_bridge/include/depthai_bridge/ImgDetectionConverter.hpp
)
#pragma once
#include <deque>
#include <memory>
#include <string>
#include <vision_msgs/msg/detection2_d_array.hpp>
#include "depthai/pipeline/datatype/ImgDetections.hpp"
#include "rclcpp/time.hpp"
namespace dai {
namespace ros {
namespace VisionMsgs = vision_msgs::msg;
using Detection2DArrayPtr = VisionMsgs::Detection2DArray::SharedPtr;
class ImgDetectionConverter {
public:
// DetectionConverter() = default;
ImgDetectionConverter(std::string frameName, int width, int height, bool normalized = false, bool getBaseDeviceTimestamp = false);
~ImgDetectionConverter();
void updateRosBaseTime();
void setUpdateRosBaseTimeOnToRosMsg(bool update = true) {
_updateRosBaseTimeOnToRosMsg = update;
}
void toRosMsg(std::shared_ptr<dai::ImgDetections> inNetData, std::deque<VisionMsgs::Detection2DArray>& opDetectionMsgs);
Detection2DArrayPtr toRosMsgPtr(std::shared_ptr<dai::ImgDetections> inNetData);
private:
int _width, _height;
const std::string _frameName;
bool _normalized;
std::chrono::time_point<std::chrono::steady_clock> _steadyBaseTime;
rclcpp::Time _rosBaseTime;
bool _getBaseDeviceTimestamp;
// For handling ROS time shifts and debugging
int64_t _totalNsChange{0};
// Whether to update the ROS base time on each message conversion
bool _updateRosBaseTimeOnToRosMsg{false};
};
} // namespace ros
namespace rosBridge = ros;
} // namespace dai