image_proc_utils.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 
7 #ifndef IMAGE_PROC_UTILS_H
8 #define IMAGE_PROC_UTILS_H
9 
10 #include "adi_camera.h"
11 #include <cmath>
12 #include <cv_bridge/cv_bridge.h>
13 #include <opencv2/calib3d.hpp>
14 
20 {
21 public:
22  // default constructor with no argument
23  ImageProcUtils() = default;
24 
25  ImageProcUtils(CameraIntrinsics* camera_intrinsics, int image_width, int image_height)
26  {
27  image_width_ = image_width;
28  image_height_ = image_height;
29 
30  // Generate LUT for range to depth correction
31  range_to_3d_lut_ = new float[image_width_ * image_height_ * 3];
32  memset(range_to_3d_lut_, 0, sizeof(float) * image_width_ * image_height_ * 3);
33 
34  generateRangeTo3DLUT(camera_intrinsics);
35  }
36 
38  {
39  delete[] range_to_3d_lut_;
40  }
41 
42  float* getRangeToXYZLUT()
43  {
44  return range_to_3d_lut_;
45  }
52  void generateRangeTo3DLUT(CameraIntrinsics* camera_intrinsics)
53  {
54  /* Generate Camera Intrinsics calibration arrays. */
55  double k_raw_array[9] = { camera_intrinsics->camera_matrix[0], camera_intrinsics->camera_matrix[1],
56  camera_intrinsics->camera_matrix[2], camera_intrinsics->camera_matrix[3],
57  camera_intrinsics->camera_matrix[4], camera_intrinsics->camera_matrix[5],
58  camera_intrinsics->camera_matrix[6], camera_intrinsics->camera_matrix[7],
59  camera_intrinsics->camera_matrix[8] };
60  double d_raw_array[8] = { camera_intrinsics->distortion_coeffs[0], camera_intrinsics->distortion_coeffs[1],
61  camera_intrinsics->distortion_coeffs[2], camera_intrinsics->distortion_coeffs[3],
62  camera_intrinsics->distortion_coeffs[4], camera_intrinsics->distortion_coeffs[5],
63  camera_intrinsics->distortion_coeffs[6], camera_intrinsics->distortion_coeffs[7] };
64 
65  cv::Mat K_raw = cv::Mat(3, 3, CV_64F, k_raw_array);
66  cv::Mat D_raw = cv::Mat(1, 8, CV_64F, d_raw_array);
67  cv::Size img_size(image_width_, image_height_);
68  cv::Mat K_rect = cv::getOptimalNewCameraMatrix(K_raw, D_raw, img_size, 0, img_size, nullptr);
69 
70  // Prepare the rectification maps
71  cv::Mat r = cv::Mat::eye(3, 3, CV_32F);
72 
73  float* range_to_3d_lut = range_to_3d_lut_;
74 
75  for (int y = 0; y < image_height_; y++)
76  {
77  for (int x = 0; x < image_width_; x++)
78  {
79  cv::Mat distorted_pt(1, 1, CV_32FC2, cv::Scalar(x, y));
80  cv::Mat undistorted_pt(1, 1, CV_32FC2);
81 
82  cv::undistortPoints(distorted_pt, undistorted_pt, K_raw, D_raw);
83 
84  float ux = undistorted_pt.at<float>(0);
85  float uy = undistorted_pt.at<float>(1);
86 
87  float scale_factor = 1.0f / sqrtf(1.0f + ux * ux + uy * uy);
88 
89  *range_to_3d_lut++ = (ux * scale_factor);
90  *range_to_3d_lut++ = (uy * scale_factor);
91  *range_to_3d_lut++ = (scale_factor);
92  }
93  }
94  }
95 
104 void computePointCloud(unsigned short* range_image, short* xyz_frame)
105 {
106  float* range_to_3d_lut = range_to_3d_lut_;
107  float a = 0;
108 
109  for (int i = 0; i < image_height_; i++)
110  {
111  for (int j = 0; j < image_width_; j++)
112  {
113  unsigned short depth = (*range_image);
114  if (depth == 0)
115  depth = 8000;
116  *xyz_frame++ = (*range_to_3d_lut++) * (depth);
117  *xyz_frame++ = (*range_to_3d_lut++) * (depth);
118  *xyz_frame++ = (*range_to_3d_lut++) * (depth);
119  range_image++;
120  }
121  }
122 }
123 
130  static void gammaCorrect(unsigned short* src_dst, int num_pixels)
131  {
132  for (int i = 0; i < num_pixels; i++)
133  {
134  float pixel_value = (float)src_dst[i];
135  float out_pixel_value = (float)(255.0f * log(pixel_value)) / log(2048.0f);
136  src_dst[i] = (unsigned short)out_pixel_value;
137  }
138  }
139 
140 private:
141  int image_width_;
142  int image_height_;
143  float* range_to_3d_lut_;
144 };
145 
146 #endif
ImageProcUtils::image_width_
int image_width_
Definition: image_proc_utils.h:145
CameraIntrinsics::camera_matrix
float camera_matrix[9]
Camera matrix = [fx, 0, cx, 0, fy, cy, 0, 0, 1] fx, fy : Camera focal lengths (pixels) cx,...
Definition: adi_camera.h:27
ImageProcUtils
This class has image processing utilities.
Definition: image_proc_utils.h:19
ImageProcUtils::image_height_
int image_height_
Definition: image_proc_utils.h:146
ImageProcUtils::range_to_3d_lut_
float * range_to_3d_lut_
Definition: image_proc_utils.h:147
ImageProcUtils::computePointCloud
void computePointCloud(unsigned short *range_image, short *xyz_frame)
Computes point cloud using range_to_xyz_lut look up table and range image.
Definition: image_proc_utils.h:108
adi_camera.h
ImageProcUtils::ImageProcUtils
ImageProcUtils()=default
cv_bridge.h
CameraIntrinsics
Intrinsic parameters of the camera.
Definition: adi_camera.h:15
ImageProcUtils::getRangeToXYZLUT
float * getRangeToXYZLUT()
Definition: image_proc_utils.h:46
CameraIntrinsics::distortion_coeffs
float distortion_coeffs[8]
Distortion vector = [k1, k2, p1, p2, k3, k4, k5, k6] k1, k2, k3, k4, k5, k6 : Camera radial distortio...
Definition: adi_camera.h:35
ImageProcUtils::~ImageProcUtils
~ImageProcUtils()
Definition: image_proc_utils.h:41
ImageProcUtils::generateRangeTo3DLUT
void generateRangeTo3DLUT(CameraIntrinsics *camera_intrinsics)
Generates a Range to 3D projection Look up table, which can be used to compute point-cloud from the d...
Definition: image_proc_utils.h:56
ImageProcUtils::gammaCorrect
static void gammaCorrect(unsigned short *src_dst, int num_pixels)
Function for Gamma Correction.
Definition: image_proc_utils.h:134


adi_3dtof_image_stitching
Author(s):
autogenerated on Fri Mar 21 2025 02:27:20