ON THIS PAGE

  • RGBDData
  • Usage
  • Reference

RGBDData

RGBDData bundles an aligned color frame and depth frame into a single payload. It is produced by the RGBD node after synchronizing the incoming ImgFrame streams, and can be consumed on the host to render textured point clouds or fuse color and depth for higher-level perception tasks.The message exposes:
  • rgbFrame — the undistorted color image as an ImgFrame;
  • depthFrame — the registered depth map (millimeters by default);
  • Camera calibration and projection helpers for reconstructing 3D coordinates;
  • Convenience methods to iterate fused pixels or export packed RGB-D arrays.

Usage

On the host, fetch RGBDData from the output queue:
Python
1queue = device.getOutputQueue("rgbd", maxSize=2, blocking=False)
2rgbd = queue.get()  # type: dai.RGBDData
3rgb_frame = rgbd.getRgbFrame()
4depth_frame = rgbd.getDepthFrame()

Reference

class

dai::RGBDData

#include RGBDData.hpp
variable
std::map< std::string, std::shared_ptr< ADatatype > > frames
function
RGBDData()
Construct RGBD message.
function
~RGBDData()
function
void setRGBFrame(const std::shared_ptr< ImgFrame > & frame)
function
void setDepthFrame(const std::shared_ptr< ImgFrame > & frame)
function
std::shared_ptr< ImgFrame > getRGBFrame()
function
std::shared_ptr< ImgFrame > getDepthFrame()
function
void serialize(std::vector< std::uint8_t > & metadata, DatatypeEnum & datatype)
function
DEPTHAI_SERIALIZE(RGBDData, frames, Buffer::ts, Buffer::tsDevice, Buffer::sequenceNum)

Need assistance?

Head over to Discussion Forum for technical support or any other questions you might have.