Visual Servoing Platform  version 3.6.1 under development (2024-07-27)
vpImageConvert.h
1 /*
2  * ViSP, open source Visual Servoing Platform software.
3  * Copyright (C) 2005 - 2024 by Inria. All rights reserved.
4  *
5  * This software is free software; you can redistribute it and/or modify
6  * it under the terms of the GNU General Public License as published by
7  * the Free Software Foundation; either version 2 of the License, or
8  * (at your option) any later version.
9  * See the file LICENSE.txt at the root directory of this source
10  * distribution for additional information about the GNU GPL.
11  *
12  * For using ViSP with software that can not be combined with the GNU
13  * GPL, please contact Inria about acquiring a ViSP Professional
14  * Edition License.
15  *
16  * See https://visp.inria.fr for more information.
17  *
18  * This software was developed at:
19  * Inria Rennes - Bretagne Atlantique
20  * Campus Universitaire de Beaulieu
21  * 35042 Rennes Cedex
22  * France
23  *
24  * If you have questions regarding the use of this file, please contact
25  * Inria at visp@inria.fr
26  *
27  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
28  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
29  *
30  * Description:
31  * Convert image types.
32  */
33 
39 #ifndef VP_IMAGE_CONVERT_H
40 #define VP_IMAGE_CONVERT_H
41 
42 #include <stdint.h>
43 
44 // image
45 #include <visp3/core/vpConfig.h>
46 #include <visp3/core/vpImage.h>
47 // color
48 #include <visp3/core/vpRGBa.h>
49 
50 #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC)
51 #include <opencv2/imgproc/imgproc.hpp>
52 #include <opencv2/imgproc/types_c.h>
53 #endif
54 
55 #ifdef VISP_HAVE_YARP
56 #include <yarp/sig/Image.h>
57 #endif
58 
59 #if defined(_WIN32)
60 // Include WinSock2.h before windows.h to ensure that winsock.h is not
61 // included by windows.h since winsock.h and winsock2.h are incompatible
62 #include <WinSock2.h>
63 #include <windows.h>
64 #endif
65 
66 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON) && defined(VISP_HAVE_THREADS)
67 #include <mutex>
68 #include <visp3/core/vpColVector.h>
69 #include <visp3/core/vpImageException.h>
70 #include <visp3/core/vpPixelMeterConversion.h>
71 
72 #include <pcl/pcl_config.h>
73 #include <pcl/point_types.h>
74 #include <pcl/point_cloud.h>
75 #endif
76 
91 class VISP_EXPORT vpImageConvert
92 {
93 
94 public:
95  static void createDepthHistogram(const vpImage<uint16_t> &src_depth, vpImage<vpRGBa> &dest_rgba);
96  static void createDepthHistogram(const vpImage<uint16_t> &src_depth, vpImage<unsigned char> &dest_depth);
97 
98  static void createDepthHistogram(const vpImage<float> &src_depth, vpImage<vpRGBa> &dest_depth);
99  static void createDepthHistogram(const vpImage<float> &src_depth, vpImage<unsigned char> &dest_depth);
100 
101  static void convert(const vpImage<unsigned char> &src, vpImage<vpRGBa> &dest);
102  static void convert(const vpImage<vpRGBa> &src, vpImage<unsigned char> &dest, unsigned int nThreads = 0);
103 
104  static void convert(const vpImage<float> &src, vpImage<unsigned char> &dest);
105  static void convert(const vpImage<vpRGBf> &src, vpImage<vpRGBa> &dest);
106  static void convert(const vpImage<unsigned char> &src, vpImage<float> &dest);
107 
108  static void convert(const vpImage<double> &src, vpImage<unsigned char> &dest);
109  static void convert(const vpImage<unsigned char> &src, vpImage<double> &dest);
110 
111  static void convert(const vpImage<uint16_t> &src, vpImage<unsigned char> &dest, unsigned char bitshift = 8);
112  static void convert(const vpImage<unsigned char> &src, vpImage<uint16_t> &dest, unsigned char bitshift = 8);
113 
119  template <typename Type> static void convert(const vpImage<Type> &src, vpImage<Type> &dest) { dest = src; }
120 
121 #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC)
122  static void convert(const cv::Mat &src, vpImage<vpRGBa> &dest, bool flip = false);
123  static void convert(const cv::Mat &src, vpImage<unsigned char> &dest, bool flip = false, unsigned int nThreads = 0);
124  static void convert(const cv::Mat &src, vpImage<float> &dest, bool flip = false);
125  static void convert(const cv::Mat &src, vpImage<double> &dest, bool flip = false);
126  static void convert(const cv::Mat &src, vpImage<vpRGBf> &dest, bool flip = false);
127  static void convert(const cv::Mat &src, vpImage<uint16_t> &dest, bool flip = false);
128  static void convert(const vpImage<vpRGBa> &src, cv::Mat &dest);
129  static void convert(const vpImage<unsigned char> &src, cv::Mat &dest, bool copyData = true);
130  static void convert(const vpImage<float> &src, cv::Mat &dest, bool copyData = true);
131  static void convert(const vpImage<double> &src, cv::Mat &dest, bool copyData = true);
132  static void convert(const vpImage<vpRGBf> &src, cv::Mat &dest);
133 #endif
134 
135 #ifdef VISP_HAVE_YARP
136  static void convert(const vpImage<unsigned char> &src, yarp::sig::ImageOf<yarp::sig::PixelMono> *dest,
137  bool copyData = true);
138  static void convert(const yarp::sig::ImageOf<yarp::sig::PixelMono> *src, vpImage<unsigned char> &dest,
139  bool copyData = true);
140 
141  static void convert(const vpImage<vpRGBa> &src, yarp::sig::ImageOf<yarp::sig::PixelRgba> *dest, bool copyData = true);
142  static void convert(const yarp::sig::ImageOf<yarp::sig::PixelRgba> *src, vpImage<vpRGBa> &dest, bool copyData = true);
143 
144  static void convert(const vpImage<vpRGBa> &src, yarp::sig::ImageOf<yarp::sig::PixelRgb> *dest);
145  static void convert(const yarp::sig::ImageOf<yarp::sig::PixelRgb> *src, vpImage<vpRGBa> &dest);
146 #endif
147 
148 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON) && defined(VISP_HAVE_THREADS)
149  static int depthToPointCloud(const vpImage<uint16_t> &depth_raw,
150  float depth_scale, const vpCameraParameters &cam_depth,
151  pcl::PointCloud<pcl::PointXYZ>::Ptr pointcloud,
152  std::mutex *pointcloud_mutex = nullptr,
153  const vpImage<unsigned char> *mask = nullptr, float Z_min = 0.2, float Z_max = 2.5);
154  static int depthToPointCloud(const vpImage<vpRGBa> &color, const vpImage<uint16_t> &depth_raw,
155  float depth_scale, const vpCameraParameters &cam_depth,
156  pcl::PointCloud<pcl::PointXYZRGB>::Ptr pointcloud,
157  std::mutex *pointcloud_mutex = nullptr,
158  const vpImage<unsigned char> *mask = nullptr, float Z_min = 0.2, float Z_max = 2.5);
159 #endif
160 
161  static void split(const vpImage<vpRGBa> &src, vpImage<unsigned char> *pR, vpImage<unsigned char> *pG,
163 
164  static void merge(const vpImage<unsigned char> *R, const vpImage<unsigned char> *G, const vpImage<unsigned char> *B,
165  const vpImage<unsigned char> *a, vpImage<vpRGBa> &RGBa);
166 
181  static inline void YUVToRGB(unsigned char y, unsigned char u, unsigned char v, unsigned char &r, unsigned char &g,
182  unsigned char &b)
183  {
184  double dr, dg, db;
185  dr = floor(((0.9999695 * y) - (0.0009508 * (u - 128))) + (1.1359061 * (v - 128)));
186  dg = floor(((0.9999695 * y) - (0.3959609 * (u - 128))) - (0.5782955 * (v - 128)));
187  db = floor(((0.9999695 * y) + (2.04112 * (u - 128))) - (0.0016314 * (v - 128)));
188 
189  dr = dr < 0. ? 0. : dr;
190  dg = dg < 0. ? 0. : dg;
191  db = db < 0. ? 0. : db;
192  dr = dr > 255. ? 255. : dr;
193  dg = dg > 255. ? 255. : dg;
194  db = db > 255. ? 255. : db;
195 
196  r = static_cast<unsigned char>(dr);
197  g = static_cast<unsigned char>(dg);
198  b = static_cast<unsigned char>(db);
199  }
200  static void YUYVToRGBa(unsigned char *yuyv, unsigned char *rgba, unsigned int width, unsigned int height);
201  static void YUYVToRGB(unsigned char *yuyv, unsigned char *rgb, unsigned int width, unsigned int height);
202  static void YUYVToGrey(unsigned char *yuyv, unsigned char *grey, unsigned int size);
203  static void YUV411ToRGBa(unsigned char *yuv, unsigned char *rgba, unsigned int size);
204  static void YUV411ToRGB(unsigned char *yuv, unsigned char *rgb, unsigned int size);
205  static void YUV411ToGrey(unsigned char *yuv, unsigned char *grey, unsigned int size);
206  static void YUV422ToRGBa(unsigned char *yuv, unsigned char *rgba, unsigned int size);
207  static void YUV422ToRGB(unsigned char *yuv, unsigned char *rgb, unsigned int size);
208  static void YUV422ToGrey(unsigned char *yuv, unsigned char *grey, unsigned int size);
209  static void YUV420ToRGBa(unsigned char *yuv, unsigned char *rgba, unsigned int width, unsigned int height);
210  static void YUV420ToRGB(unsigned char *yuv, unsigned char *rgb, unsigned int width, unsigned int height);
211  static void YUV420ToGrey(unsigned char *yuv, unsigned char *grey, unsigned int size);
212 
213  static void YUV444ToRGBa(unsigned char *yuv, unsigned char *rgba, unsigned int size);
214  static void YUV444ToRGB(unsigned char *yuv, unsigned char *rgb, unsigned int size);
215  static void YUV444ToGrey(unsigned char *yuv, unsigned char *grey, unsigned int size);
216 
217  static void YV12ToRGBa(unsigned char *yuv, unsigned char *rgba, unsigned int width, unsigned int height);
218  static void YV12ToRGB(unsigned char *yuv, unsigned char *rgb, unsigned int width, unsigned int height);
219  static void YVU9ToRGBa(unsigned char *yuv, unsigned char *rgba, unsigned int width, unsigned int height);
220  static void YVU9ToRGB(unsigned char *yuv, unsigned char *rgb, unsigned int width, unsigned int height);
221  static void RGBToRGBa(unsigned char *rgb, unsigned char *rgba, unsigned int size);
222  static void RGBaToRGB(unsigned char *rgba, unsigned char *rgb, unsigned int size);
223 
224  static void RGBToGrey(unsigned char *rgb, unsigned char *grey, unsigned int width, unsigned int height,
225  bool flip = false);
226  static void RGBToGrey(unsigned char *rgb, unsigned char *grey, unsigned int size);
227  static void RGBaToGrey(unsigned char *rgba, unsigned char *grey, unsigned int width, unsigned int height,
228  unsigned int nThreads = 0);
229  static void RGBaToGrey(unsigned char *rgba, unsigned char *grey, unsigned int size);
230 
231  static void RGBToRGBa(unsigned char *rgb, unsigned char *rgba, unsigned int width, unsigned int height,
232  bool flip = false);
233 
234  static void GreyToRGBa(unsigned char *grey, unsigned char *rgba, unsigned int width, unsigned int height);
235  static void GreyToRGBa(unsigned char *grey, unsigned char *rgba, unsigned int size);
236  static void GreyToRGB(unsigned char *grey, unsigned char *rgb, unsigned int size);
237 
238  static void BGRToRGBa(unsigned char *bgr, unsigned char *rgba, unsigned int width, unsigned int height,
239  bool flip = false);
240 
241  static void BGRToGrey(unsigned char *bgr, unsigned char *grey, unsigned int width, unsigned int height,
242  bool flip = false, unsigned int nThreads = 0);
243 
244  static void BGRaToGrey(unsigned char *bgra, unsigned char *grey, unsigned int width, unsigned int height,
245  bool flip = false, unsigned int nThreads = 0);
246  static void BGRaToRGBa(unsigned char *bgra, unsigned char *rgba, unsigned int width, unsigned int height,
247  bool flip = false);
248 
249  static void YCbCrToRGB(unsigned char *ycbcr, unsigned char *rgb, unsigned int size);
250  static void YCbCrToRGBa(unsigned char *ycbcr, unsigned char *rgb, unsigned int size);
251  static void YCbCrToGrey(unsigned char *ycbcr, unsigned char *grey, unsigned int size);
252  static void YCrCbToRGB(unsigned char *ycrcb, unsigned char *rgb, unsigned int size);
253  static void YCrCbToRGBa(unsigned char *ycrcb, unsigned char *rgb, unsigned int size);
254  static void MONO16ToGrey(unsigned char *grey16, unsigned char *grey, unsigned int size);
255  static void MONO16ToRGBa(unsigned char *grey16, unsigned char *rgba, unsigned int size);
256 
257  static void HSVToRGBa(const double *hue, const double *saturation, const double *value, unsigned char *rgba,
258  unsigned int size);
259  static void HSVToRGBa(const unsigned char *hue, const unsigned char *saturation, const unsigned char *value,
260  unsigned char *rgba, unsigned int size, bool h_full = true);
261  static void RGBaToHSV(const unsigned char *rgba, double *hue, double *saturation, double *value, unsigned int size);
262  static void RGBaToHSV(const unsigned char *rgba, unsigned char *hue, unsigned char *saturation, unsigned char *value,
263  unsigned int size, bool h_full = true);
264 
265  static void HSVToRGB(const double *hue, const double *saturation, const double *value, unsigned char *rgb,
266  unsigned int size);
267  static void HSVToRGB(const unsigned char *hue, const unsigned char *saturation, const unsigned char *value,
268  unsigned char *rgb, unsigned int size, bool h_full = true);
269  static void RGBToHSV(const unsigned char *rgb, double *hue, double *saturation, double *value, unsigned int size);
270  static void RGBToHSV(const unsigned char *rgb, unsigned char *hue, unsigned char *saturation, unsigned char *value,
271  unsigned int size, bool h_full = true);
272 
273 #ifndef VISP_SKIP_BAYER_CONVERSION
274  static void demosaicBGGRToRGBaBilinear(const uint8_t *bggr, uint8_t *rgba, unsigned int width, unsigned int height,
275  unsigned int nThreads = 0);
276  static void demosaicBGGRToRGBaBilinear(const uint16_t *bggr, uint16_t *rgba, unsigned int width, unsigned int height,
277  unsigned int nThreads = 0);
278 
279  static void demosaicGBRGToRGBaBilinear(const uint8_t *gbrg, uint8_t *rgba, unsigned int width, unsigned int height,
280  unsigned int nThreads = 0);
281  static void demosaicGBRGToRGBaBilinear(const uint16_t *gbrg, uint16_t *rgba, unsigned int width, unsigned int height,
282  unsigned int nThreads = 0);
283 
284  static void demosaicGRBGToRGBaBilinear(const uint8_t *grbg, uint8_t *rgba, unsigned int width, unsigned int height,
285  unsigned int nThreads = 0);
286  static void demosaicGRBGToRGBaBilinear(const uint16_t *grbg, uint16_t *rgba, unsigned int width, unsigned int height,
287  unsigned int nThreads = 0);
288 
289  static void demosaicRGGBToRGBaBilinear(const uint8_t *rggb, uint8_t *rgba, unsigned int width, unsigned int height,
290  unsigned int nThreads = 0);
291  static void demosaicRGGBToRGBaBilinear(const uint16_t *rggb, uint16_t *rgba, unsigned int width, unsigned int height,
292  unsigned int nThreads = 0);
293 
294  static void demosaicBGGRToRGBaMalvar(const uint8_t *bggr, uint8_t *rgba, unsigned int width, unsigned int height,
295  unsigned int nThreads = 0);
296  static void demosaicBGGRToRGBaMalvar(const uint16_t *bggr, uint16_t *rgba, unsigned int width, unsigned int height,
297  unsigned int nThreads = 0);
298 
299  static void demosaicGBRGToRGBaMalvar(const uint8_t *gbrg, uint8_t *rgba, unsigned int width, unsigned int height,
300  unsigned int nThreads = 0);
301  static void demosaicGBRGToRGBaMalvar(const uint16_t *gbrg, uint16_t *rgba, unsigned int width, unsigned int height,
302  unsigned int nThreads = 0);
303 
304  static void demosaicGRBGToRGBaMalvar(const uint8_t *grbg, uint8_t *rgba, unsigned int width, unsigned int height,
305  unsigned int nThreads = 0);
306  static void demosaicGRBGToRGBaMalvar(const uint16_t *grbg, uint16_t *rgba, unsigned int width, unsigned int height,
307  unsigned int nThreads = 0);
308 
309  static void demosaicRGGBToRGBaMalvar(const uint8_t *rggb, uint8_t *rgba, unsigned int width, unsigned int height,
310  unsigned int nThreads = 0);
311  static void demosaicRGGBToRGBaMalvar(const uint16_t *rggb, uint16_t *rgba, unsigned int width, unsigned int height,
312  unsigned int nThreads = 0);
313 #endif
314 
315 private:
316  static void computeYCbCrLUT();
317 
318  static void HSV2RGB(const double *hue, const double *saturation, const double *value, unsigned char *rgba,
319  unsigned int size, unsigned int step);
320  static void HSV2RGB(const unsigned char *hue, const unsigned char *saturation, const unsigned char *value, unsigned char *rgba,
321  unsigned int size, unsigned int step, bool h_full);
322  static void RGB2HSV(const unsigned char *rgb, double *hue, double *saturation, double *value, unsigned int size,
323  unsigned int step);
324  static void RGB2HSV(const unsigned char *rgb, unsigned char *hue, unsigned char *saturation, unsigned char *value,
325  unsigned int size, unsigned int step, bool h_full);
326 
327 private:
328  static bool YCbCrLUTcomputed;
329  static int vpCrr[256];
330  static int vpCgb[256];
331  static int vpCgr[256];
332  static int vpCbb[256];
333 };
334 END_VISP_NAMESPACE
335 #endif
Generic class defining intrinsic camera parameters.
static void convert(const vpImage< Type > &src, vpImage< Type > &dest)
static void YUVToRGB(unsigned char y, unsigned char u, unsigned char v, unsigned char &r, unsigned char &g, unsigned char &b)
Definition of the vpImage class member functions.
Definition: vpImage.h:131