Visual Servoing Platform  version 3.6.1 under development (2024-04-16)
vpImageConvert.cpp
1 /****************************************************************************
2  *
3  * ViSP, open source Visual Servoing Platform software.
4  * Copyright (C) 2005 - 2023 by Inria. All rights reserved.
5  *
6  * This software is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License as published by
8  * the Free Software Foundation; either version 2 of the License, or
9  * (at your option) any later version.
10  * See the file LICENSE.txt at the root directory of this source
11  * distribution for additional information about the GNU GPL.
12  *
13  * For using ViSP with software that can not be combined with the GNU
14  * GPL, please contact Inria about acquiring a ViSP Professional
15  * Edition License.
16  *
17  * See https://visp.inria.fr for more information.
18  *
19  * This software was developed at:
20  * Inria Rennes - Bretagne Atlantique
21  * Campus Universitaire de Beaulieu
22  * 35042 Rennes Cedex
23  * France
24  *
25  * If you have questions regarding the use of this file, please contact
26  * Inria at visp@inria.fr
27  *
28  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
29  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
30  *
31  * Description:
32  * Convert image types.
33  *
34 *****************************************************************************/
35 
41 #include <map>
42 #include <sstream>
43 
44 #if defined(_OPENMP)
45 #include <omp.h>
46 #endif
47 
48 
49 #include <visp3/core/vpConfig.h>
50 // image
51 #include "private/vpBayerConversion.h"
52 #include "private/vpImageConvert_impl.h"
53 #if defined(VISP_HAVE_SIMDLIB)
54 #include <Simd/SimdLib.h>
55 #endif
56 #include <visp3/core/vpImageConvert.h>
57 
58 bool vpImageConvert::YCbCrLUTcomputed = false;
59 int vpImageConvert::vpCrr[256];
60 int vpImageConvert::vpCgb[256];
61 int vpImageConvert::vpCgr[256];
62 int vpImageConvert::vpCbb[256];
63 
73 {
74  dest.resize(src.getHeight(), src.getWidth());
75 
76  GreyToRGBa(src.bitmap, reinterpret_cast<unsigned char *>(dest.bitmap), src.getWidth(), src.getHeight());
77 }
78 
88 void vpImageConvert::convert(const vpImage<vpRGBa> &src, vpImage<unsigned char> &dest, unsigned int nThreads)
89 {
90  dest.resize(src.getHeight(), src.getWidth());
91 
92  RGBaToGrey(reinterpret_cast<unsigned char *>(src.bitmap), dest.bitmap, src.getWidth(), src.getHeight(), nThreads);
93 }
94 
102 {
103  dest.resize(src.getHeight(), src.getWidth());
104  unsigned int max_xy = src.getWidth() * src.getHeight();
105  float min, max;
106 
107  src.getMinMaxValue(min, max);
108 
109  for (unsigned int i = 0; i < max_xy; ++i) {
110  float val = 255.f * ((src.bitmap[i] - min) / (max - min));
111  if (val < 0) {
112  dest.bitmap[i] = 0;
113  }
114  else if (val > 255) {
115  dest.bitmap[i] = 255;
116  }
117  else {
118  dest.bitmap[i] = static_cast<unsigned char>(val);
119  }
120  }
121 }
122 
130 {
131  const unsigned int srcHeight = src.getHeight(), srcWidth = src.getWidth();
132  dest.resize(src.getHeight(), src.getWidth());
133  vpRGBf min, max;
134  src.getMinMaxValue(min, max);
135 
136  for (unsigned int i = 0; i < srcHeight; ++i) {
137  for (unsigned int j = 0; j < srcWidth; ++j) {
138  for (unsigned int c = 0; c < 3; ++c) {
139  float val = 255.f * ((reinterpret_cast<const float *>(&(src[i][j]))[c] - reinterpret_cast<float *>(&min)[c]) /
140  (reinterpret_cast<float *>(&max)[c] - reinterpret_cast<float *>(&min)[c]));
141  if (val < 0) {
142  reinterpret_cast<unsigned char *>(&(dest[i][j]))[c] = 0;
143  }
144  else if (val > 255) {
145  reinterpret_cast<unsigned char *>(&(dest[i][j]))[c] = 255;
146  }
147  else {
148  reinterpret_cast<unsigned char *>(&(dest[i][j]))[c] = static_cast<unsigned char>(val);
149  }
150  }
151  }
152  }
153 }
154 
161 {
162  const unsigned int srcHeight = src.getHeight(), srcWidth = src.getWidth();
163  const unsigned int srcSize = srcHeight * srcWidth;
164  dest.resize(srcHeight, srcWidth);
165  for (unsigned int i = 0; i < srcSize; ++i) {
166  dest.bitmap[i] = static_cast<float>(src.bitmap[i]);
167  }
168 }
169 
177 {
178  dest.resize(src.getHeight(), src.getWidth());
179  unsigned int max_xy = src.getWidth() * src.getHeight();
180  double min, max;
181 
182  src.getMinMaxValue(min, max);
183 
184  for (unsigned int i = 0; i < max_xy; ++i) {
185  double val = 255. * ((src.bitmap[i] - min) / (max - min));
186  if (val < 0) {
187  dest.bitmap[i] = 0;
188  }
189  else if (val > 255) {
190  dest.bitmap[i] = 255;
191  }
192  else {
193  dest.bitmap[i] = static_cast<unsigned char>(val);
194  }
195  }
196 }
197 
204 void vpImageConvert::convert(const vpImage<uint16_t> &src, vpImage<unsigned char> &dest, unsigned char bitshift)
205 {
206  const unsigned int srcSize = src.getSize();
207  dest.resize(src.getHeight(), src.getWidth());
208 
209  for (unsigned int i = 0; i < srcSize; ++i) {
210  dest.bitmap[i] = static_cast<unsigned char>(src.bitmap[i] >> bitshift);
211  }
212 }
213 
220 void vpImageConvert::convert(const vpImage<unsigned char> &src, vpImage<uint16_t> &dest, unsigned char bitshift)
221 {
222  const unsigned int srcSize = src.getSize();
223  dest.resize(src.getHeight(), src.getWidth());
224 
225  for (unsigned int i = 0; i < srcSize; ++i) {
226  dest.bitmap[i] = static_cast<unsigned char>(src.bitmap[i] << bitshift);
227  }
228 }
229 
236 {
237  const unsigned int srcHeight = src.getHeight(), srcWidth = src.getWidth();
238  const unsigned int srcSize = srcHeight * srcWidth;
239  dest.resize(srcHeight, srcWidth);
240  for (unsigned int i = 0; i < srcSize; ++i) {
241  dest.bitmap[i] = static_cast<double>(src.bitmap[i]);
242  }
243 }
244 
253 {
254  vp_createDepthHistogram(src_depth, dest_rgba);
255 }
256 
264 {
265  vp_createDepthHistogram(src_depth, dest_depth);
266 }
267 
276 {
277  vp_createDepthHistogram(src_depth, dest_rgba);
278 }
279 
287 {
288  vp_createDepthHistogram(src_depth, dest_depth);
289 }
290 
291 #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC)
292 
333 void vpImageConvert::convert(const cv::Mat &src, vpImage<vpRGBa> &dest, bool flip)
334 {
335  dest.resize(static_cast<unsigned int>(src.rows), static_cast<unsigned int>(src.cols));
336  unsigned int destRows = dest.getRows();
337  unsigned int destCols = dest.getCols();
338  if (src.type() == CV_8UC4) {
339  vpRGBa rgbaVal;
340  for (unsigned int i = 0; i < destRows; ++i)
341  for (unsigned int j = 0; j < destCols; ++j) {
342  cv::Vec4b tmp = src.at<cv::Vec4b>(static_cast<int>(i), static_cast<int>(j));
343  rgbaVal.R = tmp[2];
344  rgbaVal.G = tmp[1];
345  rgbaVal.B = tmp[0];
346  rgbaVal.A = tmp[3];
347  if (flip) {
348  dest[destRows - i - 1][j] = rgbaVal;
349  }
350  else {
351  dest[i][j] = rgbaVal;
352  }
353  }
354  }
355  else if (src.type() == CV_8UC3) {
356 #if defined(VISP_HAVE_SIMDLIB)
357  if (src.isContinuous() && (!flip)) {
358  SimdRgbToBgra(src.data, src.cols, src.rows, src.step[0], reinterpret_cast<uint8_t *>(dest.bitmap),
359  dest.getWidth() * sizeof(vpRGBa), vpRGBa::alpha_default);
360  }
361  else {
362 #endif
363  vpRGBa rgbaVal;
364  rgbaVal.A = vpRGBa::alpha_default;
365  for (unsigned int i = 0; i < destRows; ++i) {
366  for (unsigned int j = 0; j < destCols; ++j) {
367  cv::Vec3b tmp = src.at<cv::Vec3b>(static_cast<int>(i), static_cast<int>(j));
368  rgbaVal.R = tmp[2];
369  rgbaVal.G = tmp[1];
370  rgbaVal.B = tmp[0];
371  if (flip) {
372  dest[destRows - i - 1][j] = rgbaVal;
373  }
374  else {
375  dest[i][j] = rgbaVal;
376  }
377  }
378  }
379 #if defined(VISP_HAVE_SIMDLIB)
380  }
381 #endif
382  }
383  else if (src.type() == CV_8UC1) {
384 #if defined(VISP_HAVE_SIMDLIB)
385  if (src.isContinuous() && (!flip)) {
386  SimdGrayToBgra(src.data, src.cols, src.rows, src.step[0], reinterpret_cast<uint8_t *>(dest.bitmap),
387  dest.getWidth() * sizeof(vpRGBa), vpRGBa::alpha_default);
388  }
389  else {
390 #endif
391  vpRGBa rgbaVal;
392  for (unsigned int i = 0; i < destRows; ++i) {
393  for (unsigned int j = 0; j < destCols; ++j) {
394  rgbaVal = src.at<unsigned char>(static_cast<int>(i), static_cast<int>(j));
395  rgbaVal.A = vpRGBa::alpha_default;
396  if (flip) {
397  dest[destRows - i - 1][j] = rgbaVal;
398  }
399  else {
400  dest[i][j] = rgbaVal;
401  }
402  }
403  }
404 #if defined(VISP_HAVE_SIMDLIB)
405  }
406 #endif
407  }
408 }
409 
445 void vpImageConvert::convert(const cv::Mat &src, vpImage<unsigned char> &dest, bool flip, unsigned int nThreads)
446 {
447  if (src.type() == CV_8UC1) {
448  dest.resize(static_cast<unsigned int>(src.rows), static_cast<unsigned int>(src.cols));
449  unsigned int destRows = dest.getRows();
450  unsigned int destCols = dest.getCols();
451  if (src.isContinuous() && (!flip)) {
452  memcpy(dest.bitmap, src.data, static_cast<size_t>(src.rows * src.cols));
453  }
454  else {
455  if (flip) {
456  for (unsigned int i = 0; i < destRows; ++i) {
457  memcpy(dest.bitmap + (i * destCols), src.data + ((destRows - i - 1) * src.step1()), static_cast<size_t>(src.step));
458  }
459  }
460  else {
461  for (unsigned int i = 0; i < destRows; ++i) {
462  memcpy(dest.bitmap + (i * destCols), src.data + (i * src.step1()), static_cast<size_t>(src.step));
463  }
464  }
465  }
466  }
467  else if (src.type() == CV_8UC3) {
468  dest.resize(static_cast<unsigned int>(src.rows), static_cast<unsigned int>(src.cols));
469  unsigned int destRows = dest.getRows();
470  unsigned int destCols = dest.getCols();
471  if (src.isContinuous()) {
472  BGRToGrey((unsigned char *)src.data, (unsigned char *)dest.bitmap, static_cast<unsigned int>(src.cols), static_cast<unsigned int>(src.rows),
473  flip, nThreads);
474  }
475  else {
476  if (flip) {
477  for (unsigned int i = 0; i < destRows; ++i) {
478  BGRToGrey((unsigned char *)src.data + (i * src.step1()),
479  (unsigned char *)dest.bitmap + ((destRows - i - 1) * destCols),
480  static_cast<unsigned int>(destCols), 1, false);
481  }
482  }
483  else {
484  for (unsigned int i = 0; i < destRows; ++i) {
485  BGRToGrey((unsigned char *)src.data + (i * src.step1()), (unsigned char *)dest.bitmap + (i * destCols),
486  static_cast<unsigned int>(destCols), 1, false);
487  }
488  }
489  }
490  }
491  else if (src.type() == CV_8UC4) {
492  dest.resize(static_cast<unsigned int>(src.rows), static_cast<unsigned int>(src.cols));
493  unsigned int destRows = dest.getRows();
494  unsigned int destCols = dest.getCols();
495  if (src.isContinuous()) {
496  BGRaToGrey((unsigned char *)src.data, (unsigned char *)dest.bitmap, static_cast<unsigned int>(src.cols),
497  static_cast<unsigned int>(src.rows), flip, nThreads);
498  }
499  else {
500  if (flip) {
501  for (unsigned int i = 0; i < destRows; ++i) {
502  BGRaToGrey((unsigned char *)src.data + (i * src.step1()),
503  (unsigned char *)dest.bitmap + ((destRows - i - 1) * destCols),
504  static_cast<unsigned int>(destCols), 1, false);
505  }
506  }
507  else {
508  for (unsigned int i = 0; i < destRows; ++i) {
509  BGRaToGrey((unsigned char *)src.data + (i * src.step1()), (unsigned char *)dest.bitmap + (i * destCols),
510  static_cast<unsigned int>(destCols), 1, false);
511  }
512  }
513  }
514  }
515 }
516 
524 void vpImageConvert::convert(const cv::Mat &src, vpImage<float> &dest, bool flip)
525 {
526  dest.resize(static_cast<unsigned int>(src.rows), static_cast<unsigned int>(src.cols));
527  unsigned int destRows = dest.getRows();
528  unsigned int destCols = dest.getCols();
529 
530  if (src.type() == CV_32FC1) {
531  for (unsigned int i = 0; i < destRows; ++i)
532  for (unsigned int j = 0; j < destCols; ++j) {
533  if (flip) {
534  dest[dest.getRows() - i - 1][j] = src.at<float>(static_cast<int>(i), static_cast<int>(j));
535  }
536  else {
537  dest[i][j] = src.at<float>(static_cast<int>(i), static_cast<int>(j));
538  }
539  }
540  }
541  else {
542  throw vpException(vpException::badValue, "cv::Mat type is not supported!");
543  }
544 }
545 
553 void vpImageConvert::convert(const cv::Mat &src, vpImage<double> &dest, bool flip)
554 {
555  vpImage<float> I_float;
556  convert(src, I_float, flip);
557  unsigned int nbRows = static_cast<unsigned int>(src.rows);
558  unsigned int nbCols = static_cast<unsigned int>(src.cols);
559  dest.resize(nbRows, nbCols);
560  for (unsigned int i = 0; i < nbRows; ++i) {
561  for (unsigned int j = 0; j < nbCols; ++j) {
562  dest[i][j] = I_float[i][j];
563  }
564  }
565 }
566 
574 void vpImageConvert::convert(const cv::Mat &src, vpImage<uint16_t> &dest, bool flip)
575 {
576  dest.resize(static_cast<unsigned int>(src.rows), static_cast<unsigned int>(src.cols));
577  unsigned int destRows = dest.getRows();
578  unsigned int destCols = dest.getCols();
579 
580  if (src.type() == CV_16UC1) {
581  if (src.isContinuous()) {
582  memcpy(dest.bitmap, src.data, static_cast<size_t>(src.rows * src.cols) * sizeof(uint16_t));
583  }
584  else {
585  if (flip) {
586  for (unsigned int i = 0; i < destRows; ++i) {
587  memcpy(dest.bitmap + (i * destCols), src.data + ((destRows - i - 1) * src.step1() * sizeof(uint16_t)), static_cast<size_t>(src.step));
588  }
589  }
590  else {
591  for (unsigned int i = 0; i < destRows; ++i) {
592  memcpy(dest.bitmap + (i * destCols), src.data + (i * src.step1() * sizeof(uint16_t)), static_cast<size_t>(src.step));
593  }
594  }
595  }
596  }
597  else {
598  throw(vpException(vpException::fatalError, "cv:Mat format not supported for conversion into vpImage<uint16_t>"));
599  }
600 }
601 
609 void vpImageConvert::convert(const cv::Mat &src, vpImage<vpRGBf> &dest, bool flip)
610 {
611  dest.resize(static_cast<unsigned int>(src.rows), static_cast<unsigned int>(src.cols));
612  unsigned int destRows = dest.getRows();
613  unsigned int destCols = dest.getCols();
614 
615  if (src.type() == CV_32FC3) {
616  vpRGBf rgbVal;
617  for (unsigned int i = 0; i < destRows; ++i)
618  for (unsigned int j = 0; j < destCols; ++j) {
619  cv::Vec3f tmp = src.at<cv::Vec3f>(static_cast<int>(i), static_cast<int>(j));
620  rgbVal.R = tmp[2];
621  rgbVal.G = tmp[1];
622  rgbVal.B = tmp[0];
623  if (flip) {
624  dest[destRows - i - 1][j] = rgbVal;
625  }
626  else {
627  dest[i][j] = rgbVal;
628  }
629  }
630  }
631  else {
632  throw vpException(vpException::badValue, "cv::Mat type is not supported!");
633  }
634 }
635 
672 void vpImageConvert::convert(const vpImage<vpRGBa> &src, cv::Mat &dest)
673 {
674  cv::Mat vpToMat(static_cast<int>(src.getRows()), static_cast<int>(src.getCols()), CV_8UC4, (void *)src.bitmap);
675  cv::cvtColor(vpToMat, dest, cv::COLOR_RGBA2BGR);
676 }
677 
716 void vpImageConvert::convert(const vpImage<unsigned char> &src, cv::Mat &dest, bool copyData)
717 {
718  if (copyData) {
719  cv::Mat tmpMap(static_cast<int>(src.getRows()), static_cast<int>(src.getCols()), CV_8UC1, (void *)src.bitmap);
720  dest = tmpMap.clone();
721  }
722  else {
723  dest = cv::Mat(static_cast<int>(src.getRows()), static_cast<int>(src.getCols()), CV_8UC1, (void *)src.bitmap);
724  }
725 }
726 
727 void vpImageConvert::convert(const vpImage<float> &src, cv::Mat &dest, bool copyData)
728 {
729  if (copyData) {
730  cv::Mat tmpMap(static_cast<int>(src.getRows()), static_cast<int>(src.getCols()), CV_32FC1, (void *)src.bitmap);
731  dest = tmpMap.clone();
732  }
733  else {
734  dest = cv::Mat(static_cast<int>(src.getRows()), static_cast<int>(src.getCols()), CV_32FC1, (void *)src.bitmap);
735  }
736 }
737 
738 void vpImageConvert::convert(const vpImage<double> &src, cv::Mat &dest, bool copyData)
739 {
740  unsigned int nbRows = src.getRows();
741  unsigned int nbCols = src.getCols();
742  vpImage<float> I_float(nbRows, nbCols);
743  for (unsigned int i = 0; i < nbRows; ++i) {
744  for (unsigned int j = 0; j < nbCols; ++j) {
745  I_float[i][j] = static_cast<float>(src[i][j]);
746  }
747  }
748  convert(I_float, dest, copyData);
749 }
750 
751 void vpImageConvert::convert(const vpImage<vpRGBf> &src, cv::Mat &dest)
752 {
753  cv::Mat vpToMat(static_cast<int>(src.getRows()), static_cast<int>(src.getCols()), CV_32FC3, (void *)src.bitmap);
754  cv::cvtColor(vpToMat, dest, cv::COLOR_RGB2BGR);
755 }
756 
757 #endif
758 
759 #ifdef VISP_HAVE_YARP
793 void vpImageConvert::convert(const vpImage<unsigned char> &src, yarp::sig::ImageOf<yarp::sig::PixelMono> *dest,
794  bool copyData)
795 {
796  if (copyData) {
797  dest->resize(src.getWidth(), src.getHeight());
798  memcpy(dest->getRawImage(), src.bitmap, src.getHeight() * src.getWidth());
799  }
800  else {
801  dest->setExternal(src.bitmap, static_cast<int>(src.getCols()), static_cast<int>(src.getRows()));
802  }
803 }
804 
843 void vpImageConvert::convert(const yarp::sig::ImageOf<yarp::sig::PixelMono> *src, vpImage<unsigned char> &dest,
844  bool copyData)
845 {
846  dest.resize(src->height(), src->width());
847  if (copyData) {
848  memcpy(dest.bitmap, src->getRawImage(), src->height() * src->width() * sizeof(yarp::sig::PixelMono));
849  }
850  else {
851  dest.bitmap = src->getRawImage();
852  }
853 }
854 
889 void vpImageConvert::convert(const vpImage<vpRGBa> &src, yarp::sig::ImageOf<yarp::sig::PixelRgba> *dest, bool copyData)
890 {
891  if (copyData) {
892  dest->resize(src.getWidth(), src.getHeight());
893  memcpy(dest->getRawImage(), src.bitmap, src.getHeight() * src.getWidth() * sizeof(vpRGBa));
894  }
895  else {
896  dest->setExternal(src.bitmap, static_cast<int>(src.getCols()), static_cast<int>(src.getRows()));
897  }
898 }
899 
938 void vpImageConvert::convert(const yarp::sig::ImageOf<yarp::sig::PixelRgba> *src, vpImage<vpRGBa> &dest, bool copyData)
939 {
940  dest.resize(src->height(), src->width());
941  if (copyData)
942  memcpy(dest.bitmap, src->getRawImage(), src->height() * src->width() * sizeof(yarp::sig::PixelRgba));
943  else {
944  dest.bitmap = static_cast<vpRGBa *>(src->getRawImage());
945  }
946 }
947 
980 void vpImageConvert::convert(const vpImage<vpRGBa> &src, yarp::sig::ImageOf<yarp::sig::PixelRgb> *dest)
981 {
982  const unsigned int srcRows = src.getRows(), srcWidth = src.getWidth();
983  dest->resize(src.getWidth(), src.getHeight());
984  for (unsigned int i = 0; i < srcRows; ++i) {
985  for (unsigned int j = 0; j < srcWidth; ++j) {
986  dest->pixel(j, i).r = src[i][j].R;
987  dest->pixel(j, i).g = src[i][j].G;
988  dest->pixel(j, i).b = src[i][j].B;
989  }
990  }
991 }
992 
1031 void vpImageConvert::convert(const yarp::sig::ImageOf<yarp::sig::PixelRgb> *src, vpImage<vpRGBa> &dest)
1032 {
1033  const int srcHeight = src->height(), srcWidth = src->width();
1034  dest.resize(srcHeight, srcWidth);
1035  for (int i = 0; i < srcHeight; ++i) {
1036  for (int j = 0; j < srcWidth; ++j) {
1037  dest[i][j].R = src->pixel(j, i).r;
1038  dest[i][j].G = src->pixel(j, i).g;
1039  dest[i][j].B = src->pixel(j, i).b;
1040  dest[i][j].A = vpRGBa::alpha_default;
1041  }
1042  }
1043 }
1044 
1045 #endif
1046 
1056 void vpImageConvert::RGBToRGBa(unsigned char *rgb, unsigned char *rgba, unsigned int size)
1057 {
1058  RGBToRGBa(rgb, rgba, size, 1, false);
1059 }
1060 
1076 void vpImageConvert::RGBToRGBa(unsigned char *rgb, unsigned char *rgba, unsigned int width, unsigned int height,
1077  bool flip)
1078 {
1079 #if defined(VISP_HAVE_SIMDLIB)
1080  if (!flip) {
1081  SimdBgrToBgra(rgb, width, height, width * 3, rgba, width * 4, vpRGBa::alpha_default);
1082  }
1083  else {
1084 #endif
1085  // if we have to flip the image, we start from the end last scanline so the
1086  // step is negative
1087  int lineStep = flip ? -static_cast<int>(width * 3) : static_cast<int>(width * 3);
1088 
1089  // starting source address = last line if we need to flip the image
1090  unsigned char *src = flip ? (rgb + (width * height * 3) + lineStep) : rgb;
1091 
1092  unsigned int j = 0;
1093  unsigned int i = 0;
1094 
1095  for (i = 0; i < height; ++i) {
1096  unsigned char *line = src;
1097  for (j = 0; j < width; ++j) {
1098  *rgba++ = *(++line);
1099  *rgba++ = *(++line);
1100  *rgba++ = *(++line);
1101  *rgba++ = vpRGBa::alpha_default;
1102  }
1103  // go to the next line
1104  src += lineStep;
1105  }
1106 #if defined(VISP_HAVE_SIMDLIB)
1107  }
1108 #endif
1109 }
1110 
1123 void vpImageConvert::RGBaToRGB(unsigned char *rgba, unsigned char *rgb, unsigned int size)
1124 {
1125 #if defined(VISP_HAVE_SIMDLIB)
1126  SimdBgraToBgr(rgba, size, 1, size * 4, rgb, size * 3);
1127 #else
1128  unsigned char *pt_input = rgba;
1129  unsigned char *pt_end = rgba + (4 * size);
1130  unsigned char *pt_output = rgb;
1131 
1132  while (pt_input != pt_end) {
1133  *(++pt_output) = *(++pt_input); // R
1134  *(++pt_output) = *(++pt_input); // G
1135  *(++pt_output) = *(++pt_input); // B
1136  pt_input++;
1137  }
1138 #endif
1139 }
1140 
1153 void vpImageConvert::RGBToGrey(unsigned char *rgb, unsigned char *grey, unsigned int size)
1154 {
1155  RGBToGrey(rgb, grey, size, 1, false);
1156 }
1157 
1171 void vpImageConvert::RGBToGrey(unsigned char *rgb, unsigned char *grey, unsigned int width, unsigned int height,
1172  bool flip)
1173 {
1174 #if defined(VISP_HAVE_SIMDLIB)
1175  if (!flip) {
1176  SimdRgbToGray(rgb, width, height, width * 3, grey, width);
1177  }
1178  else {
1179 #endif
1180  // if we have to flip the image, we start from the end last scanline so
1181  // the step is negative
1182  int lineStep = flip ? -static_cast<int>(width * 3) : static_cast<int>(width * 3);
1183 
1184  // starting source address = last line if we need to flip the image
1185  unsigned char *src = flip ? (rgb + (width * height * 3) + lineStep) : rgb;
1186 
1187  unsigned int j = 0;
1188  unsigned int i = 0;
1189 
1190  unsigned r, g, b;
1191 
1192  for (i = 0; i < height; ++i) {
1193  unsigned char *line = src;
1194  for (j = 0; j < width; ++j) {
1195  r = *(++line);
1196  g = *(++line);
1197  b = *(++line);
1198  *grey++ = static_cast<unsigned char>((0.2126 * r) + (0.7152 * g) + (0.0722 * b));
1199  }
1200 
1201  // go to the next line
1202  src += lineStep;
1203  }
1204 #if defined(VISP_HAVE_SIMDLIB)
1205  }
1206 #endif
1207 }
1208 
1224 void vpImageConvert::RGBaToGrey(unsigned char *rgba, unsigned char *grey, unsigned int width, unsigned int height,
1225  unsigned int
1226 #if defined(_OPENMP)
1227  nThreads
1228 #endif
1229 )
1230 {
1231 #if defined(VISP_HAVE_SIMDLIB)
1232  const int heightAsInt = static_cast<int>(height);
1233 #if defined(_OPENMP)
1234  if (nThreads > 0) {
1235  omp_set_num_threads(static_cast<int>(nThreads));
1236  }
1237 #pragma omp parallel for
1238 #endif
1239  for (int i = 0; i < heightAsInt; ++i) {
1240  SimdRgbaToGray(rgba + (i * width * 4), width, 1, width * 4, grey + (i * width), width);
1241  }
1242 #else
1243 #if defined(_OPENMP)
1244  (void)nThreads;
1245 #endif
1246  vpImageConvert::RGBaToGrey(rgba, grey, width * height);
1247 #endif
1248 }
1249 
1264 void vpImageConvert::RGBaToGrey(unsigned char *rgba, unsigned char *grey, unsigned int size)
1265 {
1266 #if defined(VISP_HAVE_SIMDLIB)
1267  SimdRgbaToGray(rgba, size, 1, size * 4, grey, size);
1268 #else
1269  unsigned char *pt_input = rgba;
1270  unsigned char *pt_end = rgba + (size * 4);
1271  unsigned char *pt_output = grey;
1272 
1273  while (pt_input != pt_end) {
1274  *pt_output = static_cast<unsigned char>((0.2126 * (*pt_input)) + (0.7152 * (*(pt_input + 1))) + (0.0722 * (*(pt_input + 2))));
1275  pt_input += 4;
1276  pt_output++;
1277  }
1278 #endif
1279 }
1280 
1292 void vpImageConvert::GreyToRGBa(unsigned char *grey, unsigned char *rgba, unsigned int width, unsigned int height)
1293 {
1294 #if defined(VISP_HAVE_SIMDLIB)
1295  SimdGrayToBgra(grey, width, height, width, rgba, width * sizeof(vpRGBa), vpRGBa::alpha_default);
1296 #else
1297  vpImageConvert::GreyToRGBa(grey, rgba, width * height);
1298 #endif
1299 }
1300 
1313 void vpImageConvert::GreyToRGBa(unsigned char *grey, unsigned char *rgba, unsigned int size)
1314 {
1315 #if defined(VISP_HAVE_SIMDLIB)
1316  GreyToRGBa(grey, rgba, size, 1);
1317 #else
1318  unsigned char *pt_input = grey;
1319  unsigned char *pt_end = grey + size;
1320  unsigned char *pt_output = rgba;
1321 
1322  while (pt_input != pt_end) {
1323  unsigned char p = *pt_input;
1324  *(pt_output) = p; // R
1325  *(pt_output + 1) = p; // G
1326  *(pt_output + 2) = p; // B
1327  *(pt_output + 3) = vpRGBa::alpha_default; // A
1328 
1329  pt_input++;
1330  pt_output += 4;
1331  }
1332 #endif
1333 }
1334 
1345 void vpImageConvert::GreyToRGB(unsigned char *grey, unsigned char *rgb, unsigned int size)
1346 {
1347 #if defined(VISP_HAVE_SIMDLIB)
1348  SimdGrayToBgr(grey, size, 1, size, rgb, size * 3);
1349 #else
1350  unsigned char *pt_input = grey;
1351  unsigned char *pt_end = grey + size;
1352  unsigned char *pt_output = rgb;
1353 
1354  while (pt_input != pt_end) {
1355  unsigned char p = *pt_input;
1356  *(pt_output) = p; // R
1357  *(pt_output + 1) = p; // G
1358  *(pt_output + 2) = p; // B
1359 
1360  pt_input++;
1361  pt_output += 3;
1362  }
1363 #endif
1364 }
1365 
1381 void vpImageConvert::BGRToRGBa(unsigned char *bgr, unsigned char *rgba, unsigned int width, unsigned int height,
1382  bool flip)
1383 {
1384 #if defined(VISP_HAVE_SIMDLIB)
1385  if (!flip) {
1386  SimdRgbToBgra(bgr, width, height, width * 3, rgba, width * sizeof(vpRGBa), vpRGBa::alpha_default);
1387  }
1388  else {
1389 #endif
1390  // if we have to flip the image, we start from the end last scanline so the
1391  // step is negative
1392  int lineStep = flip ? -static_cast<int>(width * 3) : static_cast<int>(width * 3);
1393 
1394  // starting source address = last line if we need to flip the image
1395  unsigned char *src = flip ? (bgr + (width * height * 3) + lineStep) : bgr;
1396 
1397  for (unsigned int i = 0; i < height; ++i) {
1398  unsigned char *line = src;
1399  for (unsigned int j = 0; j < width; ++j) {
1400  *rgba++ = *(line + 2);
1401  *rgba++ = *(line + 1);
1402  *rgba++ = *(line + 0);
1403  *rgba++ = vpRGBa::alpha_default;
1404 
1405  line += 3;
1406  }
1407  // go to the next line
1408  src += lineStep;
1409  }
1410 #if defined(VISP_HAVE_SIMDLIB)
1411  }
1412 #endif
1413 }
1414 
1429 void vpImageConvert::BGRaToRGBa(unsigned char *bgra, unsigned char *rgba, unsigned int width, unsigned int height,
1430  bool flip)
1431 {
1432 #if defined(VISP_HAVE_SIMDLIB)
1433  if (!flip) {
1434  SimdBgraToRgba(bgra, width, height, width * 4, rgba, width * 4);
1435  }
1436  else {
1437 #endif
1438  // if we have to flip the image, we start from the end last scanline so the
1439  // step is negative
1440  int lineStep = flip ? -static_cast<int>(width * 4) : static_cast<int>(width * 4);
1441 
1442  // starting source address = last line if we need to flip the image
1443  unsigned char *src = flip ? (bgra + (width * height * 4) + lineStep) : bgra;
1444 
1445  for (unsigned int i = 0; i < height; ++i) {
1446  unsigned char *line = src;
1447  for (unsigned int j = 0; j < width; ++j) {
1448  *rgba++ = *(line + 2);
1449  *rgba++ = *(line + 1);
1450  *rgba++ = *(line + 0);
1451  *rgba++ = *(line + 3);
1452 
1453  line += 4;
1454  }
1455  // go to the next line
1456  src += lineStep;
1457  }
1458 #if defined(VISP_HAVE_SIMDLIB)
1459  }
1460 #endif
1461 }
1462 
1477 void vpImageConvert::BGRToGrey(unsigned char *bgr, unsigned char *grey, unsigned int width, unsigned int height,
1478  bool flip,
1479  unsigned int
1480 #if defined(_OPENMP)
1481  nThreads
1482 #endif
1483 )
1484 {
1485 #if defined(VISP_HAVE_SIMDLIB)
1486  const int heightAsInt = static_cast<int>(height);
1487  if (!flip) {
1488 #if defined(_OPENMP)
1489  if (nThreads > 0) {
1490  omp_set_num_threads(static_cast<int>(nThreads));
1491  }
1492 #pragma omp parallel for
1493 #endif
1494  for (int i = 0; i < heightAsInt; ++i) {
1495  SimdBgrToGray(bgr + (i * width * 3), width, 1, width * 3, grey + (i * width), width);
1496  }
1497  }
1498  else {
1499 #endif
1500  // if we have to flip the image, we start from the end last scanline so
1501  // the step is negative
1502  int lineStep = flip ? -static_cast<int>(width * 3) : static_cast<int>(width * 3);
1503 
1504  // starting source address = last line if we need to flip the image
1505  unsigned char *src = flip ? (bgr + (width * height * 3) + lineStep) : bgr;
1506 
1507  for (unsigned int i = 0; i < height; ++i) {
1508  unsigned char *line = src;
1509  for (unsigned int j = 0; j < width; ++j) {
1510  *grey++ = static_cast<unsigned int>((0.2126 * *(line + 2)) + (0.7152 * *(line + 1)) + (0.0722 * *(line + 0)));
1511  line += 3;
1512  }
1513 
1514  // go to the next line
1515  src += lineStep;
1516  }
1517 #if defined(VISP_HAVE_SIMDLIB)
1518  }
1519 #endif
1520 #if !defined(VISP_HAVE_SIMDLIB) && defined(_OPENMP)
1521  (void)nThreads;
1522 #endif
1523 }
1524 
1539 void vpImageConvert::BGRaToGrey(unsigned char *bgra, unsigned char *grey, unsigned int width, unsigned int height,
1540  bool flip,
1541  unsigned int
1542 #if defined(_OPENMP)
1543  nThreads
1544 #endif
1545 )
1546 {
1547 #if defined(VISP_HAVE_SIMDLIB)
1548  if (!flip) {
1549  const int heightAsInt = static_cast<int>(height);
1550 #if defined(_OPENMP)
1551  if (nThreads > 0) {
1552  omp_set_num_threads(static_cast<int>(nThreads));
1553  }
1554 #pragma omp parallel for
1555 #endif
1556  for (int i = 0; i < heightAsInt; ++i) {
1557  SimdBgraToGray(bgra + (i * width * 4), width, 1, width * 4, grey + (i * width), width);
1558  }
1559  }
1560  else {
1561 #endif
1562  // if we have to flip the image, we start from the end last scanline so
1563  // the step is negative
1564  int lineStep = flip ? -static_cast<int>(width * 4) : static_cast<int>(width * 4);
1565 
1566  // starting source address = last line if we need to flip the image
1567  unsigned char *src = flip ? (bgra + (width * height * 4) + lineStep) : bgra;
1568 
1569  for (unsigned int i = 0; i < height; ++i) {
1570  unsigned char *line = src;
1571  for (unsigned int j = 0; j < width; ++j) {
1572  *grey++ = static_cast<unsigned char>((0.2126 * *(line + 2)) + (0.7152 * *(line + 1)) + (0.0722 * *(line + 0)));
1573  line += 4;
1574  }
1575 
1576  // go to the next line
1577  src += lineStep;
1578  }
1579 #if defined(VISP_HAVE_SIMDLIB)
1580  }
1581 #endif
1582 #if !defined(VISP_HAVE_SIMDLIB) && defined(_OPENMP)
1583  (void)nThreads;
1584 #endif
1585 }
1586 
1590 void vpImageConvert::computeYCbCrLUT()
1591 {
1592  if (YCbCrLUTcomputed == false) {
1593  int index = 256;
1594 
1595  while (index--) {
1596 
1597  int aux = index - 128;
1598  vpImageConvert::vpCrr[index] = static_cast<int>((364.6610 * aux) / 256);
1599  vpImageConvert::vpCgb[index] = static_cast<int>((-89.8779 * aux) / 256);
1600  vpImageConvert::vpCgr[index] = static_cast<int>((-185.8154 * aux) / 256);
1601  vpImageConvert::vpCbb[index] = static_cast<int>((460.5724 * aux) / 256);
1602  }
1603 
1604  YCbCrLUTcomputed = true;
1605  }
1606 }
1607 
1629 void vpImageConvert::YCbCrToRGB(unsigned char *ycbcr, unsigned char *rgb, unsigned int size)
1630 {
1631  unsigned char *cbv;
1632  unsigned char *crv;
1633  unsigned char *pt_ycbcr = ycbcr;
1634  unsigned char *pt_rgb = rgb;
1635  cbv = pt_ycbcr + 1;
1636  crv = pt_ycbcr + 3;
1637 
1638  vpImageConvert::computeYCbCrLUT();
1639 
1640  int col = 0;
1641 
1642  while (size--) {
1643  int val_r, val_g, val_b;
1644  if (!(col % 2)) {
1645  cbv = pt_ycbcr + 1;
1646  crv = pt_ycbcr + 3;
1647  }
1648 
1649  val_r = *pt_ycbcr + vpImageConvert::vpCrr[*crv];
1650  val_g = *pt_ycbcr + vpImageConvert::vpCgb[*cbv] + vpImageConvert::vpCgr[*crv];
1651  val_b = *pt_ycbcr + vpImageConvert::vpCbb[*cbv];
1652 
1653  vpDEBUG_TRACE(5, "[%d] R: %d G: %d B: %d\n", size, val_r, val_g, val_b);
1654 
1655  *pt_rgb++ = (val_r < 0) ? 0u : ((val_r > 255) ? 255u : static_cast<unsigned char>(val_r)); // Red component.
1656  *pt_rgb++ = (val_g < 0) ? 0u : ((val_g > 255) ? 255u : static_cast<unsigned char>(val_g)); // Green component.
1657  *pt_rgb++ = (val_b < 0) ? 0u : ((val_b > 255) ? 255u : static_cast<unsigned char>(val_b)); // Blue component.
1658 
1659  pt_ycbcr += 2;
1660  ++col;
1661  }
1662 }
1663 
1689 void vpImageConvert::YCbCrToRGBa(unsigned char *ycbcr, unsigned char *rgba, unsigned int size)
1690 {
1691  unsigned char *cbv;
1692  unsigned char *crv;
1693  unsigned char *pt_ycbcr = ycbcr;
1694  unsigned char *pt_rgba = rgba;
1695  cbv = pt_ycbcr + 1;
1696  crv = pt_ycbcr + 3;
1697 
1698  vpImageConvert::computeYCbCrLUT();
1699 
1700  int col = 0;
1701 
1702  while (size--) {
1703  int val_r, val_g, val_b;
1704  if (!(col % 2)) {
1705  cbv = pt_ycbcr + 1;
1706  crv = pt_ycbcr + 3;
1707  }
1708 
1709  val_r = *pt_ycbcr + vpImageConvert::vpCrr[*crv];
1710  val_g = *pt_ycbcr + vpImageConvert::vpCgb[*cbv] + vpImageConvert::vpCgr[*crv];
1711  val_b = *pt_ycbcr + vpImageConvert::vpCbb[*cbv];
1712 
1713  vpDEBUG_TRACE(5, "[%d] R: %d G: %d B: %d\n", size, val_r, val_g, val_b);
1714 
1715  *pt_rgba++ = (val_r < 0) ? 0u : ((val_r > 255) ? 255u : static_cast<unsigned char>(val_r)); // Red component.
1716  *pt_rgba++ = (val_g < 0) ? 0u : ((val_g > 255) ? 255u : static_cast<unsigned char>(val_g)); // Green component.
1717  *pt_rgba++ = (val_b < 0) ? 0u : ((val_b > 255) ? 255u : static_cast<unsigned char>(val_b)); // Blue component.
1718  *pt_rgba++ = vpRGBa::alpha_default;
1719 
1720  pt_ycbcr += 2;
1721  ++col;
1722  }
1723 }
1724 
1744 void vpImageConvert::YCbCrToGrey(unsigned char *ycbcr, unsigned char *grey, unsigned int size)
1745 {
1746  unsigned int i = 0, j = 0;
1747  const unsigned int doubleSize = size * 2;
1748  while (j < doubleSize) {
1749  grey[i++] = ycbcr[j];
1750  grey[i++] = ycbcr[j + 2];
1751  j += 4;
1752  }
1753 }
1754 
1776 void vpImageConvert::YCrCbToRGB(unsigned char *ycrcb, unsigned char *rgb, unsigned int size)
1777 {
1778  unsigned char *cbv;
1779  unsigned char *crv;
1780  unsigned char *pt_ycbcr = ycrcb;
1781  unsigned char *pt_rgb = rgb;
1782  crv = pt_ycbcr + 1;
1783  cbv = pt_ycbcr + 3;
1784 
1785  vpImageConvert::computeYCbCrLUT();
1786 
1787  int col = 0;
1788 
1789  while (size--) {
1790  int val_r, val_g, val_b;
1791  if (!(col % 2)) {
1792  crv = pt_ycbcr + 1;
1793  cbv = pt_ycbcr + 3;
1794  }
1795 
1796  val_r = *pt_ycbcr + vpImageConvert::vpCrr[*crv];
1797  val_g = *pt_ycbcr + vpImageConvert::vpCgb[*cbv] + vpImageConvert::vpCgr[*crv];
1798  val_b = *pt_ycbcr + vpImageConvert::vpCbb[*cbv];
1799 
1800  vpDEBUG_TRACE(5, "[%d] R: %d G: %d B: %d\n", size, val_r, val_g, val_b);
1801 
1802  *pt_rgb++ = (val_r < 0) ? 0u : ((val_r > 255) ? 255u : static_cast<unsigned char>(val_r)); // Red component.
1803  *pt_rgb++ = (val_g < 0) ? 0u : ((val_g > 255) ? 255u : static_cast<unsigned char>(val_g)); // Green component.
1804  *pt_rgb++ = (val_b < 0) ? 0u : ((val_b > 255) ? 255u : static_cast<unsigned char>(val_b)); // Blue component.
1805 
1806  pt_ycbcr += 2;
1807  ++col;
1808  }
1809 }
1810 
1835 void vpImageConvert::YCrCbToRGBa(unsigned char *ycrcb, unsigned char *rgba, unsigned int size)
1836 {
1837  unsigned char *cbv;
1838  unsigned char *crv;
1839  unsigned char *pt_ycbcr = ycrcb;
1840  unsigned char *pt_rgba = rgba;
1841  crv = pt_ycbcr + 1;
1842  cbv = pt_ycbcr + 3;
1843 
1844  vpImageConvert::computeYCbCrLUT();
1845 
1846  int col = 0;
1847 
1848  while (size--) {
1849  int val_r, val_g, val_b;
1850  if (!(col % 2)) {
1851  crv = pt_ycbcr + 1;
1852  cbv = pt_ycbcr + 3;
1853  }
1854 
1855  val_r = *pt_ycbcr + vpImageConvert::vpCrr[*crv];
1856  val_g = *pt_ycbcr + vpImageConvert::vpCgb[*cbv] + vpImageConvert::vpCgr[*crv];
1857  val_b = *pt_ycbcr + vpImageConvert::vpCbb[*cbv];
1858 
1859  vpDEBUG_TRACE(5, "[%d] R: %d G: %d B: %d\n", size, val_r, val_g, val_b);
1860 
1861  *pt_rgba++ = (val_r < 0) ? 0u : ((val_r > 255) ? 255u : static_cast<unsigned char>(val_r)); // Red component.
1862  *pt_rgba++ = (val_g < 0) ? 0u : ((val_g > 255) ? 255u : static_cast<unsigned char>(val_g)); // Green component.
1863  *pt_rgba++ = (val_b < 0) ? 0u : ((val_b > 255) ? 255u : static_cast<unsigned char>(val_b)); // Blue component.
1864  *pt_rgba++ = vpRGBa::alpha_default;
1865 
1866  pt_ycbcr += 2;
1867  ++col;
1868  }
1869 }
1870 
1911 {
1912 #if defined(VISP_HAVE_SIMDLIB)
1913  if (src.getSize() > 0) {
1914  if (pR) {
1915  pR->resize(src.getHeight(), src.getWidth());
1916  }
1917  if (pG) {
1918  pG->resize(src.getHeight(), src.getWidth());
1919  }
1920  if (pB) {
1921  pB->resize(src.getHeight(), src.getWidth());
1922  }
1923  if (pa) {
1924  pa->resize(src.getHeight(), src.getWidth());
1925  }
1926 
1927  unsigned char *ptrR = pR ? pR->bitmap : new unsigned char[src.getSize()];
1928  unsigned char *ptrG = pG ? pG->bitmap : new unsigned char[src.getSize()];
1929  unsigned char *ptrB = pB ? pB->bitmap : new unsigned char[src.getSize()];
1930  unsigned char *ptrA = pa ? pa->bitmap : new unsigned char[src.getSize()];
1931 
1932  SimdDeinterleaveBgra(reinterpret_cast<unsigned char *>(src.bitmap), src.getWidth() * sizeof(vpRGBa), src.getWidth(),
1933  src.getHeight(), ptrR, src.getWidth(), ptrG, src.getWidth(), ptrB, src.getWidth(), ptrA,
1934  src.getWidth());
1935 
1936  if (!pR) {
1937  delete[] ptrR;
1938  }
1939  if (!pG) {
1940  delete[] ptrG;
1941  }
1942  if (!pB) {
1943  delete[] ptrB;
1944  }
1945  if (!pa) {
1946  delete[] ptrA;
1947  }
1948  }
1949 #else
1950  size_t n = src.getNumberOfPixel();
1951  unsigned int height = src.getHeight();
1952  unsigned int width = src.getWidth();
1953  unsigned char *input;
1954  unsigned char *dst;
1955 
1956  vpImage<unsigned char> *tabChannel[4];
1957 
1958  /* incrsrc[0] = 0; //init
1959  incrsrc[1] = 0; //step after the first used channel
1960  incrsrc[2] = 0; //step after the second used channel
1961  incrsrc[3] = 0;
1962  incrsrc[4] = 0;
1963  */
1964  tabChannel[0] = pR;
1965  tabChannel[1] = pG;
1966  tabChannel[2] = pB;
1967  tabChannel[3] = pa;
1968 
1969  size_t i; /* ordre */
1970  for (unsigned int j = 0; j < 4; ++j) {
1971  if (tabChannel[j] != nullptr) {
1972  if ((tabChannel[j]->getHeight() != height) || (tabChannel[j]->getWidth() != width)) {
1973  tabChannel[j]->resize(height, width);
1974  }
1975  dst = (unsigned char *)tabChannel[j]->bitmap;
1976 
1977  input = (unsigned char *)src.bitmap + j;
1978  i = 0;
1979  // optimization
1980  if (n >= 4) {
1981  n -= 3;
1982  for (; i < n; i += 4) {
1983  *dst = *input;
1984  input += 4;
1985  dst++;
1986  *dst = *input;
1987  input += 4;
1988  dst++;
1989  *dst = *input;
1990  input += 4;
1991  dst++;
1992  *dst = *input;
1993  input += 4;
1994  dst++;
1995  }
1996  n += 3;
1997  }
1998 
1999  for (; i < n; ++i) {
2000  *dst = *input;
2001  input += 4;
2002  dst++;
2003  }
2004  }
2005  }
2006 #endif
2007 }
2008 
2021 {
2022  // Check if the input channels have all the same dimensions
2023  std::map<unsigned int, unsigned int> mapOfWidths, mapOfHeights;
2024  if (R != nullptr) {
2025  ++mapOfWidths[R->getWidth()];
2026  ++mapOfHeights[R->getHeight()];
2027  }
2028 
2029  if (G != nullptr) {
2030  ++mapOfWidths[G->getWidth()];
2031  ++mapOfHeights[G->getHeight()];
2032  }
2033 
2034  if (B != nullptr) {
2035  ++mapOfWidths[B->getWidth()];
2036  ++mapOfHeights[B->getHeight()];
2037  }
2038 
2039  if (a != nullptr) {
2040  ++mapOfWidths[a->getWidth()];
2041  ++mapOfHeights[a->getHeight()];
2042  }
2043 
2044  if ((mapOfWidths.size() == 1) && (mapOfHeights.size() == 1)) {
2045  unsigned int width = mapOfWidths.begin()->first;
2046  unsigned int height = mapOfHeights.begin()->first;
2047 
2048  RGBa.resize(height, width);
2049 
2050 
2051 #if defined(VISP_HAVE_SIMDLIB)
2052  if ((R != nullptr) && (G != nullptr) && (B != nullptr) && (a != nullptr)) {
2053  SimdInterleaveBgra(R->bitmap, width, G->bitmap, width, B->bitmap, width, a->bitmap, width, width, height,
2054  reinterpret_cast<uint8_t *>(RGBa.bitmap), width * sizeof(vpRGBa));
2055  }
2056  else {
2057 #endif
2058  unsigned int size = width * height;
2059  for (unsigned int i = 0; i < size; ++i) {
2060  if (R != nullptr) {
2061  RGBa.bitmap[i].R = R->bitmap[i];
2062  }
2063 
2064  if (G != nullptr) {
2065  RGBa.bitmap[i].G = G->bitmap[i];
2066  }
2067 
2068  if (B != nullptr) {
2069  RGBa.bitmap[i].B = B->bitmap[i];
2070  }
2071 
2072  if (a != nullptr) {
2073  RGBa.bitmap[i].A = a->bitmap[i];
2074  }
2075  }
2076 #if defined(VISP_HAVE_SIMDLIB)
2077  }
2078 #endif
2079  }
2080  else {
2081  throw vpException(vpException::dimensionError, "Mismatched dimensions!");
2082  }
2083 }
2084 
2095 void vpImageConvert::MONO16ToGrey(unsigned char *grey16, unsigned char *grey, unsigned int size)
2096 {
2097  int i = (static_cast<int>(size) * 2) - 1;
2098  int j = static_cast<int>(size) - 1;
2099 
2100  while (i >= 0) {
2101  int y = grey16[i--];
2102  grey[j--] = static_cast<unsigned char>((y + (grey16[i] * 256)) / 256);
2103  --i;
2104  }
2105 }
2106 
2118 void vpImageConvert::MONO16ToRGBa(unsigned char *grey16, unsigned char *rgba, unsigned int size)
2119 {
2120  int i = (static_cast<int>(size) * 2) - 1;
2121  int j = (static_cast<int>(size) * 4) - 1;
2122 
2123  while (i >= 0) {
2124  int y = grey16[i--];
2125  unsigned char v = static_cast<unsigned char>((y + (grey16[i] * 256)) / 256);
2126  --i;
2127  rgba[j--] = vpRGBa::alpha_default;
2128  rgba[j--] = v;
2129  rgba[j--] = v;
2130  rgba[j--] = v;
2131  }
2132 }
2133 
2134 // Bilinear
2135 
2148 void vpImageConvert::demosaicBGGRToRGBaBilinear(const uint8_t *bggr, uint8_t *rgba, unsigned int width,
2149  unsigned int height, unsigned int nThreads)
2150 {
2151  demosaicBGGRToRGBaBilinearTpl(bggr, rgba, width, height, nThreads);
2152 }
2153 
2166 void vpImageConvert::demosaicBGGRToRGBaBilinear(const uint16_t *bggr, uint16_t *rgba, unsigned int width,
2167  unsigned int height, unsigned int nThreads)
2168 {
2169  demosaicBGGRToRGBaBilinearTpl(bggr, rgba, width, height, nThreads);
2170 }
2171 
2184 void vpImageConvert::demosaicGBRGToRGBaBilinear(const uint8_t *gbrg, uint8_t *rgba, unsigned int width,
2185  unsigned int height, unsigned int nThreads)
2186 {
2187  demosaicGBRGToRGBaBilinearTpl(gbrg, rgba, width, height, nThreads);
2188 }
2189 
2202 void vpImageConvert::demosaicGBRGToRGBaBilinear(const uint16_t *gbrg, uint16_t *rgba, unsigned int width,
2203  unsigned int height, unsigned int nThreads)
2204 {
2205  demosaicGBRGToRGBaBilinearTpl(gbrg, rgba, width, height, nThreads);
2206 }
2207 
2220 void vpImageConvert::demosaicGRBGToRGBaBilinear(const uint8_t *grbg, uint8_t *rgba, unsigned int width,
2221  unsigned int height, unsigned int nThreads)
2222 {
2223  demosaicGRBGToRGBaBilinearTpl(grbg, rgba, width, height, nThreads);
2224 }
2225 
2238 void vpImageConvert::demosaicGRBGToRGBaBilinear(const uint16_t *grbg, uint16_t *rgba, unsigned int width,
2239  unsigned int height, unsigned int nThreads)
2240 {
2241  demosaicGRBGToRGBaBilinearTpl(grbg, rgba, width, height, nThreads);
2242 }
2243 
2256 void vpImageConvert::demosaicRGGBToRGBaBilinear(const uint8_t *rggb, uint8_t *rgba, unsigned int width,
2257  unsigned int height, unsigned int nThreads)
2258 {
2259  demosaicRGGBToRGBaBilinearTpl(rggb, rgba, width, height, nThreads);
2260 }
2261 
2274 void vpImageConvert::demosaicRGGBToRGBaBilinear(const uint16_t *rggb, uint16_t *rgba, unsigned int width,
2275  unsigned int height, unsigned int nThreads)
2276 {
2277  demosaicRGGBToRGBaBilinearTpl(rggb, rgba, width, height, nThreads);
2278 }
2279 
2280 // Malvar
2281 
2294 void vpImageConvert::demosaicBGGRToRGBaMalvar(const uint8_t *bggr, uint8_t *rgba, unsigned int width,
2295  unsigned int height, unsigned int nThreads)
2296 {
2297  demosaicBGGRToRGBaMalvarTpl(bggr, rgba, width, height, nThreads);
2298 }
2299 
2312 void vpImageConvert::demosaicBGGRToRGBaMalvar(const uint16_t *bggr, uint16_t *rgba, unsigned int width,
2313  unsigned int height, unsigned int nThreads)
2314 {
2315  demosaicBGGRToRGBaMalvarTpl(bggr, rgba, width, height, nThreads);
2316 }
2317 
2330 void vpImageConvert::demosaicGBRGToRGBaMalvar(const uint8_t *gbrg, uint8_t *rgba, unsigned int width,
2331  unsigned int height, unsigned int nThreads)
2332 {
2333  demosaicGBRGToRGBaMalvarTpl(gbrg, rgba, width, height, nThreads);
2334 }
2335 
2348 void vpImageConvert::demosaicGBRGToRGBaMalvar(const uint16_t *gbrg, uint16_t *rgba, unsigned int width,
2349  unsigned int height, unsigned int nThreads)
2350 {
2351  demosaicGBRGToRGBaMalvarTpl(gbrg, rgba, width, height, nThreads);
2352 }
2353 
2366 void vpImageConvert::demosaicGRBGToRGBaMalvar(const uint8_t *grbg, uint8_t *rgba, unsigned int width,
2367  unsigned int height, unsigned int nThreads)
2368 {
2369  demosaicGRBGToRGBaMalvarTpl(grbg, rgba, width, height, nThreads);
2370 }
2371 
2384 void vpImageConvert::demosaicGRBGToRGBaMalvar(const uint16_t *grbg, uint16_t *rgba, unsigned int width,
2385  unsigned int height, unsigned int nThreads)
2386 {
2387  demosaicGRBGToRGBaMalvarTpl(grbg, rgba, width, height, nThreads);
2388 }
2389 
2402 void vpImageConvert::demosaicRGGBToRGBaMalvar(const uint8_t *rggb, uint8_t *rgba, unsigned int width,
2403  unsigned int height, unsigned int nThreads)
2404 {
2405  demosaicRGGBToRGBaMalvarTpl(rggb, rgba, width, height, nThreads);
2406 }
2407 
2420 void vpImageConvert::demosaicRGGBToRGBaMalvar(const uint16_t *rggb, uint16_t *rgba, unsigned int width,
2421  unsigned int height, unsigned int nThreads)
2422 {
2423  demosaicRGGBToRGBaMalvarTpl(rggb, rgba, width, height, nThreads);
2424 }
error that can be emitted by ViSP classes.
Definition: vpException.h:59
@ badValue
Used to indicate that a value is not in the allowed range.
Definition: vpException.h:85
@ dimensionError
Bad dimension.
Definition: vpException.h:83
@ fatalError
Fatal error.
Definition: vpException.h:84
static void MONO16ToGrey(unsigned char *grey16, unsigned char *grey, unsigned int size)
static void demosaicBGGRToRGBaBilinear(const uint8_t *bggr, uint8_t *rgba, unsigned int width, unsigned int height, unsigned int nThreads=0)
static void demosaicGRBGToRGBaBilinear(const uint8_t *grbg, uint8_t *rgba, unsigned int width, unsigned int height, unsigned int nThreads=0)
static void demosaicGRBGToRGBaMalvar(const uint8_t *grbg, uint8_t *rgba, unsigned int width, unsigned int height, unsigned int nThreads=0)
static void demosaicGBRGToRGBaMalvar(const uint8_t *gbrg, uint8_t *rgba, unsigned int width, unsigned int height, unsigned int nThreads=0)
static void merge(const vpImage< unsigned char > *R, const vpImage< unsigned char > *G, const vpImage< unsigned char > *B, const vpImage< unsigned char > *a, vpImage< vpRGBa > &RGBa)
static void demosaicBGGRToRGBaMalvar(const uint8_t *bggr, uint8_t *rgba, unsigned int width, unsigned int height, unsigned int nThreads=0)
static void demosaicGBRGToRGBaBilinear(const uint8_t *gbrg, uint8_t *rgba, unsigned int width, unsigned int height, unsigned int nThreads=0)
static void YCbCrToGrey(unsigned char *ycbcr, unsigned char *grey, unsigned int size)
static void split(const vpImage< vpRGBa > &src, vpImage< unsigned char > *pR, vpImage< unsigned char > *pG, vpImage< unsigned char > *pB, vpImage< unsigned char > *pa=nullptr)
static void YCrCbToRGB(unsigned char *ycrcb, unsigned char *rgb, unsigned int size)
static void YCbCrToRGBa(unsigned char *ycbcr, unsigned char *rgb, unsigned int size)
static void createDepthHistogram(const vpImage< uint16_t > &src_depth, vpImage< vpRGBa > &dest_rgba)
static void demosaicRGGBToRGBaMalvar(const uint8_t *rggb, uint8_t *rgba, unsigned int width, unsigned int height, unsigned int nThreads=0)
static void GreyToRGBa(unsigned char *grey, unsigned char *rgba, unsigned int width, unsigned int height)
static void convert(const vpImage< unsigned char > &src, vpImage< vpRGBa > &dest)
static void MONO16ToRGBa(unsigned char *grey16, unsigned char *rgba, unsigned int size)
static void RGBToGrey(unsigned char *rgb, unsigned char *grey, unsigned int width, unsigned int height, bool flip=false)
static void RGBaToGrey(unsigned char *rgba, unsigned char *grey, unsigned int width, unsigned int height, unsigned int nThreads=0)
static void GreyToRGB(unsigned char *grey, unsigned char *rgb, unsigned int size)
static void YCrCbToRGBa(unsigned char *ycrcb, unsigned char *rgb, unsigned int size)
static void RGBToRGBa(unsigned char *rgb, unsigned char *rgba, unsigned int size)
static void YCbCrToRGB(unsigned char *ycbcr, unsigned char *rgb, unsigned int size)
static void BGRaToGrey(unsigned char *bgra, unsigned char *grey, unsigned int width, unsigned int height, bool flip=false, unsigned int nThreads=0)
static void BGRToGrey(unsigned char *bgr, unsigned char *grey, unsigned int width, unsigned int height, bool flip=false, unsigned int nThreads=0)
static void BGRToRGBa(unsigned char *bgr, unsigned char *rgba, unsigned int width, unsigned int height, bool flip=false)
static void demosaicRGGBToRGBaBilinear(const uint8_t *rggb, uint8_t *rgba, unsigned int width, unsigned int height, unsigned int nThreads=0)
static void BGRaToRGBa(unsigned char *bgra, unsigned char *rgba, unsigned int width, unsigned int height, bool flip=false)
static void RGBaToRGB(unsigned char *rgba, unsigned char *rgb, unsigned int size)
unsigned int getWidth() const
Definition: vpImage.h:245
void resize(unsigned int h, unsigned int w)
resize the image : Image initialization
Definition: vpImage.h:783
unsigned int getNumberOfPixel() const
Definition: vpImage.h:206
unsigned int getSize() const
Definition: vpImage.h:224
unsigned int getCols() const
Definition: vpImage.h:175
Type * bitmap
points toward the bitmap
Definition: vpImage.h:139
unsigned int getHeight() const
Definition: vpImage.h:184
unsigned int getRows() const
Definition: vpImage.h:215
void getMinMaxValue(Type &min, Type &max, bool onlyFiniteVal=true) const
Look for the minimum and the maximum value within the bitmap.
Definition: vpImage.h:1230
Definition: vpRGBa.h:61
unsigned char B
Blue component.
Definition: vpRGBa.h:139
unsigned char R
Red component.
Definition: vpRGBa.h:137
unsigned char G
Green component.
Definition: vpRGBa.h:138
@ alpha_default
Definition: vpRGBa.h:63
unsigned char A
Additionnal component.
Definition: vpRGBa.h:140
Definition: vpRGBf.h:57
float B
Blue component.
Definition: vpRGBf.h:126
float G
Green component.
Definition: vpRGBf.h:125
float R
Red component.
Definition: vpRGBf.h:124
#define vpDEBUG_TRACE
Definition: vpDebug.h:473