Class ADI3DToFADTF31xxFrameInfo
Defined in File adi_3dtof_adtf31xx_frame_info.h
Class Documentation
-
class ADI3DToFADTF31xxFrameInfo
This is the class for adtf31xx sensor frame.
Public Functions
-
inline ADI3DToFADTF31xxFrameInfo(int image_width, int image_height)
Constructor.
- Parameters:
image_width – - Image Width
image_height – - Image Height
-
inline unsigned short *getDepthFrame() const
Get the depth image frame.
- Returns:
unsigned short* depth image pointer
-
inline unsigned short *getABFrame() const
Get the AB image frame.
- Returns:
unsigned short* AB image pointer
-
inline unsigned short *getConfFrame() const
Get Confidence frame.
- Returns:
unsigned short* Confidence pointer
-
inline unsigned char *getCompressedDepthFrame() const
Get Compressed depth image frame.
- Returns:
unsigned char* compressed depth image pointer
-
inline unsigned char *getCompressedABFrame() const
Get Compressed AB image frame.
- Returns:
unsigned char* compressed AB image pointer
-
inline unsigned char *getCompressedConfFrame() const
Get Compressed Confidence image frame.
- Returns:
unsigned char* compressed AB image pointer
-
inline rclcpp::Time *getFrameTimestampPtr()
Get Frame Timestamp Pointer.
- Returns:
rclcpp::Time* Frame Timnestamp pointer
-
inline rclcpp::Time getFrameTimestamp() const
Get Frame Timestamp.
- Returns:
rclcpp::Time Frame Timestamp
-
inline int getCompressedDepthFrameSize() const
Gives compressed depth image size.
- Returns:
int size of compressed depth image
-
inline int getCompressedABFrameSize() const
Gives compressed AB image size.
- Returns:
int size of compressed AB image
-
inline int getCompressedConfFrameSize() const
Gives compressed confidence image size.
- Returns:
int size of compressed confidence image
-
inline void setCompressedDepthFrameSize(int compressed_depth_frame_size)
Set the Compressed depth image size.
- Parameters:
compressed_depth_frame_size – size of compressed depth image
-
inline void setCompressedABFrameSize(int compressed_ab_frame_size)
Set the Compressed AB Image Size.
- Parameters:
compressed_ab_frame_size – size of compressed AB image
-
inline void setCompressedConfFrameSize(int compressed_conf_frame_size)
Set the Compressed confidence Image Size.
- Parameters:
compressed_conf_frame_size – size of compressed confidence image
-
inline ADI3DToFADTF31xxFrameInfo &operator=(const ADI3DToFADTF31xxFrameInfo &rhs)
-
inline ADI3DToFADTF31xxFrameInfo(int image_width, int image_height)