Class ImageConverter

Inheritance Relationships

Base Type

Class Documentation

class ImageConverter : public depthai_bridge::BaseConverter

Public Functions

ImageConverter(const std::string &frameName, bool interleaved, bool getBaseDeviceTimestamp = false)
~ImageConverter()
void convertFromBitstream(dai::ImgFrame::Type srcType)

Sets converter behavior to convert from bitstream to raw data.

Parameters:

srcType – The type of the bitstream data used for conversion.

void addExposureOffset(dai::CameraExposureOffset &offset)

Sets exposure offset when getting timestamps from the message.

Parameters:

offset – The exposure offset to be added to the timestamp.

void convertDispToDepth(double baseline)

Sets converter behavior to convert from disparity to depth when converting messages from bitstream.

Parameters:

baseline – The baseline of the stereo pair.

void reverseStereoSocketOrder()

Reverses the order of the stereo sockets when creating CameraInfo to calculate Tx component of Projection matrix. By default the right socket is used as the base, calling this function will set left as base.

void setAlphaScaling(double alphaScalingFactor = 0.0)

Sets the alpha scaling factor for the image.

Parameters:

alphaScalingFactor – The alpha scaling factor to be used.

void setFFMPEGEncoding(const std::string &encoding)

Sets the encoding of the image when converting to FFMPEG message. Default is libx264.

Parameters:

encoding – The encoding to be used.

void toRosMsg(std::shared_ptr<dai::EncodedFrame> inData, std::deque<ImageMsgs::Image> &outImageMsgs)
void toRosMsg(std::shared_ptr<dai::ImgFrame> inData, std::deque<ImageMsgs::Image> &outImageMsgs)
ImageMsgs::Image toRosMsgRawPtr(std::shared_ptr<dai::EncodedFrame> inData, const sensor_msgs::msg::CameraInfo &info = sensor_msgs::msg::CameraInfo())
ImageMsgs::Image toRosMsgRawPtr(std::shared_ptr<dai::ImgFrame> inData, const sensor_msgs::msg::CameraInfo &info = sensor_msgs::msg::CameraInfo())
ImagePtr toRosMsgPtr(std::shared_ptr<dai::ImgFrame> inData)
void toRosFFMPEGPacket(std::shared_ptr<dai::EncodedFrame> inData, std::deque<FFMPEGMsgs::FFMPEGPacket> &outImageMsgs)
void toRosCompressedMsg(std::shared_ptr<dai::EncodedFrame> inData, std::deque<ImageMsgs::CompressedImage> &outImageMsgs)
void toDaiMsg(const ImageMsgs::Image &inMsg, dai::ImgFrame &outData)
sensor_msgs::msg::CameraInfo generateCameraInfo(std::shared_ptr<dai::ImgFrame> imgFrame) const
sensor_msgs::msg::CameraInfo generateCameraInfo(std::shared_ptr<dai::EncodedFrame> imgFrame) const
cv::Mat rosMsgtoCvMat(ImageMsgs::Image &inMsg)

TODO(sachin): Add support for ros msg to cv mat since we have some encodings which cv supports but ros doesn’t

ImageMsgs::CameraInfo calibrationToCameraInfo(dai::CalibrationHandler calibHandler, dai::CameraBoardSocket cameraId, int width = -1, int height = -1, dai::Point2f topLeftPixelId = dai::Point2f(), dai::Point2f bottomRightPixelId = dai::Point2f())
void planarToInterleaved(const std::vector<uint8_t> &srcData, std::vector<uint8_t> &destData, int w, int h, int numPlanes, int bpp)
void interleavedToPlanar(const std::vector<uint8_t> &srcData, std::vector<uint8_t> &destData, int w, int h, int numPlanes, int bpp)
inline bool isDaiInterleaved() const
inline bool isFromBitstream() const
inline dai::ImgFrame::Type getSrcType() const
inline bool isDispToDepth() const
inline double getBaseline() const
inline bool isAddExpOffset() const
inline dai::CameraExposureOffset getExpOffset() const
inline bool isReversedStereoSocketOrder() const
inline bool isAlphaScalingEnabled() const
inline double getAlphaScalingFactor() const
inline std::string getFFMPEGEncoding() const