Go to the documentation of this file.
6 #ifndef ADI_3DTOF_ADTF31XX_FRAME_INFO_H
7 #define ADI_3DTOF_ADTF31XX_FRAME_INFO_H
10 #include <pcl/point_types.h>
35 depth_frame_ =
new unsigned short[image_width * image_height];
36 ab_frame_ =
new unsigned short[image_width * image_height];
37 xyz_frame_ =
new short[image_width * image_height * 3];
38 conf_frame_ =
new unsigned short[image_width * image_height];
int compressed_depth_frame_size_
compressed depth frame size
short * xyz_frame_
xyz frame
unsigned short * getDepthFrame() const
Get the depth image frame.
ADI3DToFADTF31xxFrameInfo(int image_width, int image_height)
Constructor.
int image_height_
Image height.
ros::Time * getFrameTimestampPtr()
Get Frame Timestamp Pointer.
This is the class for adtf31xx sensor frame.
unsigned short * depth_frame_
Depth image.
unsigned short * conf_frame_
conf frame
int image_width_
Image width.
short * getXYZFrame() const
Get point cloud frame.
ros::Time frame_timestamp_
Frame Timestamp.
~ADI3DToFADTF31xxFrameInfo()
Destructor.
unsigned char * compressed_ab_frame_
compressed ab frame
unsigned short * ab_frame_
AB image.
ros::Time getFrameTimestamp() const
Get Frame Timestamp.
int getCompressedABFrameSize() const
Gives compressed AB image size.
void setCompressedABFrameSize(int compressed_ab_frame_size)
Set the Compressed AB Image Size.
int compressed_ab_frame_size_
compressed ab frame size
unsigned char * getCompressedDepthFrame() const
Get Compressed depth image frame.
int getCompressedDepthFrameSize() const
Gives compressed depth image size.
unsigned char * compressed_depth_frame_
compressed depth frame
unsigned short * getConfFrame() const
Get Confidence frame.
ADI3DToFADTF31xxFrameInfo & operator=(const ADI3DToFADTF31xxFrameInfo &rhs)
unsigned short * getABFrame() const
Get the AB image frame.
unsigned char * getCompressedABFrame() const
Get Compressed AB image frame.
void setCompressedDepthFrameSize(int compressed_depth_frame_size)
Set the Compressed depth image size.