adi_3dtof_adtf31xx_frame_info.h
Go to the documentation of this file.
1 /******************************************************************************
2 Copyright (c), 2023 - Analog Devices Inc. All Rights Reserved.
3 This software is PROPRIETARY & CONFIDENTIAL to Analog Devices, Inc.
4 and its licensors.
5 ******************************************************************************/
6 #ifndef ADI_3DTOF_ADTF31XX_FRAME_INFO_H
7 #define ADI_3DTOF_ADTF31XX_FRAME_INFO_H
8 
9 #include <pcl_ros/point_cloud.h>
10 #include <pcl/point_types.h>
11 #include <cstring>
17 {
18 public:
25  ADI3DToFADTF31xxFrameInfo(int image_width, int image_height)
26  {
27  // Create the node.
28  depth_frame_ = nullptr;
29  ab_frame_ = nullptr;
30  xyz_frame_ = nullptr;
31  conf_frame_ = nullptr;
32  image_width_ = image_width;
33  image_height_ = image_height;
34 
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];
39 
40  // Worst case, RVL compression can take ~1.5x the input data.
41  compressed_depth_frame_ = new unsigned char[3 * image_width * image_height];
42  compressed_ab_frame_ = new unsigned char[3 * image_width * image_height];
46  }
47 
52  {
53  if (depth_frame_ != nullptr)
54  {
55  delete[] depth_frame_;
56  }
57  if (ab_frame_ != nullptr)
58  {
59  delete[] ab_frame_;
60  }
61  if (xyz_frame_ != nullptr)
62  {
63  delete[] xyz_frame_;
64  }
65  if (conf_frame_ != nullptr)
66  {
67  delete[] conf_frame_;
68  }
69  if (compressed_depth_frame_ != nullptr)
70  {
71  delete[] compressed_depth_frame_;
72  }
73  if (compressed_ab_frame_ != nullptr)
74  {
75  delete[] compressed_ab_frame_;
76  }
77  }
78 
84  unsigned short* getDepthFrame() const
85  {
86  return depth_frame_;
87  }
88 
94  unsigned short* getABFrame() const
95  {
96  return ab_frame_;
97  }
98 
104  short* getXYZFrame() const
105  {
106  return xyz_frame_;
107  }
108 
114  unsigned short* getConfFrame() const
115  {
116  return conf_frame_;
117  }
118 
124  unsigned char* getCompressedDepthFrame() const
125  {
127  }
128 
134  unsigned char* getCompressedABFrame() const
135  {
136  return compressed_ab_frame_;
137  }
138 
145  {
146  return &frame_timestamp_;
147  }
148 
155  {
156  return frame_timestamp_;
157  }
158 
164  int getCompressedDepthFrameSize() const
165  {
167  }
168 
174  int getCompressedABFrameSize() const
175  {
177  }
178 
184  void setCompressedDepthFrameSize(int compressed_depth_frame_size)
185  {
186  compressed_depth_frame_size_ = compressed_depth_frame_size;
187  }
188 
194  void setCompressedABFrameSize(int compressed_ab_frame_size)
195  {
196  compressed_ab_frame_size_ = compressed_ab_frame_size;
197  }
198 
199  // Assignment operator
201  {
205  memcpy(ab_frame_, rhs.ab_frame_, sizeof(ab_frame_[0]) * image_width_ * image_height_);
206  memcpy(xyz_frame_, rhs.xyz_frame_, sizeof(xyz_frame_[0]) * image_width_ * image_height_ * 3);
207  memcpy(conf_frame_, rhs.conf_frame_, sizeof(conf_frame_[0]) * image_width_ * image_height_);
214  return *this;
215  }
216 
217 private:
221  unsigned short* depth_frame_;
225  unsigned short* ab_frame_;
230  short* xyz_frame_;
235  unsigned short* conf_frame_;
240  unsigned char* compressed_depth_frame_;
245  unsigned char* compressed_ab_frame_;
268 };
269 
270 #endif
ADI3DToFADTF31xxFrameInfo::compressed_depth_frame_size_
int compressed_depth_frame_size_
compressed depth frame size
Definition: adi_3dtof_adtf31xx_frame_info.h:254
ADI3DToFADTF31xxFrameInfo::xyz_frame_
short * xyz_frame_
xyz frame
Definition: adi_3dtof_adtf31xx_frame_info.h:234
ADI3DToFADTF31xxFrameInfo::getDepthFrame
unsigned short * getDepthFrame() const
Get the depth image frame.
Definition: adi_3dtof_adtf31xx_frame_info.h:88
ADI3DToFADTF31xxFrameInfo::ADI3DToFADTF31xxFrameInfo
ADI3DToFADTF31xxFrameInfo(int image_width, int image_height)
Constructor.
Definition: adi_3dtof_adtf31xx_frame_info.h:29
ADI3DToFADTF31xxFrameInfo::image_height_
int image_height_
Image height.
Definition: adi_3dtof_adtf31xx_frame_info.h:267
ADI3DToFADTF31xxFrameInfo::getFrameTimestampPtr
ros::Time * getFrameTimestampPtr()
Get Frame Timestamp Pointer.
Definition: adi_3dtof_adtf31xx_frame_info.h:148
ADI3DToFADTF31xxFrameInfo
This is the class for adtf31xx sensor frame.
Definition: adi_3dtof_adtf31xx_frame_info.h:16
ADI3DToFADTF31xxFrameInfo::depth_frame_
unsigned short * depth_frame_
Depth image.
Definition: adi_3dtof_adtf31xx_frame_info.h:225
ADI3DToFADTF31xxFrameInfo::conf_frame_
unsigned short * conf_frame_
conf frame
Definition: adi_3dtof_adtf31xx_frame_info.h:239
point_cloud.h
ADI3DToFADTF31xxFrameInfo::image_width_
int image_width_
Image width.
Definition: adi_3dtof_adtf31xx_frame_info.h:263
ADI3DToFADTF31xxFrameInfo::getXYZFrame
short * getXYZFrame() const
Get point cloud frame.
Definition: adi_3dtof_adtf31xx_frame_info.h:108
ADI3DToFADTF31xxFrameInfo::frame_timestamp_
ros::Time frame_timestamp_
Frame Timestamp.
Definition: adi_3dtof_adtf31xx_frame_info.h:271
ADI3DToFADTF31xxFrameInfo::~ADI3DToFADTF31xxFrameInfo
~ADI3DToFADTF31xxFrameInfo()
Destructor.
Definition: adi_3dtof_adtf31xx_frame_info.h:55
ADI3DToFADTF31xxFrameInfo::compressed_ab_frame_
unsigned char * compressed_ab_frame_
compressed ab frame
Definition: adi_3dtof_adtf31xx_frame_info.h:249
ADI3DToFADTF31xxFrameInfo::ab_frame_
unsigned short * ab_frame_
AB image.
Definition: adi_3dtof_adtf31xx_frame_info.h:229
ADI3DToFADTF31xxFrameInfo::getFrameTimestamp
ros::Time getFrameTimestamp() const
Get Frame Timestamp.
Definition: adi_3dtof_adtf31xx_frame_info.h:158
ADI3DToFADTF31xxFrameInfo::getCompressedABFrameSize
int getCompressedABFrameSize() const
Gives compressed AB image size.
Definition: adi_3dtof_adtf31xx_frame_info.h:178
ADI3DToFADTF31xxFrameInfo::setCompressedABFrameSize
void setCompressedABFrameSize(int compressed_ab_frame_size)
Set the Compressed AB Image Size.
Definition: adi_3dtof_adtf31xx_frame_info.h:198
ADI3DToFADTF31xxFrameInfo::compressed_ab_frame_size_
int compressed_ab_frame_size_
compressed ab frame size
Definition: adi_3dtof_adtf31xx_frame_info.h:259
ADI3DToFADTF31xxFrameInfo::getCompressedDepthFrame
unsigned char * getCompressedDepthFrame() const
Get Compressed depth image frame.
Definition: adi_3dtof_adtf31xx_frame_info.h:128
ros::Time
ADI3DToFADTF31xxFrameInfo::getCompressedDepthFrameSize
int getCompressedDepthFrameSize() const
Gives compressed depth image size.
Definition: adi_3dtof_adtf31xx_frame_info.h:168
ADI3DToFADTF31xxFrameInfo::compressed_depth_frame_
unsigned char * compressed_depth_frame_
compressed depth frame
Definition: adi_3dtof_adtf31xx_frame_info.h:244
ADI3DToFADTF31xxFrameInfo::getConfFrame
unsigned short * getConfFrame() const
Get Confidence frame.
Definition: adi_3dtof_adtf31xx_frame_info.h:118
ADI3DToFADTF31xxFrameInfo::operator=
ADI3DToFADTF31xxFrameInfo & operator=(const ADI3DToFADTF31xxFrameInfo &rhs)
Definition: adi_3dtof_adtf31xx_frame_info.h:204
ADI3DToFADTF31xxFrameInfo::getABFrame
unsigned short * getABFrame() const
Get the AB image frame.
Definition: adi_3dtof_adtf31xx_frame_info.h:98
ADI3DToFADTF31xxFrameInfo::getCompressedABFrame
unsigned char * getCompressedABFrame() const
Get Compressed AB image frame.
Definition: adi_3dtof_adtf31xx_frame_info.h:138
ADI3DToFADTF31xxFrameInfo::setCompressedDepthFrameSize
void setCompressedDepthFrameSize(int compressed_depth_frame_size)
Set the Compressed depth image size.
Definition: adi_3dtof_adtf31xx_frame_info.h:188
ros::Time::now
static Time now()


adi_3dtof_adtf31xx
Author(s):
autogenerated on Sat May 17 2025 02:12:30