.. _program_listing_file__tmp_ws_src_depthai-ros_depthai_bridge_include_depthai_bridge_ImageConverter.hpp: Program Listing for File ImageConverter.hpp =========================================== |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/depthai-ros/depthai_bridge/include/depthai_bridge/ImageConverter.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp #pragma once #include #include #include #include #include #include "cv_bridge/cv_bridge.h" #include "depthai-shared/common/CameraBoardSocket.hpp" #include "depthai-shared/common/Point2f.hpp" #include "depthai/device/CalibrationHandler.hpp" #include "depthai/pipeline/datatype/ImgFrame.hpp" #include "rclcpp/time.hpp" #include "sensor_msgs/msg/camera_info.hpp" #include "sensor_msgs/msg/image.hpp" #include "std_msgs/msg/header.hpp" namespace dai { namespace ros { namespace StdMsgs = std_msgs::msg; namespace ImageMsgs = sensor_msgs::msg; using ImagePtr = ImageMsgs::Image::SharedPtr; using TimePoint = std::chrono::time_point; class ImageConverter { public: // ImageConverter() = default; ImageConverter(const std::string frameName, bool interleaved, bool getBaseDeviceTimestamp = false); ~ImageConverter(); ImageConverter(bool interleaved, bool getBaseDeviceTimestamp = false); void updateRosBaseTime(); void setUpdateRosBaseTimeOnToRosMsg(bool update = true) { _updateRosBaseTimeOnToRosMsg = update; } void convertFromBitstream(dai::RawImgFrame::Type srcType); void addExposureOffset(dai::CameraExposureOffset& offset); void convertDispToDepth(double baseline); void reverseStereoSocketOrder(); void setAlphaScaling(double alphaScalingFactor = 0.0); void toRosMsg(std::shared_ptr inData, std::deque& outImageMsgs); ImageMsgs::Image toRosMsgRawPtr(std::shared_ptr inData, const sensor_msgs::msg::CameraInfo& info = sensor_msgs::msg::CameraInfo()); ImagePtr toRosMsgPtr(std::shared_ptr inData); void toDaiMsg(const ImageMsgs::Image& inMsg, dai::ImgFrame& outData); cv::Mat rosMsgtoCvMat(ImageMsgs::Image& inMsg); ImageMsgs::CameraInfo calibrationToCameraInfo(dai::CalibrationHandler calibHandler, dai::CameraBoardSocket cameraId, int width = -1, int height = -1, Point2f topLeftPixelId = Point2f(), Point2f bottomRightPixelId = Point2f()); private: static std::unordered_map encodingEnumMap; static std::unordered_map planarEncodingEnumMap; // dai::RawImgFrame::Type _srcType; bool _daiInterleaved; // bool c const std::string _frameName = ""; void planarToInterleaved(const std::vector& srcData, std::vector& destData, int w, int h, int numPlanes, int bpp); void interleavedToPlanar(const std::vector& srcData, std::vector& destData, int w, int h, int numPlanes, int bpp); std::chrono::time_point _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}; dai::RawImgFrame::Type _srcType; bool _fromBitstream = false; bool _convertDispToDepth = false; bool _addExpOffset = false; bool _alphaScalingEnabled = false; dai::CameraExposureOffset _expOffset; bool _reverseStereoSocketOrder = false; double _baseline; double _alphaScalingFactor = 0.0; }; } // namespace ros namespace rosBridge = ros; } // namespace dai