Class ImageConverter

Class Documentation

class ImageConverter

Public Functions

ImageConverter(const std::string frameName, bool interleaved, bool getBaseDeviceTimestamp = false)
~ImageConverter()
ImageConverter(bool interleaved, bool getBaseDeviceTimestamp = false)
void updateRosBaseTime()

Handles cases in which the ROS time shifts forward or backward Should be called at regular intervals or on-change of ROS time, depending on monitoring.

inline void setUpdateRosBaseTimeOnToRosMsg(bool update = true)

Commands the converter to automatically update the ROS base time on message conversion based on variable.

Parameters:

update – bool whether to automatically update the ROS base time on message conversion

void convertFromBitstream(dai::RawImgFrame::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 toRosMsg(std::shared_ptr<dai::ImgFrame> inData, std::deque<ImageMsgs::Image> &outImageMsgs)
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 toDaiMsg(const ImageMsgs::Image &inMsg, dai::ImgFrame &outData)
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, Point2f topLeftPixelId = Point2f(), Point2f bottomRightPixelId = Point2f())