Visual Servoing Platform  version 3.6.1 under development (2024-04-26)
vpImageConvert.h
1 /*
2  * ViSP, open source Visual Servoing Platform software.
3  * Copyright (C) 2005 - 2023 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 _vpImageConvert_h_
40 #define _vpImageConvert_h_
41 
42 #include <stdint.h>
43 
44 // image
45 #include <visp3/core/vpConfig.h>
46 #include <visp3/core/vpDebug.h>
47 #include <visp3/core/vpImage.h>
48 // color
49 #include <visp3/core/vpRGBa.h>
50 
51 #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC)
52 #include <opencv2/imgproc/imgproc.hpp>
53 #include <opencv2/imgproc/types_c.h>
54 #endif
55 
56 #ifdef VISP_HAVE_YARP
57 #include <yarp/sig/Image.h>
58 #endif
59 
60 #if defined(_WIN32)
61 // Include WinSock2.h before windows.h to ensure that winsock.h is not
62 // included by windows.h since winsock.h and winsock2.h are incompatible
63 #include <WinSock2.h>
64 #include <windows.h>
65 #endif
66 
67 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON) && defined(VISP_HAVE_THREADS)
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 
90 class VISP_EXPORT vpImageConvert
91 {
92 
93 public:
94  static void createDepthHistogram(const vpImage<uint16_t> &src_depth, vpImage<vpRGBa> &dest_rgba);
95  static void createDepthHistogram(const vpImage<uint16_t> &src_depth, vpImage<unsigned char> &dest_depth);
96 
97  static void createDepthHistogram(const vpImage<float> &src_depth, vpImage<vpRGBa> &dest_depth);
98  static void createDepthHistogram(const vpImage<float> &src_depth, vpImage<unsigned char> &dest_depth);
99 
100  static void convert(const vpImage<unsigned char> &src, vpImage<vpRGBa> &dest);
101  static void convert(const vpImage<vpRGBa> &src, vpImage<unsigned char> &dest, unsigned int nThreads = 0);
102 
103  static void convert(const vpImage<float> &src, vpImage<unsigned char> &dest);
104  static void convert(const vpImage<vpRGBf> &src, vpImage<vpRGBa> &dest);
105  static void convert(const vpImage<unsigned char> &src, vpImage<float> &dest);
106 
107  static void convert(const vpImage<double> &src, vpImage<unsigned char> &dest);
108  static void convert(const vpImage<unsigned char> &src, vpImage<double> &dest);
109 
110  static void convert(const vpImage<uint16_t> &src, vpImage<unsigned char> &dest, unsigned char bitshift = 8);
111  static void convert(const vpImage<unsigned char> &src, vpImage<uint16_t> &dest, unsigned char bitshift = 8);
112 
118  template <typename Type> static void convert(const vpImage<Type> &src, vpImage<Type> &dest) { dest = src; }
119 
120 #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC)
121  static void convert(const cv::Mat &src, vpImage<vpRGBa> &dest, bool flip = false);
122  static void convert(const cv::Mat &src, vpImage<unsigned char> &dest, bool flip = false, unsigned int nThreads = 0);
123  static void convert(const cv::Mat &src, vpImage<float> &dest, bool flip = false);
124  static void convert(const cv::Mat &src, vpImage<double> &dest, bool flip = false);
125  static void convert(const cv::Mat &src, vpImage<vpRGBf> &dest, bool flip = false);
126  static void convert(const cv::Mat &src, vpImage<uint16_t> &dest, bool flip = false);
127  static void convert(const vpImage<vpRGBa> &src, cv::Mat &dest);
128  static void convert(const vpImage<unsigned char> &src, cv::Mat &dest, bool copyData = true);
129  static void convert(const vpImage<float> &src, cv::Mat &dest, bool copyData = true);
130  static void convert(const vpImage<double> &src, cv::Mat &dest, bool copyData = true);
131  static void convert(const vpImage<vpRGBf> &src, cv::Mat &dest);
132 #endif
133 
134 #ifdef VISP_HAVE_YARP
135  static void convert(const vpImage<unsigned char> &src, yarp::sig::ImageOf<yarp::sig::PixelMono> *dest,
136  bool copyData = true);
137  static void convert(const yarp::sig::ImageOf<yarp::sig::PixelMono> *src, vpImage<unsigned char> &dest,
138  bool copyData = true);
139 
140  static void convert(const vpImage<vpRGBa> &src, yarp::sig::ImageOf<yarp::sig::PixelRgba> *dest, bool copyData = true);
141  static void convert(const yarp::sig::ImageOf<yarp::sig::PixelRgba> *src, vpImage<vpRGBa> &dest, bool copyData = true);
142 
143  static void convert(const vpImage<vpRGBa> &src, yarp::sig::ImageOf<yarp::sig::PixelRgb> *dest);
144  static void convert(const yarp::sig::ImageOf<yarp::sig::PixelRgb> *src, vpImage<vpRGBa> &dest);
145 #endif
146 
147 #if defined(VISP_HAVE_PCL) && defined(VISP_HAVE_PCL_COMMON) && defined(VISP_HAVE_THREADS)
148  static int depthToPointCloud(const vpImage<uint16_t> &depth_raw,
149  float depth_scale, const vpCameraParameters &cam_depth,
150  pcl::PointCloud<pcl::PointXYZ>::Ptr pointcloud,
151  std::mutex *pointcloud_mutex = nullptr,
152  const vpImage<unsigned char> *mask = nullptr, float Z_min = 0.2, float Z_max = 2.5);
153  static int depthToPointCloud(const vpImage<vpRGBa> &color, const vpImage<uint16_t> &depth_raw,
154  float depth_scale, const vpCameraParameters &cam_depth,
155  pcl::PointCloud<pcl::PointXYZRGB>::Ptr pointcloud,
156  std::mutex *pointcloud_mutex = nullptr,
157  const vpImage<unsigned char> *mask = nullptr, float Z_min = 0.2, float Z_max = 2.5);
158 #endif
159 
160  static void split(const vpImage<vpRGBa> &src, vpImage<unsigned char> *pR, vpImage<unsigned char> *pG,
162 
163  static void merge(const vpImage<unsigned char> *R, const vpImage<unsigned char> *G, const vpImage<unsigned char> *B,
164  const vpImage<unsigned char> *a, vpImage<vpRGBa> &RGBa);
165 
180  static inline void YUVToRGB(unsigned char y, unsigned char u, unsigned char v, unsigned char &r, unsigned char &g,
181  unsigned char &b)
182  {
183  double dr, dg, db;
184  dr = floor(0.9999695 * y - 0.0009508 * (u - 128) + 1.1359061 * (v - 128));
185  dg = floor(0.9999695 * y - 0.3959609 * (u - 128) - 0.5782955 * (v - 128));
186  db = floor(0.9999695 * y + 2.04112 * (u - 128) - 0.0016314 * (v - 128));
187 
188  dr = dr < 0. ? 0. : dr;
189  dg = dg < 0. ? 0. : dg;
190  db = db < 0. ? 0. : db;
191  dr = dr > 255. ? 255. : dr;
192  dg = dg > 255. ? 255. : dg;
193  db = db > 255. ? 255. : db;
194 
195  r = (unsigned char)dr;
196  g = (unsigned char)dg;
197  b = (unsigned char)db;
198  }
199  static void YUYVToRGBa(unsigned char *yuyv, unsigned char *rgba, unsigned int width, unsigned int height);
200  static void YUYVToRGB(unsigned char *yuyv, unsigned char *rgb, unsigned int width, unsigned int height);
201  static void YUYVToGrey(unsigned char *yuyv, unsigned char *grey, unsigned int size);
202  static void YUV411ToRGBa(unsigned char *yuv, unsigned char *rgba, unsigned int size);
203  static void YUV411ToRGB(unsigned char *yuv, unsigned char *rgb, unsigned int size);
204  static void YUV411ToGrey(unsigned char *yuv, unsigned char *grey, unsigned int size);
205  static void YUV422ToRGBa(unsigned char *yuv, unsigned char *rgba, unsigned int size);
206  static void YUV422ToRGB(unsigned char *yuv, unsigned char *rgb, unsigned int size);
207  static void YUV422ToGrey(unsigned char *yuv, unsigned char *grey, unsigned int size);
208  static void YUV420ToRGBa(unsigned char *yuv, unsigned char *rgba, unsigned int width, unsigned int height);
209  static void YUV420ToRGB(unsigned char *yuv, unsigned char *rgb, unsigned int width, unsigned int height);
210  static void YUV420ToGrey(unsigned char *yuv, unsigned char *grey, unsigned int size);
211 
212  static void YUV444ToRGBa(unsigned char *yuv, unsigned char *rgba, unsigned int size);
213  static void YUV444ToRGB(unsigned char *yuv, unsigned char *rgb, unsigned int size);
214  static void YUV444ToGrey(unsigned char *yuv, unsigned char *grey, unsigned int size);
215 
216  static void YV12ToRGBa(unsigned char *yuv, unsigned char *rgba, unsigned int width, unsigned int height);
217  static void YV12ToRGB(unsigned char *yuv, unsigned char *rgb, unsigned int width, unsigned int height);
218  static void YVU9ToRGBa(unsigned char *yuv, unsigned char *rgba, unsigned int width, unsigned int height);
219  static void YVU9ToRGB(unsigned char *yuv, unsigned char *rgb, unsigned int width, unsigned int height);
220  static void RGBToRGBa(unsigned char *rgb, unsigned char *rgba, unsigned int size);
221  static void RGBaToRGB(unsigned char *rgba, unsigned char *rgb, unsigned int size);
222 
223  static void RGBToGrey(unsigned char *rgb, unsigned char *grey, unsigned int width, unsigned int height,
224  bool flip = false);
225  static void RGBToGrey(unsigned char *rgb, unsigned char *grey, unsigned int size);
226  static void RGBaToGrey(unsigned char *rgba, unsigned char *grey, unsigned int width, unsigned int height,
227  unsigned int nThreads = 0);
228  static void RGBaToGrey(unsigned char *rgba, unsigned char *grey, unsigned int size);
229 
230  static void RGBToRGBa(unsigned char *rgb, unsigned char *rgba, unsigned int width, unsigned int height,
231  bool flip = false);
232 
233  static void GreyToRGBa(unsigned char *grey, unsigned char *rgba, unsigned int width, unsigned int height);
234  static void GreyToRGBa(unsigned char *grey, unsigned char *rgba, unsigned int size);
235  static void GreyToRGB(unsigned char *grey, unsigned char *rgb, unsigned int size);
236 
237  static void BGRToRGBa(unsigned char *bgr, unsigned char *rgba, unsigned int width, unsigned int height,
238  bool flip = false);
239 
240  static void BGRToGrey(unsigned char *bgr, unsigned char *grey, unsigned int width, unsigned int height,
241  bool flip = false, unsigned int nThreads = 0);
242 
243  static void BGRaToGrey(unsigned char *bgra, unsigned char *grey, unsigned int width, unsigned int height,
244  bool flip = false, unsigned int nThreads = 0);
245  static void BGRaToRGBa(unsigned char *bgra, unsigned char *rgba, unsigned int width, unsigned int height,
246  bool flip = false);
247 
248  static void YCbCrToRGB(unsigned char *ycbcr, unsigned char *rgb, unsigned int size);
249  static void YCbCrToRGBa(unsigned char *ycbcr, unsigned char *rgb, unsigned int size);
250  static void YCbCrToGrey(unsigned char *ycbcr, unsigned char *grey, unsigned int size);
251  static void YCrCbToRGB(unsigned char *ycrcb, unsigned char *rgb, unsigned int size);
252  static void YCrCbToRGBa(unsigned char *ycrcb, unsigned char *rgb, unsigned int size);
253  static void MONO16ToGrey(unsigned char *grey16, unsigned char *grey, unsigned int size);
254  static void MONO16ToRGBa(unsigned char *grey16, unsigned char *rgba, unsigned int size);
255 
256  static void HSVToRGBa(const double *hue, const double *saturation, const double *value, unsigned char *rgba,
257  unsigned int size);
258  static void HSVToRGBa(const unsigned char *hue, const unsigned char *saturation, const unsigned char *value,
259  unsigned char *rgba, unsigned int size, bool h_full = true);
260  static void RGBaToHSV(const unsigned char *rgba, double *hue, double *saturation, double *value, unsigned int size);
261  static void RGBaToHSV(const unsigned char *rgba, unsigned char *hue, unsigned char *saturation, unsigned char *value,
262  unsigned int size, bool h_full = true);
263 
264  static void HSVToRGB(const double *hue, const double *saturation, const double *value, unsigned char *rgb,
265  unsigned int size);
266  static void HSVToRGB(const unsigned char *hue, const unsigned char *saturation, const unsigned char *value,
267  unsigned char *rgb, unsigned int size, bool h_full = true);
268  static void RGBToHSV(const unsigned char *rgb, double *hue, double *saturation, double *value, unsigned int size);
269  static void RGBToHSV(const unsigned char *rgb, unsigned char *hue, unsigned char *saturation, unsigned char *value,
270  unsigned int size, bool h_full = true);
271 
272  static void demosaicBGGRToRGBaBilinear(const uint8_t *bggr, uint8_t *rgba, unsigned int width, unsigned int height,
273  unsigned int nThreads = 0);
274  static void demosaicBGGRToRGBaBilinear(const uint16_t *bggr, uint16_t *rgba, unsigned int width, unsigned int height,
275  unsigned int nThreads = 0);
276 
277  static void demosaicGBRGToRGBaBilinear(const uint8_t *gbrg, uint8_t *rgba, unsigned int width, unsigned int height,
278  unsigned int nThreads = 0);
279  static void demosaicGBRGToRGBaBilinear(const uint16_t *gbrg, uint16_t *rgba, unsigned int width, unsigned int height,
280  unsigned int nThreads = 0);
281 
282  static void demosaicGRBGToRGBaBilinear(const uint8_t *grbg, uint8_t *rgba, unsigned int width, unsigned int height,
283  unsigned int nThreads = 0);
284  static void demosaicGRBGToRGBaBilinear(const uint16_t *grbg, uint16_t *rgba, unsigned int width, unsigned int height,
285  unsigned int nThreads = 0);
286 
287  static void demosaicRGGBToRGBaBilinear(const uint8_t *rggb, uint8_t *rgba, unsigned int width, unsigned int height,
288  unsigned int nThreads = 0);
289  static void demosaicRGGBToRGBaBilinear(const uint16_t *rggb, uint16_t *rgba, unsigned int width, unsigned int height,
290  unsigned int nThreads = 0);
291 
292  static void demosaicBGGRToRGBaMalvar(const uint8_t *bggr, uint8_t *rgba, unsigned int width, unsigned int height,
293  unsigned int nThreads = 0);
294  static void demosaicBGGRToRGBaMalvar(const uint16_t *bggr, uint16_t *rgba, unsigned int width, unsigned int height,
295  unsigned int nThreads = 0);
296 
297  static void demosaicGBRGToRGBaMalvar(const uint8_t *gbrg, uint8_t *rgba, unsigned int width, unsigned int height,
298  unsigned int nThreads = 0);
299  static void demosaicGBRGToRGBaMalvar(const uint16_t *gbrg, uint16_t *rgba, unsigned int width, unsigned int height,
300  unsigned int nThreads = 0);
301 
302  static void demosaicGRBGToRGBaMalvar(const uint8_t *grbg, uint8_t *rgba, unsigned int width, unsigned int height,
303  unsigned int nThreads = 0);
304  static void demosaicGRBGToRGBaMalvar(const uint16_t *grbg, uint16_t *rgba, unsigned int width, unsigned int height,
305  unsigned int nThreads = 0);
306 
307  static void demosaicRGGBToRGBaMalvar(const uint8_t *rggb, uint8_t *rgba, unsigned int width, unsigned int height,
308  unsigned int nThreads = 0);
309  static void demosaicRGGBToRGBaMalvar(const uint16_t *rggb, uint16_t *rgba, unsigned int width, unsigned int height,
310  unsigned int nThreads = 0);
311 
312 private:
313  static void computeYCbCrLUT();
314 
315  static void HSV2RGB(const double *hue, const double *saturation, const double *value, unsigned char *rgba,
316  unsigned int size, unsigned int step);
317  static void HSV2RGB(const unsigned char *hue, const unsigned char *saturation, const unsigned char *value, unsigned char *rgba,
318  unsigned int size, unsigned int step, bool h_full);
319  static void RGB2HSV(const unsigned char *rgb, double *hue, double *saturation, double *value, unsigned int size,
320  unsigned int step);
321  static void RGB2HSV(const unsigned char *rgb, unsigned char *hue, unsigned char *saturation, unsigned char *value,
322  unsigned int size, unsigned int step, bool h_full);
323 
324 private:
325  static bool YCbCrLUTcomputed;
326  static int vpCrr[256];
327  static int vpCgb[256];
328  static int vpCgr[256];
329  static int vpCbb[256];
330 };
331 
332 #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:69