Class PointCloudData

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

Class Documentation

class PointCloudData : public dai::Buffer

PointCloudData message. Carries point cloud data.

Public Functions

PointCloudData()

Construct PointCloudData message.

explicit PointCloudData(std::shared_ptr<RawPointCloudData> ptr)
virtual ~PointCloudData() = default
std::vector<Point3f> &getPoints()
unsigned int getInstanceNum() const

Retrieves instance number

unsigned int getWidth() const

Retrieves the height in pixels - in case of a sparse point cloud, this represents the hight of the frame which was used to generate the point cloud

unsigned int getHeight() const

Retrieves the height in pixels - in case of a sparse point cloud, this represents the hight of the frame which was used to generate the point cloud

float getMinX() const

Retrieves minimal x coordinate in depth units (millimeter by default)

float getMinY() const

Retrieves minimal y coordinate in depth units (millimeter by default)

float getMinZ() const

Retrieves minimal z coordinate in depth units (millimeter by default)

float getMaxX() const

Retrieves maximal x coordinate in depth units (millimeter by default)

float getMaxY() const

Retrieves maximal y coordinate in depth units (millimeter by default)

float getMaxZ() const

Retrieves maximal z coordinate in depth units (millimeter by default)

bool isSparse() const

Retrieves whether point cloud is sparse

PointCloudData &setTimestamp(std::chrono::time_point<std::chrono::steady_clock, std::chrono::steady_clock::duration> timestamp)

Retrieves image timestamp related to dai::Clock::now()

PointCloudData &setTimestampDevice(std::chrono::time_point<std::chrono::steady_clock, std::chrono::steady_clock::duration> timestamp)

Sets image timestamp related to dai::Clock::now()

PointCloudData &setInstanceNum(unsigned int instance)

Instance number relates to the origin of the frame (which camera)

Parameters:

instance – Instance number

PointCloudData &setSequenceNum(int64_t seq)

Specifies sequence number

Parameters:

seq – Sequence number

PointCloudData &setWidth(unsigned int width)

Specifies frame width

Parameters:

width – frame width

PointCloudData &setHeight(unsigned int height)

Specifies frame height

Parameters:

height – frame height

PointCloudData &setSize(unsigned int width, unsigned int height)

Specifies frame size

Parameters:
  • height – frame height

  • width – frame width

PointCloudData &setSize(std::tuple<unsigned int, unsigned int> size)

Specifies frame size

Parameters:

size – frame size

PointCloudData &setMinX(float val)

Specifies minimal x coordinate in depth units (millimeter by default)

Parameters:

val – minimal x coordinate in depth units (millimeter by default)

PointCloudData &setMinY(float val)

Specifies minimal y coordinate in depth units (millimeter by default)

Parameters:

val – minimal y coordinate in depth units (millimeter by default)

PointCloudData &setMinZ(float val)

Specifies minimal z coordinate in depth units (millimeter by default)

Parameters:

val – minimal z coordinate in depth units (millimeter by default)

PointCloudData &setMaxX(float val)

Specifies maximal x coordinate in depth units (millimeter by default)

Parameters:

val – maximal x coordinate in depth units (millimeter by default)

PointCloudData &setMaxY(float val)

Specifies maximal y coordinate in depth units (millimeter by default)

Parameters:

val – maximal y coordinate in depth units (millimeter by default)

PointCloudData &setMaxZ(float val)

Specifies maximal z coordinate in depth units (millimeter by default)

Parameters:

val – maximal z coordinate in depth units (millimeter by default)

template<typename ...T>
inline void getPclData() const
int64_t getSequenceNum() const

Retrieves sequence number

std::chrono::time_point<std::chrono::steady_clock, std::chrono::steady_clock::duration> getTimestamp() const

Retrieves timestamp related to dai::Clock::now()

std::chrono::time_point<std::chrono::steady_clock, std::chrono::steady_clock::duration> getTimestampDevice() const

Retrieves timestamp directly captured from device’s monotonic clock, not synchronized to host time. Used mostly for debugging

template<typename ...T>
struct dependent_false

Public Static Attributes

static constexpr bool value = false