Visual Servoing Platform  version 3.6.1 under development (2024-12-04)
vpImageConvert.cpp
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 #include <map>
40 #include <sstream>
41 
42 #if defined(_OPENMP)
43 #include <omp.h>
44 #endif
45 
46 
47 #include <visp3/core/vpConfig.h>
48 
49 #ifndef VISP_SKIP_BAYER_CONVERSION
50 #include "private/vpBayerConversion.h"
51 #endif
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 BEGIN_VISP_NAMESPACE
59 bool vpImageConvert::YCbCrLUTcomputed = false;
60 int vpImageConvert::vpCrr[256];
61 int vpImageConvert::vpCgb[256];
62 int vpImageConvert::vpCgr[256];
63 int vpImageConvert::vpCbb[256];
64 
74 {
75  dest.resize(src.getHeight(), src.getWidth());
76 
77  GreyToRGBa(src.bitmap, reinterpret_cast<unsigned char *>(dest.bitmap), src.getWidth(), src.getHeight());
78 }
79 
89 void vpImageConvert::convert(const vpImage<vpRGBa> &src, vpImage<unsigned char> &dest, unsigned int nThreads)
90 {
91  dest.resize(src.getHeight(), src.getWidth());
92 
93  RGBaToGrey(reinterpret_cast<unsigned char *>(src.bitmap), dest.bitmap, src.getWidth(), src.getHeight(), nThreads);
94 }
95 
103 {
104  dest.resize(src.getHeight(), src.getWidth());
105  unsigned int max_xy = src.getWidth() * src.getHeight();
106  float min, max;
107 
108  src.getMinMaxValue(min, max);
109 
110  const unsigned char var_uc_255 = 255;
111  for (unsigned int i = 0; i < max_xy; ++i) {
112  float val = 255.f * ((src.bitmap[i] - min) / (max - min));
113  if (val < 0) {
114  dest.bitmap[i] = 0;
115  }
116  else if (val > 255.f) {
117  dest.bitmap[i] = var_uc_255;
118  }
119  else {
120  dest.bitmap[i] = static_cast<unsigned char>(val);
121  }
122  }
123 }
124 
132 {
133  const unsigned int srcHeight = src.getHeight(), srcWidth = src.getWidth();
134  dest.resize(src.getHeight(), src.getWidth());
135  vpRGBf min, max;
136  src.getMinMaxValue(min, max);
137 
138  const unsigned int val_3 = 3;
139  const unsigned char var_uc_255 = 255;
140  for (unsigned int i = 0; i < srcHeight; ++i) {
141  for (unsigned int j = 0; j < srcWidth; ++j) {
142  for (unsigned int c = 0; c < val_3; ++c) {
143  float val = 255.f * ((reinterpret_cast<const float *>(&(src[i][j]))[c] - reinterpret_cast<float *>(&min)[c]) /
144  (reinterpret_cast<float *>(&max)[c] - reinterpret_cast<float *>(&min)[c]));
145  if (val < 0) {
146  reinterpret_cast<unsigned char *>(&(dest[i][j]))[c] = 0;
147  }
148  else if (val > 255.f) {
149  reinterpret_cast<unsigned char *>(&(dest[i][j]))[c] = var_uc_255;
150  }
151  else {
152  reinterpret_cast<unsigned char *>(&(dest[i][j]))[c] = static_cast<unsigned char>(val);
153  }
154  }
155  }
156  }
157 }
158 
165 {
166  const unsigned int srcHeight = src.getHeight(), srcWidth = src.getWidth();
167  const unsigned int srcSize = srcHeight * srcWidth;
168  dest.resize(srcHeight, srcWidth);
169  for (unsigned int i = 0; i < srcSize; ++i) {
170  dest.bitmap[i] = static_cast<float>(src.bitmap[i]);
171  }
172 }
173 
181 {
182  dest.resize(src.getHeight(), src.getWidth());
183  unsigned int max_xy = src.getWidth() * src.getHeight();
184  double min, max;
185 
186  src.getMinMaxValue(min, max);
187 
188  const unsigned char var_uc_255 = 255;
189  for (unsigned int i = 0; i < max_xy; ++i) {
190  double val = 255. * ((src.bitmap[i] - min) / (max - min));
191  if (val < 0) {
192  dest.bitmap[i] = 0;
193  }
194  else if (val > 255.0) {
195  dest.bitmap[i] = var_uc_255;
196  }
197  else {
198  dest.bitmap[i] = static_cast<unsigned char>(val);
199  }
200  }
201 }
202 
209 void vpImageConvert::convert(const vpImage<uint16_t> &src, vpImage<unsigned char> &dest, unsigned char bitshift)
210 {
211  const unsigned int srcSize = src.getSize();
212  dest.resize(src.getHeight(), src.getWidth());
213 
214  for (unsigned int i = 0; i < srcSize; ++i) {
215  dest.bitmap[i] = static_cast<unsigned char>(src.bitmap[i] >> bitshift);
216  }
217 }
218 
225 void vpImageConvert::convert(const vpImage<unsigned char> &src, vpImage<uint16_t> &dest, unsigned char bitshift)
226 {
227  const unsigned int srcSize = src.getSize();
228  dest.resize(src.getHeight(), src.getWidth());
229 
230  for (unsigned int i = 0; i < srcSize; ++i) {
231  dest.bitmap[i] = static_cast<unsigned char>(src.bitmap[i] << bitshift);
232  }
233 }
234 
241 {
242  const unsigned int srcHeight = src.getHeight(), srcWidth = src.getWidth();
243  const unsigned int srcSize = srcHeight * srcWidth;
244  dest.resize(srcHeight, srcWidth);
245  for (unsigned int i = 0; i < srcSize; ++i) {
246  dest.bitmap[i] = static_cast<double>(src.bitmap[i]);
247  }
248 }
249 
258 {
259  vp_createDepthHistogram(src_depth, dest_rgba);
260 }
261 
269 {
270  vp_createDepthHistogram(src_depth, dest_depth);
271 }
272 
281 {
282  vp_createDepthHistogram(src_depth, dest_rgba);
283 }
284 
292 {
293  vp_createDepthHistogram(src_depth, dest_depth);
294 }
295 
305 void vpImageConvert::RGBToRGBa(unsigned char *rgb, unsigned char *rgba, unsigned int size)
306 {
307  RGBToRGBa(rgb, rgba, size, 1, false);
308 }
309 
325 void vpImageConvert::RGBToRGBa(unsigned char *rgb, unsigned char *rgba, unsigned int width, unsigned int height,
326  bool flip)
327 {
328 #if defined(VISP_HAVE_SIMDLIB)
329  if (!flip) {
330  SimdBgrToBgra(rgb, width, height, width * 3, rgba, width * 4, vpRGBa::alpha_default);
331  }
332  else {
333 #endif
334  // if we have to flip the image, we start from the end last scanline so the
335  // step is negative
336  int lineStep = flip ? -static_cast<int>(width * 3) : static_cast<int>(width * 3);
337 
338  // starting source address = last line if we need to flip the image
339  unsigned char *src = flip ? (rgb + (width * height * 3) + lineStep) : rgb;
340 
341  unsigned int j = 0;
342  unsigned int i = 0;
343 
344  for (i = 0; i < height; ++i) {
345  unsigned char *line = src;
346  for (j = 0; j < width; ++j) {
347  *rgba++ = *(++line);
348  *rgba++ = *(++line);
349  *rgba++ = *(++line);
350  *rgba++ = vpRGBa::alpha_default;
351  }
352  // go to the next line
353  src += lineStep;
354  }
355 #if defined(VISP_HAVE_SIMDLIB)
356  }
357 #endif
358 }
359 
372 void vpImageConvert::RGBaToRGB(unsigned char *rgba, unsigned char *rgb, unsigned int size)
373 {
374 #if defined(VISP_HAVE_SIMDLIB)
375  SimdBgraToBgr(rgba, size, 1, size * 4, rgb, size * 3);
376 #else
377  unsigned char *pt_input = rgba;
378  unsigned char *pt_end = rgba + (4 * size);
379  unsigned char *pt_output = rgb;
380 
381  while (pt_input != pt_end) {
382  *(++pt_output) = *(++pt_input); // R
383  *(++pt_output) = *(++pt_input); // G
384  *(++pt_output) = *(++pt_input); // B
385  ++pt_input;
386  }
387 #endif
388 }
389 
402 void vpImageConvert::RGBToGrey(unsigned char *rgb, unsigned char *grey, unsigned int size)
403 {
404  RGBToGrey(rgb, grey, size, 1, false);
405 }
406 
420 void vpImageConvert::RGBToGrey(unsigned char *rgb, unsigned char *grey, unsigned int width, unsigned int height,
421  bool flip)
422 {
423 #if defined(VISP_HAVE_SIMDLIB)
424  if (!flip) {
425  SimdRgbToGray(rgb, width, height, width * 3, grey, width);
426  }
427  else {
428 #endif
429  // if we have to flip the image, we start from the end last scanline so
430  // the step is negative
431  int lineStep = flip ? -static_cast<int>(width * 3) : static_cast<int>(width * 3);
432 
433  // starting source address = last line if we need to flip the image
434  unsigned char *src = flip ? (rgb + (width * height * 3) + lineStep) : rgb;
435 
436  unsigned int j = 0;
437  unsigned int i = 0;
438 
439  unsigned r, g, b;
440 
441  for (i = 0; i < height; ++i) {
442  unsigned char *line = src;
443  for (j = 0; j < width; ++j) {
444  r = *(++line);
445  g = *(++line);
446  b = *(++line);
447  *grey++ = static_cast<unsigned char>((0.2126 * r) + (0.7152 * g) + (0.0722 * b));
448  }
449 
450  // go to the next line
451  src += lineStep;
452  }
453 #if defined(VISP_HAVE_SIMDLIB)
454  }
455 #endif
456 }
457 
473 void vpImageConvert::RGBaToGrey(unsigned char *rgba, unsigned char *grey, unsigned int width, unsigned int height,
474  unsigned int
475 #if defined(_OPENMP)
476  nThreads
477 #endif
478 )
479 {
480 #if defined(VISP_HAVE_SIMDLIB)
481  const int heightAsInt = static_cast<int>(height);
482 #if defined(_OPENMP)
483  if (nThreads > 0) {
484  omp_set_num_threads(static_cast<int>(nThreads));
485  }
486 #pragma omp parallel for
487 #endif
488  for (int i = 0; i < heightAsInt; ++i) {
489  SimdRgbaToGray(rgba + (i * width * 4), width, 1, width * 4, grey + (i * width), width);
490  }
491 #else
492 #if defined(_OPENMP)
493  (void)nThreads;
494 #endif
495  vpImageConvert::RGBaToGrey(rgba, grey, width * height);
496 #endif
497 }
498 
513 void vpImageConvert::RGBaToGrey(unsigned char *rgba, unsigned char *grey, unsigned int size)
514 {
515 #if defined(VISP_HAVE_SIMDLIB)
516  SimdRgbaToGray(rgba, size, 1, size * 4, grey, size);
517 #else
518  const unsigned int val_2 = 2;
519  const unsigned int val_4 = 4;
520  unsigned char *pt_input = rgba;
521  unsigned char *pt_end = rgba + (size * 4);
522  unsigned char *pt_output = grey;
523 
524  while (pt_input != pt_end) {
525  *pt_output = static_cast<unsigned char>((0.2126 * (*pt_input)) + (0.7152 * (*(pt_input + 1))) + (0.0722 * (*(pt_input + val_2))));
526  pt_input += val_4;
527  ++pt_output;
528  }
529 #endif
530 }
531 
543 void vpImageConvert::GreyToRGBa(unsigned char *grey, unsigned char *rgba, unsigned int width, unsigned int height)
544 {
545 #if defined(VISP_HAVE_SIMDLIB)
546  SimdGrayToBgra(grey, width, height, width, rgba, width * sizeof(vpRGBa), vpRGBa::alpha_default);
547 #else
548  vpImageConvert::GreyToRGBa(grey, rgba, width * height);
549 #endif
550 }
551 
564 void vpImageConvert::GreyToRGBa(unsigned char *grey, unsigned char *rgba, unsigned int size)
565 {
566 #if defined(VISP_HAVE_SIMDLIB)
567  GreyToRGBa(grey, rgba, size, 1);
568 #else
569  const unsigned int val_2 = 2;
570  const unsigned int val_3 = 3;
571  const unsigned int val_4 = 4;
572  unsigned char *pt_input = grey;
573  unsigned char *pt_end = grey + size;
574  unsigned char *pt_output = rgba;
575 
576  while (pt_input != pt_end) {
577  unsigned char p = *pt_input;
578  *pt_output = p; // R
579  *(pt_output + 1) = p; // G
580  *(pt_output + val_2) = p; // B
581  *(pt_output + val_3) = vpRGBa::alpha_default; // A
582 
583  ++pt_input;
584  pt_output += val_4;
585  }
586 #endif
587 }
588 
599 void vpImageConvert::GreyToRGB(unsigned char *grey, unsigned char *rgb, unsigned int size)
600 {
601 #if defined(VISP_HAVE_SIMDLIB)
602  SimdGrayToBgr(grey, size, 1, size, rgb, size * 3);
603 #else
604  const unsigned int val_2 = 2;
605  const unsigned int val_3 = 3;
606  unsigned char *pt_input = grey;
607  unsigned char *pt_end = grey + size;
608  unsigned char *pt_output = rgb;
609 
610  while (pt_input != pt_end) {
611  unsigned char p = *pt_input;
612  *pt_output = p; // R
613  *(pt_output + 1) = p; // G
614  *(pt_output + val_2) = p; // B
615 
616  ++pt_input;
617  pt_output += val_3;
618  }
619 #endif
620 }
621 
637 void vpImageConvert::BGRToRGBa(unsigned char *bgr, unsigned char *rgba, unsigned int width, unsigned int height,
638  bool flip)
639 {
640 #if defined(VISP_HAVE_SIMDLIB)
641  if (!flip) {
642  SimdRgbToBgra(bgr, width, height, width * 3, rgba, width * sizeof(vpRGBa), vpRGBa::alpha_default);
643  }
644  else {
645 #endif
646  // if we have to flip the image, we start from the end last scanline so the
647  // step is negative
648  const unsigned int val_2 = 2;
649  const unsigned int val_3 = 3;
650  int lineStep = flip ? -static_cast<int>(width * 3) : static_cast<int>(width * 3);
651 
652  // starting source address = last line if we need to flip the image
653  unsigned char *src = flip ? (bgr + (width * height * 3) + lineStep) : bgr;
654 
655  for (unsigned int i = 0; i < height; ++i) {
656  unsigned char *line = src;
657  for (unsigned int j = 0; j < width; ++j) {
658  *rgba++ = *(line + val_2);
659  *rgba++ = *(line + 1);
660  *rgba++ = *(line + 0);
661  *rgba++ = vpRGBa::alpha_default;
662 
663  line += val_3;
664  }
665  // go to the next line
666  src += lineStep;
667  }
668 #if defined(VISP_HAVE_SIMDLIB)
669  }
670 #endif
671 }
672 
687 void vpImageConvert::BGRaToRGBa(unsigned char *bgra, unsigned char *rgba, unsigned int width, unsigned int height,
688  bool flip)
689 {
690 #if defined(VISP_HAVE_SIMDLIB)
691  if (!flip) {
692  SimdBgraToRgba(bgra, width, height, width * 4, rgba, width * 4);
693  }
694  else {
695 #endif
696  // if we have to flip the image, we start from the end last scanline so the
697  // step is negative
698  const unsigned int val_2 = 2;
699  const unsigned int val_3 = 3;
700  const unsigned int val_4 = 4;
701  int lineStep = flip ? -static_cast<int>(width * 4) : static_cast<int>(width * 4);
702 
703  // starting source address = last line if we need to flip the image
704  unsigned char *src = flip ? (bgra + (width * height * val_4) + lineStep) : bgra;
705 
706  for (unsigned int i = 0; i < height; ++i) {
707  unsigned char *line = src;
708  for (unsigned int j = 0; j < width; ++j) {
709  *rgba++ = *(line + val_2);
710  *rgba++ = *(line + 1);
711  *rgba++ = *(line + 0);
712  *rgba++ = *(line + val_3);
713 
714  line += val_4;
715  }
716  // go to the next line
717  src += lineStep;
718  }
719 #if defined(VISP_HAVE_SIMDLIB)
720  }
721 #endif
722 }
723 
738 void vpImageConvert::BGRToGrey(unsigned char *bgr, unsigned char *grey, unsigned int width, unsigned int height,
739  bool flip,
740  unsigned int
741 #if defined(_OPENMP)
742  nThreads
743 #endif
744 )
745 {
746 #if defined(VISP_HAVE_SIMDLIB)
747  const int heightAsInt = static_cast<int>(height);
748  if (!flip) {
749 #if defined(_OPENMP)
750  if (nThreads > 0) {
751  omp_set_num_threads(static_cast<int>(nThreads));
752  }
753 #pragma omp parallel for
754 #endif
755  for (int i = 0; i < heightAsInt; ++i) {
756  SimdBgrToGray(bgr + (i * width * 3), width, 1, width * 3, grey + (i * width), width);
757  }
758  }
759  else {
760 #endif
761  // if we have to flip the image, we start from the end last scanline so
762  // the step is negative
763  const unsigned int val_2 = 2;
764  const unsigned int val_3 = 3;
765  int lineStep = flip ? -static_cast<int>(width * 3) : static_cast<int>(width * 3);
766 
767  // starting source address = last line if we need to flip the image
768  unsigned char *src = flip ? (bgr + (width * height * 3) + lineStep) : bgr;
769 
770  for (unsigned int i = 0; i < height; ++i) {
771  unsigned char *line = src;
772  for (unsigned int j = 0; j < width; ++j) {
773  *grey++ = static_cast<unsigned int>((0.2126 * *(line + val_2)) + (0.7152 * *(line + 1)) + (0.0722 * *(line + 0)));
774  line += val_3;
775  }
776 
777  // go to the next line
778  src += lineStep;
779  }
780 #if defined(VISP_HAVE_SIMDLIB)
781  }
782 #endif
783 #if !defined(VISP_HAVE_SIMDLIB) && defined(_OPENMP)
784  (void)nThreads;
785 #endif
786 }
787 
802 void vpImageConvert::BGRaToGrey(unsigned char *bgra, unsigned char *grey, unsigned int width, unsigned int height,
803  bool flip,
804  unsigned int
805 #if defined(_OPENMP)
806  nThreads
807 #endif
808 )
809 {
810 #if defined(VISP_HAVE_SIMDLIB)
811  if (!flip) {
812  const int heightAsInt = static_cast<int>(height);
813 #if defined(_OPENMP)
814  if (nThreads > 0) {
815  omp_set_num_threads(static_cast<int>(nThreads));
816  }
817 #pragma omp parallel for
818 #endif
819  for (int i = 0; i < heightAsInt; ++i) {
820  SimdBgraToGray(bgra + (i * width * 4), width, 1, width * 4, grey + (i * width), width);
821  }
822  }
823  else {
824 #endif
825  // if we have to flip the image, we start from the end last scanline so
826  // the step is negative
827  const unsigned int val_2 = 2;
828  const unsigned int val_4 = 4;
829  int lineStep = flip ? -static_cast<int>(width * 4) : static_cast<int>(width * 4);
830 
831  // starting source address = last line if we need to flip the image
832  unsigned char *src = flip ? (bgra + (width * height * 4) + lineStep) : bgra;
833 
834  for (unsigned int i = 0; i < height; ++i) {
835  unsigned char *line = src;
836  for (unsigned int j = 0; j < width; ++j) {
837  *grey++ = static_cast<unsigned char>((0.2126 * *(line + val_2)) + (0.7152 * *(line + 1)) + (0.0722 * *(line + 0)));
838  line += val_4;
839  }
840 
841  // go to the next line
842  src += lineStep;
843  }
844 #if defined(VISP_HAVE_SIMDLIB)
845  }
846 #endif
847 #if !defined(VISP_HAVE_SIMDLIB) && defined(_OPENMP)
848  (void)nThreads;
849 #endif
850 }
851 
855 void vpImageConvert::computeYCbCrLUT()
856 {
857  if (YCbCrLUTcomputed == false) {
858  const int val_256 = 256;
859  int index = 256;
860 
861  while (index--) {
862 
863  int aux = index - 128;
864  vpImageConvert::vpCrr[index] = static_cast<int>((364.6610 * aux) / val_256);
865  vpImageConvert::vpCgb[index] = static_cast<int>((-89.8779 * aux) / val_256);
866  vpImageConvert::vpCgr[index] = static_cast<int>((-185.8154 * aux) / val_256);
867  vpImageConvert::vpCbb[index] = static_cast<int>((460.5724 * aux) / val_256);
868  }
869 
870  YCbCrLUTcomputed = true;
871  }
872 }
873 
895 void vpImageConvert::YCbCrToRGB(unsigned char *ycbcr, unsigned char *rgb, unsigned int size)
896 {
897  const unsigned val_2 = 2;
898  const unsigned val_3 = 3;
899  const int val_255 = 255;
900  const unsigned int val_255u = 255u;
901  unsigned char *cbv;
902  unsigned char *crv;
903  unsigned char *pt_ycbcr = ycbcr;
904  unsigned char *pt_rgb = rgb;
905  cbv = pt_ycbcr + 1;
906  crv = pt_ycbcr + val_3;
907 
908  vpImageConvert::computeYCbCrLUT();
909 
910  int col = 0;
911 
912  while (size--) {
913  int val_r, val_g, val_b;
914  if (!(col % val_2)) {
915  cbv = pt_ycbcr + 1;
916  crv = pt_ycbcr + val_3;
917  }
918 
919  val_r = *pt_ycbcr + vpImageConvert::vpCrr[*crv];
920  val_g = *pt_ycbcr + vpImageConvert::vpCgb[*cbv] + vpImageConvert::vpCgr[*crv];
921  val_b = *pt_ycbcr + vpImageConvert::vpCbb[*cbv];
922 
923  *pt_rgb++ = (val_r < 0) ? 0u : ((val_r > val_255) ? val_255u : static_cast<unsigned char>(val_r)); // Red component.
924  *pt_rgb++ = (val_g < 0) ? 0u : ((val_g > val_255) ? val_255u : static_cast<unsigned char>(val_g)); // Green component.
925  *pt_rgb++ = (val_b < 0) ? 0u : ((val_b > val_255) ? val_255u : static_cast<unsigned char>(val_b)); // Blue component.
926 
927  pt_ycbcr += val_2;
928  ++col;
929  }
930 }
931 
957 void vpImageConvert::YCbCrToRGBa(unsigned char *ycbcr, unsigned char *rgba, unsigned int size)
958 {
959  const unsigned val_2 = 2;
960  const unsigned val_3 = 3;
961  const int val_255 = 255;
962  const unsigned int val_255u = 255u;
963  unsigned char *cbv;
964  unsigned char *crv;
965  unsigned char *pt_ycbcr = ycbcr;
966  unsigned char *pt_rgba = rgba;
967  cbv = pt_ycbcr + 1;
968  crv = pt_ycbcr + val_3;
969 
970  vpImageConvert::computeYCbCrLUT();
971 
972  int col = 0;
973 
974  while (size--) {
975  int val_r, val_g, val_b;
976  if (!(col % val_2)) {
977  cbv = pt_ycbcr + 1;
978  crv = pt_ycbcr + val_3;
979  }
980 
981  val_r = *pt_ycbcr + vpImageConvert::vpCrr[*crv];
982  val_g = *pt_ycbcr + vpImageConvert::vpCgb[*cbv] + vpImageConvert::vpCgr[*crv];
983  val_b = *pt_ycbcr + vpImageConvert::vpCbb[*cbv];
984 
985  *pt_rgba++ = (val_r < 0) ? 0u : ((val_r > val_255) ? val_255u : static_cast<unsigned char>(val_r)); // Red component.
986  *pt_rgba++ = (val_g < 0) ? 0u : ((val_g > val_255) ? val_255u : static_cast<unsigned char>(val_g)); // Green component.
987  *pt_rgba++ = (val_b < 0) ? 0u : ((val_b > val_255) ? val_255u : static_cast<unsigned char>(val_b)); // Blue component.
988  *pt_rgba++ = vpRGBa::alpha_default;
989 
990  pt_ycbcr += val_2;
991  ++col;
992  }
993 }
994 
1014 void vpImageConvert::YCbCrToGrey(unsigned char *ycbcr, unsigned char *grey, unsigned int size)
1015 {
1016  const unsigned val_2 = 2;
1017  const unsigned val_4 = 4;
1018  unsigned int i = 0, j = 0;
1019  const unsigned int doubleSize = size * 2;
1020  while (j < doubleSize) {
1021  grey[i++] = ycbcr[j];
1022  grey[i++] = ycbcr[j + val_2];
1023  j += val_4;
1024  }
1025 }
1026 
1048 void vpImageConvert::YCrCbToRGB(unsigned char *ycrcb, unsigned char *rgb, unsigned int size)
1049 {
1050  const unsigned val_2 = 2;
1051  const unsigned val_3 = 3;
1052  const int val_255 = 255;
1053  const unsigned int val_255u = 255u;
1054  unsigned char *cbv;
1055  unsigned char *crv;
1056  unsigned char *pt_ycbcr = ycrcb;
1057  unsigned char *pt_rgb = rgb;
1058  crv = pt_ycbcr + 1;
1059  cbv = pt_ycbcr + val_3;
1060 
1061  vpImageConvert::computeYCbCrLUT();
1062 
1063  int col = 0;
1064 
1065  while (size--) {
1066  int val_r, val_g, val_b;
1067  if (!(col % val_2)) {
1068  crv = pt_ycbcr + 1;
1069  cbv = pt_ycbcr + val_3;
1070  }
1071 
1072  val_r = *pt_ycbcr + vpImageConvert::vpCrr[*crv];
1073  val_g = *pt_ycbcr + vpImageConvert::vpCgb[*cbv] + vpImageConvert::vpCgr[*crv];
1074  val_b = *pt_ycbcr + vpImageConvert::vpCbb[*cbv];
1075 
1076  *pt_rgb++ = (val_r < 0) ? 0u : ((val_r > val_255) ? val_255u : static_cast<unsigned char>(val_r)); // Red component.
1077  *pt_rgb++ = (val_g < 0) ? 0u : ((val_g > val_255) ? val_255u : static_cast<unsigned char>(val_g)); // Green component.
1078  *pt_rgb++ = (val_b < 0) ? 0u : ((val_b > val_255) ? val_255u : static_cast<unsigned char>(val_b)); // Blue component.
1079 
1080  pt_ycbcr += val_2;
1081  ++col;
1082  }
1083 }
1084 
1109 void vpImageConvert::YCrCbToRGBa(unsigned char *ycrcb, unsigned char *rgba, unsigned int size)
1110 {
1111  const unsigned val_2 = 2;
1112  const unsigned val_3 = 3;
1113  const int val_255 = 255;
1114  const unsigned int val_255u = 255u;
1115  unsigned char *cbv;
1116  unsigned char *crv;
1117  unsigned char *pt_ycbcr = ycrcb;
1118  unsigned char *pt_rgba = rgba;
1119  crv = pt_ycbcr + 1;
1120  cbv = pt_ycbcr + val_3;
1121 
1122  vpImageConvert::computeYCbCrLUT();
1123 
1124  int col = 0;
1125 
1126  while (size--) {
1127  int val_r, val_g, val_b;
1128  if (!(col % val_2)) {
1129  crv = pt_ycbcr + 1;
1130  cbv = pt_ycbcr + val_3;
1131  }
1132 
1133  val_r = *pt_ycbcr + vpImageConvert::vpCrr[*crv];
1134  val_g = *pt_ycbcr + vpImageConvert::vpCgb[*cbv] + vpImageConvert::vpCgr[*crv];
1135  val_b = *pt_ycbcr + vpImageConvert::vpCbb[*cbv];
1136 
1137  *pt_rgba++ = (val_r < 0) ? 0u : ((val_r > val_255) ? val_255u : static_cast<unsigned char>(val_r)); // Red component.
1138  *pt_rgba++ = (val_g < 0) ? 0u : ((val_g > val_255) ? val_255u : static_cast<unsigned char>(val_g)); // Green component.
1139  *pt_rgba++ = (val_b < 0) ? 0u : ((val_b > val_255) ? val_255u : static_cast<unsigned char>(val_b)); // Blue component.
1140  *pt_rgba++ = vpRGBa::alpha_default;
1141 
1142  pt_ycbcr += val_2;
1143  ++col;
1144  }
1145 }
1146 
1191 {
1192 #if defined(VISP_HAVE_SIMDLIB)
1193  if (src.getSize() > 0) {
1194  if (pR) {
1195  pR->resize(src.getHeight(), src.getWidth());
1196  }
1197  if (pG) {
1198  pG->resize(src.getHeight(), src.getWidth());
1199  }
1200  if (pB) {
1201  pB->resize(src.getHeight(), src.getWidth());
1202  }
1203  if (pa) {
1204  pa->resize(src.getHeight(), src.getWidth());
1205  }
1206 
1207  unsigned char *ptrR = pR ? pR->bitmap : new unsigned char[src.getSize()];
1208  unsigned char *ptrG = pG ? pG->bitmap : new unsigned char[src.getSize()];
1209  unsigned char *ptrB = pB ? pB->bitmap : new unsigned char[src.getSize()];
1210  unsigned char *ptrA = pa ? pa->bitmap : new unsigned char[src.getSize()];
1211 
1212  SimdDeinterleaveBgra(reinterpret_cast<unsigned char *>(src.bitmap), src.getWidth() * sizeof(vpRGBa), src.getWidth(),
1213  src.getHeight(), ptrR, src.getWidth(), ptrG, src.getWidth(), ptrB, src.getWidth(), ptrA,
1214  src.getWidth());
1215 
1216  if (!pR) {
1217  delete[] ptrR;
1218  }
1219  if (!pG) {
1220  delete[] ptrG;
1221  }
1222  if (!pB) {
1223  delete[] ptrB;
1224  }
1225  if (!pa) {
1226  delete[] ptrA;
1227  }
1228  }
1229 #else
1230  size_t n = src.getNumberOfPixel();
1231  unsigned int height = src.getHeight();
1232  unsigned int width = src.getWidth();
1233  unsigned char *input;
1234  unsigned char *dst;
1235  const unsigned int index_0 = 0;
1236  const unsigned int index_1 = 1;
1237  const unsigned int index_2 = 2;
1238  const unsigned int index_3 = 3;
1239 
1240  vpImage<unsigned char> *tabChannel[4];
1241 
1242  tabChannel[index_0] = pR;
1243  tabChannel[index_1] = pG;
1244  tabChannel[index_2] = pB;
1245  tabChannel[index_3] = pa;
1246 
1247  size_t i; /* ordre */
1248  const unsigned int val_3 = 3;
1249  const unsigned int val_4 = 4;
1250  for (unsigned int j = 0; j < val_4; ++j) {
1251  if (tabChannel[j] != nullptr) {
1252  if ((tabChannel[j]->getHeight() != height) || (tabChannel[j]->getWidth() != width)) {
1253  tabChannel[j]->resize(height, width);
1254  }
1255  dst = static_cast<unsigned char *>(tabChannel[j]->bitmap);
1256 
1257  input = (unsigned char *)src.bitmap + j;
1258  i = 0;
1259  // optimization
1260  if (n >= val_4) {
1261  n -= val_3;
1262  for (; i < n; i += val_4) {
1263  *dst = *input;
1264  input += val_4;
1265  ++dst;
1266  *dst = *input;
1267  input += val_4;
1268  ++dst;
1269  *dst = *input;
1270  input += val_4;
1271  ++dst;
1272  *dst = *input;
1273  input += val_4;
1274  ++dst;
1275  }
1276  n += val_3;
1277  }
1278 
1279  for (; i < n; ++i) {
1280  *dst = *input;
1281  input += val_4;
1282  ++dst;
1283  }
1284  }
1285  }
1286 #endif
1287 }
1288 
1301 {
1302  // Check if the input channels have all the same dimensions
1303  std::map<unsigned int, unsigned int> mapOfWidths, mapOfHeights;
1304  if (R != nullptr) {
1305  ++mapOfWidths[R->getWidth()];
1306  ++mapOfHeights[R->getHeight()];
1307  }
1308 
1309  if (G != nullptr) {
1310  ++mapOfWidths[G->getWidth()];
1311  ++mapOfHeights[G->getHeight()];
1312  }
1313 
1314  if (B != nullptr) {
1315  ++mapOfWidths[B->getWidth()];
1316  ++mapOfHeights[B->getHeight()];
1317  }
1318 
1319  if (a != nullptr) {
1320  ++mapOfWidths[a->getWidth()];
1321  ++mapOfHeights[a->getHeight()];
1322  }
1323 
1324  if ((mapOfWidths.size() == 1) && (mapOfHeights.size() == 1)) {
1325  unsigned int width = mapOfWidths.begin()->first;
1326  unsigned int height = mapOfHeights.begin()->first;
1327 
1328  RGBa.resize(height, width);
1329 
1330 
1331 #if defined(VISP_HAVE_SIMDLIB)
1332  if ((R != nullptr) && (G != nullptr) && (B != nullptr) && (a != nullptr)) {
1333  SimdInterleaveBgra(R->bitmap, width, G->bitmap, width, B->bitmap, width, a->bitmap, width, width, height,
1334  reinterpret_cast<uint8_t *>(RGBa.bitmap), width * sizeof(vpRGBa));
1335  }
1336  else {
1337 #endif
1338  unsigned int size = width * height;
1339  for (unsigned int i = 0; i < size; ++i) {
1340  if (R != nullptr) {
1341  RGBa.bitmap[i].R = R->bitmap[i];
1342  }
1343 
1344  if (G != nullptr) {
1345  RGBa.bitmap[i].G = G->bitmap[i];
1346  }
1347 
1348  if (B != nullptr) {
1349  RGBa.bitmap[i].B = B->bitmap[i];
1350  }
1351 
1352  if (a != nullptr) {
1353  RGBa.bitmap[i].A = a->bitmap[i];
1354  }
1355  }
1356 #if defined(VISP_HAVE_SIMDLIB)
1357  }
1358 #endif
1359  }
1360  else {
1361  throw vpException(vpException::dimensionError, "Mismatched dimensions!");
1362  }
1363 }
1364 
1375 void vpImageConvert::MONO16ToGrey(unsigned char *grey16, unsigned char *grey, unsigned int size)
1376 {
1377  const int val_256 = 256;
1378  int i = (static_cast<int>(size) * 2) - 1;
1379  int j = static_cast<int>(size) - 1;
1380 
1381  while (i >= 0) {
1382  int y = grey16[i--];
1383  grey[j--] = static_cast<unsigned char>((y + (grey16[i] * val_256)) / val_256);
1384  --i;
1385  }
1386 }
1387 
1399 void vpImageConvert::MONO16ToRGBa(unsigned char *grey16, unsigned char *rgba, unsigned int size)
1400 {
1401  int i = (static_cast<int>(size) * 2) - 1;
1402  int j = (static_cast<int>(size) * 4) - 1;
1403 
1404  while (i >= 0) {
1405  int y = grey16[i--];
1406  unsigned char v = static_cast<unsigned char>((y + (grey16[i] * 256)) / 256);
1407  --i;
1408  rgba[j--] = vpRGBa::alpha_default;
1409  rgba[j--] = v;
1410  rgba[j--] = v;
1411  rgba[j--] = v;
1412  }
1413 }
1414 
1415 // Bilinear
1416 #ifndef VISP_SKIP_BAYER_CONVERSION
1429 void vpImageConvert::demosaicBGGRToRGBaBilinear(const uint8_t *bggr, uint8_t *rgba, unsigned int width,
1430  unsigned int height, unsigned int nThreads)
1431 {
1432  demosaicBGGRToRGBaBilinearTpl(bggr, rgba, width, height, nThreads);
1433 }
1434 
1447 void vpImageConvert::demosaicBGGRToRGBaBilinear(const uint16_t *bggr, uint16_t *rgba, unsigned int width,
1448  unsigned int height, unsigned int nThreads)
1449 {
1450  demosaicBGGRToRGBaBilinearTpl(bggr, rgba, width, height, nThreads);
1451 }
1452 
1465 void vpImageConvert::demosaicGBRGToRGBaBilinear(const uint8_t *gbrg, uint8_t *rgba, unsigned int width,
1466  unsigned int height, unsigned int nThreads)
1467 {
1468  demosaicGBRGToRGBaBilinearTpl(gbrg, rgba, width, height, nThreads);
1469 }
1470 
1483 void vpImageConvert::demosaicGBRGToRGBaBilinear(const uint16_t *gbrg, uint16_t *rgba, unsigned int width,
1484  unsigned int height, unsigned int nThreads)
1485 {
1486  demosaicGBRGToRGBaBilinearTpl(gbrg, rgba, width, height, nThreads);
1487 }
1488 
1501 void vpImageConvert::demosaicGRBGToRGBaBilinear(const uint8_t *grbg, uint8_t *rgba, unsigned int width,
1502  unsigned int height, unsigned int nThreads)
1503 {
1504  demosaicGRBGToRGBaBilinearTpl(grbg, rgba, width, height, nThreads);
1505 }
1506 
1519 void vpImageConvert::demosaicGRBGToRGBaBilinear(const uint16_t *grbg, uint16_t *rgba, unsigned int width,
1520  unsigned int height, unsigned int nThreads)
1521 {
1522  demosaicGRBGToRGBaBilinearTpl(grbg, rgba, width, height, nThreads);
1523 }
1524 
1537 void vpImageConvert::demosaicRGGBToRGBaBilinear(const uint8_t *rggb, uint8_t *rgba, unsigned int width,
1538  unsigned int height, unsigned int nThreads)
1539 {
1540  demosaicRGGBToRGBaBilinearTpl(rggb, rgba, width, height, nThreads);
1541 }
1542 
1555 void vpImageConvert::demosaicRGGBToRGBaBilinear(const uint16_t *rggb, uint16_t *rgba, unsigned int width,
1556  unsigned int height, unsigned int nThreads)
1557 {
1558  demosaicRGGBToRGBaBilinearTpl(rggb, rgba, width, height, nThreads);
1559 }
1560 
1561 // Malvar
1562 
1575 void vpImageConvert::demosaicBGGRToRGBaMalvar(const uint8_t *bggr, uint8_t *rgba, unsigned int width,
1576  unsigned int height, unsigned int nThreads)
1577 {
1578  demosaicBGGRToRGBaMalvarTpl(bggr, rgba, width, height, nThreads);
1579 }
1580 
1593 void vpImageConvert::demosaicBGGRToRGBaMalvar(const uint16_t *bggr, uint16_t *rgba, unsigned int width,
1594  unsigned int height, unsigned int nThreads)
1595 {
1596  demosaicBGGRToRGBaMalvarTpl(bggr, rgba, width, height, nThreads);
1597 }
1598 
1611 void vpImageConvert::demosaicGBRGToRGBaMalvar(const uint8_t *gbrg, uint8_t *rgba, unsigned int width,
1612  unsigned int height, unsigned int nThreads)
1613 {
1614  demosaicGBRGToRGBaMalvarTpl(gbrg, rgba, width, height, nThreads);
1615 }
1616 
1629 void vpImageConvert::demosaicGBRGToRGBaMalvar(const uint16_t *gbrg, uint16_t *rgba, unsigned int width,
1630  unsigned int height, unsigned int nThreads)
1631 {
1632  demosaicGBRGToRGBaMalvarTpl(gbrg, rgba, width, height, nThreads);
1633 }
1634 
1647 void vpImageConvert::demosaicGRBGToRGBaMalvar(const uint8_t *grbg, uint8_t *rgba, unsigned int width,
1648  unsigned int height, unsigned int nThreads)
1649 {
1650  demosaicGRBGToRGBaMalvarTpl(grbg, rgba, width, height, nThreads);
1651 }
1652 
1665 void vpImageConvert::demosaicGRBGToRGBaMalvar(const uint16_t *grbg, uint16_t *rgba, unsigned int width,
1666  unsigned int height, unsigned int nThreads)
1667 {
1668  demosaicGRBGToRGBaMalvarTpl(grbg, rgba, width, height, nThreads);
1669 }
1670 
1683 void vpImageConvert::demosaicRGGBToRGBaMalvar(const uint8_t *rggb, uint8_t *rgba, unsigned int width,
1684  unsigned int height, unsigned int nThreads)
1685 {
1686  demosaicRGGBToRGBaMalvarTpl(rggb, rgba, width, height, nThreads);
1687 }
1688 
1701 void vpImageConvert::demosaicRGGBToRGBaMalvar(const uint16_t *rggb, uint16_t *rgba, unsigned int width,
1702  unsigned int height, unsigned int nThreads)
1703 {
1704  demosaicRGGBToRGBaMalvarTpl(rggb, rgba, width, height, nThreads);
1705 }
1706 #endif // VISP_SKIP_BAYER_CONVERSION
1707 
1708 END_VISP_NAMESPACE
error that can be emitted by ViSP classes.
Definition: vpException.h:60
@ dimensionError
Bad dimension.
Definition: vpException.h:71
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:242
void resize(unsigned int h, unsigned int w)
resize the image : Image initialization
Definition: vpImage.h:544
unsigned int getNumberOfPixel() const
Definition: vpImage.h:203
unsigned int getSize() const
Definition: vpImage.h:221
Type * bitmap
points toward the bitmap
Definition: vpImage.h:135
unsigned int getHeight() const
Definition: vpImage.h:181
void getMinMaxValue(Type &min, Type &max, bool onlyFiniteVal=true) const
Look for the minimum and the maximum value within the bitmap.
Definition: vpRGBa.h:65
unsigned char B
Blue component.
Definition: vpRGBa.h:169
unsigned char R
Red component.
Definition: vpRGBa.h:167
unsigned char G
Green component.
Definition: vpRGBa.h:168
@ alpha_default
Definition: vpRGBa.h:67
unsigned char A
Additionnal component.
Definition: vpRGBa.h:170
Definition: vpRGBf.h:60