Visual Servoing Platform  version 3.6.1 under development (2024-11-21)
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  for (unsigned int i = 0; i < max_xy; ++i) {
111  float val = 255.f * ((src.bitmap[i] - min) / (max - min));
112  if (val < 0) {
113  dest.bitmap[i] = 0;
114  }
115  else if (val > 255) {
116  dest.bitmap[i] = 255;
117  }
118  else {
119  dest.bitmap[i] = static_cast<unsigned char>(val);
120  }
121  }
122 }
123 
131 {
132  const unsigned int srcHeight = src.getHeight(), srcWidth = src.getWidth();
133  dest.resize(src.getHeight(), src.getWidth());
134  vpRGBf min, max;
135  src.getMinMaxValue(min, max);
136 
137  for (unsigned int i = 0; i < srcHeight; ++i) {
138  for (unsigned int j = 0; j < srcWidth; ++j) {
139  for (unsigned int c = 0; c < 3; ++c) {
140  float val = 255.f * ((reinterpret_cast<const float *>(&(src[i][j]))[c] - reinterpret_cast<float *>(&min)[c]) /
141  (reinterpret_cast<float *>(&max)[c] - reinterpret_cast<float *>(&min)[c]));
142  if (val < 0) {
143  reinterpret_cast<unsigned char *>(&(dest[i][j]))[c] = 0;
144  }
145  else if (val > 255) {
146  reinterpret_cast<unsigned char *>(&(dest[i][j]))[c] = 255;
147  }
148  else {
149  reinterpret_cast<unsigned char *>(&(dest[i][j]))[c] = static_cast<unsigned char>(val);
150  }
151  }
152  }
153  }
154 }
155 
162 {
163  const unsigned int srcHeight = src.getHeight(), srcWidth = src.getWidth();
164  const unsigned int srcSize = srcHeight * srcWidth;
165  dest.resize(srcHeight, srcWidth);
166  for (unsigned int i = 0; i < srcSize; ++i) {
167  dest.bitmap[i] = static_cast<float>(src.bitmap[i]);
168  }
169 }
170 
178 {
179  dest.resize(src.getHeight(), src.getWidth());
180  unsigned int max_xy = src.getWidth() * src.getHeight();
181  double min, max;
182 
183  src.getMinMaxValue(min, max);
184 
185  for (unsigned int i = 0; i < max_xy; ++i) {
186  double val = 255. * ((src.bitmap[i] - min) / (max - min));
187  if (val < 0) {
188  dest.bitmap[i] = 0;
189  }
190  else if (val > 255) {
191  dest.bitmap[i] = 255;
192  }
193  else {
194  dest.bitmap[i] = static_cast<unsigned char>(val);
195  }
196  }
197 }
198 
205 void vpImageConvert::convert(const vpImage<uint16_t> &src, vpImage<unsigned char> &dest, unsigned char bitshift)
206 {
207  const unsigned int srcSize = src.getSize();
208  dest.resize(src.getHeight(), src.getWidth());
209 
210  for (unsigned int i = 0; i < srcSize; ++i) {
211  dest.bitmap[i] = static_cast<unsigned char>(src.bitmap[i] >> bitshift);
212  }
213 }
214 
221 void vpImageConvert::convert(const vpImage<unsigned char> &src, vpImage<uint16_t> &dest, unsigned char bitshift)
222 {
223  const unsigned int srcSize = src.getSize();
224  dest.resize(src.getHeight(), src.getWidth());
225 
226  for (unsigned int i = 0; i < srcSize; ++i) {
227  dest.bitmap[i] = static_cast<unsigned char>(src.bitmap[i] << bitshift);
228  }
229 }
230 
237 {
238  const unsigned int srcHeight = src.getHeight(), srcWidth = src.getWidth();
239  const unsigned int srcSize = srcHeight * srcWidth;
240  dest.resize(srcHeight, srcWidth);
241  for (unsigned int i = 0; i < srcSize; ++i) {
242  dest.bitmap[i] = static_cast<double>(src.bitmap[i]);
243  }
244 }
245 
254 {
255  vp_createDepthHistogram(src_depth, dest_rgba);
256 }
257 
265 {
266  vp_createDepthHistogram(src_depth, dest_depth);
267 }
268 
277 {
278  vp_createDepthHistogram(src_depth, dest_rgba);
279 }
280 
288 {
289  vp_createDepthHistogram(src_depth, dest_depth);
290 }
291 
301 void vpImageConvert::RGBToRGBa(unsigned char *rgb, unsigned char *rgba, unsigned int size)
302 {
303  RGBToRGBa(rgb, rgba, size, 1, false);
304 }
305 
321 void vpImageConvert::RGBToRGBa(unsigned char *rgb, unsigned char *rgba, unsigned int width, unsigned int height,
322  bool flip)
323 {
324 #if defined(VISP_HAVE_SIMDLIB)
325  if (!flip) {
326  SimdBgrToBgra(rgb, width, height, width * 3, rgba, width * 4, vpRGBa::alpha_default);
327  }
328  else {
329 #endif
330  // if we have to flip the image, we start from the end last scanline so the
331  // step is negative
332  int lineStep = flip ? -static_cast<int>(width * 3) : static_cast<int>(width * 3);
333 
334  // starting source address = last line if we need to flip the image
335  unsigned char *src = flip ? (rgb + (width * height * 3) + lineStep) : rgb;
336 
337  unsigned int j = 0;
338  unsigned int i = 0;
339 
340  for (i = 0; i < height; ++i) {
341  unsigned char *line = src;
342  for (j = 0; j < width; ++j) {
343  *rgba++ = *(++line);
344  *rgba++ = *(++line);
345  *rgba++ = *(++line);
346  *rgba++ = vpRGBa::alpha_default;
347  }
348  // go to the next line
349  src += lineStep;
350  }
351 #if defined(VISP_HAVE_SIMDLIB)
352  }
353 #endif
354 }
355 
368 void vpImageConvert::RGBaToRGB(unsigned char *rgba, unsigned char *rgb, unsigned int size)
369 {
370 #if defined(VISP_HAVE_SIMDLIB)
371  SimdBgraToBgr(rgba, size, 1, size * 4, rgb, size * 3);
372 #else
373  unsigned char *pt_input = rgba;
374  unsigned char *pt_end = rgba + (4 * size);
375  unsigned char *pt_output = rgb;
376 
377  while (pt_input != pt_end) {
378  *(++pt_output) = *(++pt_input); // R
379  *(++pt_output) = *(++pt_input); // G
380  *(++pt_output) = *(++pt_input); // B
381  ++pt_input;
382  }
383 #endif
384 }
385 
398 void vpImageConvert::RGBToGrey(unsigned char *rgb, unsigned char *grey, unsigned int size)
399 {
400  RGBToGrey(rgb, grey, size, 1, false);
401 }
402 
416 void vpImageConvert::RGBToGrey(unsigned char *rgb, unsigned char *grey, unsigned int width, unsigned int height,
417  bool flip)
418 {
419 #if defined(VISP_HAVE_SIMDLIB)
420  if (!flip) {
421  SimdRgbToGray(rgb, width, height, width * 3, grey, width);
422  }
423  else {
424 #endif
425  // if we have to flip the image, we start from the end last scanline so
426  // the step is negative
427  int lineStep = flip ? -static_cast<int>(width * 3) : static_cast<int>(width * 3);
428 
429  // starting source address = last line if we need to flip the image
430  unsigned char *src = flip ? (rgb + (width * height * 3) + lineStep) : rgb;
431 
432  unsigned int j = 0;
433  unsigned int i = 0;
434 
435  unsigned r, g, b;
436 
437  for (i = 0; i < height; ++i) {
438  unsigned char *line = src;
439  for (j = 0; j < width; ++j) {
440  r = *(++line);
441  g = *(++line);
442  b = *(++line);
443  *grey++ = static_cast<unsigned char>((0.2126 * r) + (0.7152 * g) + (0.0722 * b));
444  }
445 
446  // go to the next line
447  src += lineStep;
448  }
449 #if defined(VISP_HAVE_SIMDLIB)
450  }
451 #endif
452 }
453 
469 void vpImageConvert::RGBaToGrey(unsigned char *rgba, unsigned char *grey, unsigned int width, unsigned int height,
470  unsigned int
471 #if defined(_OPENMP)
472  nThreads
473 #endif
474 )
475 {
476 #if defined(VISP_HAVE_SIMDLIB)
477  const int heightAsInt = static_cast<int>(height);
478 #if defined(_OPENMP)
479  if (nThreads > 0) {
480  omp_set_num_threads(static_cast<int>(nThreads));
481  }
482 #pragma omp parallel for
483 #endif
484  for (int i = 0; i < heightAsInt; ++i) {
485  SimdRgbaToGray(rgba + (i * width * 4), width, 1, width * 4, grey + (i * width), width);
486  }
487 #else
488 #if defined(_OPENMP)
489  (void)nThreads;
490 #endif
491  vpImageConvert::RGBaToGrey(rgba, grey, width * height);
492 #endif
493 }
494 
509 void vpImageConvert::RGBaToGrey(unsigned char *rgba, unsigned char *grey, unsigned int size)
510 {
511 #if defined(VISP_HAVE_SIMDLIB)
512  SimdRgbaToGray(rgba, size, 1, size * 4, grey, size);
513 #else
514  unsigned char *pt_input = rgba;
515  unsigned char *pt_end = rgba + (size * 4);
516  unsigned char *pt_output = grey;
517 
518  while (pt_input != pt_end) {
519  *pt_output = static_cast<unsigned char>((0.2126 * (*pt_input)) + (0.7152 * (*(pt_input + 1))) + (0.0722 * (*(pt_input + 2))));
520  pt_input += 4;
521  ++pt_output;
522  }
523 #endif
524 }
525 
537 void vpImageConvert::GreyToRGBa(unsigned char *grey, unsigned char *rgba, unsigned int width, unsigned int height)
538 {
539 #if defined(VISP_HAVE_SIMDLIB)
540  SimdGrayToBgra(grey, width, height, width, rgba, width * sizeof(vpRGBa), vpRGBa::alpha_default);
541 #else
542  vpImageConvert::GreyToRGBa(grey, rgba, width * height);
543 #endif
544 }
545 
558 void vpImageConvert::GreyToRGBa(unsigned char *grey, unsigned char *rgba, unsigned int size)
559 {
560 #if defined(VISP_HAVE_SIMDLIB)
561  GreyToRGBa(grey, rgba, size, 1);
562 #else
563  unsigned char *pt_input = grey;
564  unsigned char *pt_end = grey + size;
565  unsigned char *pt_output = rgba;
566 
567  while (pt_input != pt_end) {
568  unsigned char p = *pt_input;
569  *pt_output = p; // R
570  *(pt_output + 1) = p; // G
571  *(pt_output + 2) = p; // B
572  *(pt_output + 3) = vpRGBa::alpha_default; // A
573 
574  ++pt_input;
575  pt_output += 4;
576  }
577 #endif
578 }
579 
590 void vpImageConvert::GreyToRGB(unsigned char *grey, unsigned char *rgb, unsigned int size)
591 {
592 #if defined(VISP_HAVE_SIMDLIB)
593  SimdGrayToBgr(grey, size, 1, size, rgb, size * 3);
594 #else
595  unsigned char *pt_input = grey;
596  unsigned char *pt_end = grey + size;
597  unsigned char *pt_output = rgb;
598 
599  while (pt_input != pt_end) {
600  unsigned char p = *pt_input;
601  *pt_output = p; // R
602  *(pt_output + 1) = p; // G
603  *(pt_output + 2) = p; // B
604 
605  ++pt_input;
606  pt_output += 3;
607  }
608 #endif
609 }
610 
626 void vpImageConvert::BGRToRGBa(unsigned char *bgr, unsigned char *rgba, unsigned int width, unsigned int height,
627  bool flip)
628 {
629 #if defined(VISP_HAVE_SIMDLIB)
630  if (!flip) {
631  SimdRgbToBgra(bgr, width, height, width * 3, rgba, width * sizeof(vpRGBa), vpRGBa::alpha_default);
632  }
633  else {
634 #endif
635  // if we have to flip the image, we start from the end last scanline so the
636  // step is negative
637  int lineStep = flip ? -static_cast<int>(width * 3) : static_cast<int>(width * 3);
638 
639  // starting source address = last line if we need to flip the image
640  unsigned char *src = flip ? (bgr + (width * height * 3) + lineStep) : bgr;
641 
642  for (unsigned int i = 0; i < height; ++i) {
643  unsigned char *line = src;
644  for (unsigned int j = 0; j < width; ++j) {
645  *rgba++ = *(line + 2);
646  *rgba++ = *(line + 1);
647  *rgba++ = *(line + 0);
648  *rgba++ = vpRGBa::alpha_default;
649 
650  line += 3;
651  }
652  // go to the next line
653  src += lineStep;
654  }
655 #if defined(VISP_HAVE_SIMDLIB)
656  }
657 #endif
658 }
659 
674 void vpImageConvert::BGRaToRGBa(unsigned char *bgra, unsigned char *rgba, unsigned int width, unsigned int height,
675  bool flip)
676 {
677 #if defined(VISP_HAVE_SIMDLIB)
678  if (!flip) {
679  SimdBgraToRgba(bgra, width, height, width * 4, rgba, width * 4);
680  }
681  else {
682 #endif
683  // if we have to flip the image, we start from the end last scanline so the
684  // step is negative
685  int lineStep = flip ? -static_cast<int>(width * 4) : static_cast<int>(width * 4);
686 
687  // starting source address = last line if we need to flip the image
688  unsigned char *src = flip ? (bgra + (width * height * 4) + lineStep) : bgra;
689 
690  for (unsigned int i = 0; i < height; ++i) {
691  unsigned char *line = src;
692  for (unsigned int j = 0; j < width; ++j) {
693  *rgba++ = *(line + 2);
694  *rgba++ = *(line + 1);
695  *rgba++ = *(line + 0);
696  *rgba++ = *(line + 3);
697 
698  line += 4;
699  }
700  // go to the next line
701  src += lineStep;
702  }
703 #if defined(VISP_HAVE_SIMDLIB)
704  }
705 #endif
706 }
707 
722 void vpImageConvert::BGRToGrey(unsigned char *bgr, unsigned char *grey, unsigned int width, unsigned int height,
723  bool flip,
724  unsigned int
725 #if defined(_OPENMP)
726  nThreads
727 #endif
728 )
729 {
730 #if defined(VISP_HAVE_SIMDLIB)
731  const int heightAsInt = static_cast<int>(height);
732  if (!flip) {
733 #if defined(_OPENMP)
734  if (nThreads > 0) {
735  omp_set_num_threads(static_cast<int>(nThreads));
736  }
737 #pragma omp parallel for
738 #endif
739  for (int i = 0; i < heightAsInt; ++i) {
740  SimdBgrToGray(bgr + (i * width * 3), width, 1, width * 3, grey + (i * width), width);
741  }
742  }
743  else {
744 #endif
745  // if we have to flip the image, we start from the end last scanline so
746  // the step is negative
747  int lineStep = flip ? -static_cast<int>(width * 3) : static_cast<int>(width * 3);
748 
749  // starting source address = last line if we need to flip the image
750  unsigned char *src = flip ? (bgr + (width * height * 3) + lineStep) : bgr;
751 
752  for (unsigned int i = 0; i < height; ++i) {
753  unsigned char *line = src;
754  for (unsigned int j = 0; j < width; ++j) {
755  *grey++ = static_cast<unsigned int>((0.2126 * *(line + 2)) + (0.7152 * *(line + 1)) + (0.0722 * *(line + 0)));
756  line += 3;
757  }
758 
759  // go to the next line
760  src += lineStep;
761  }
762 #if defined(VISP_HAVE_SIMDLIB)
763  }
764 #endif
765 #if !defined(VISP_HAVE_SIMDLIB) && defined(_OPENMP)
766  (void)nThreads;
767 #endif
768 }
769 
784 void vpImageConvert::BGRaToGrey(unsigned char *bgra, unsigned char *grey, unsigned int width, unsigned int height,
785  bool flip,
786  unsigned int
787 #if defined(_OPENMP)
788  nThreads
789 #endif
790 )
791 {
792 #if defined(VISP_HAVE_SIMDLIB)
793  if (!flip) {
794  const int heightAsInt = static_cast<int>(height);
795 #if defined(_OPENMP)
796  if (nThreads > 0) {
797  omp_set_num_threads(static_cast<int>(nThreads));
798  }
799 #pragma omp parallel for
800 #endif
801  for (int i = 0; i < heightAsInt; ++i) {
802  SimdBgraToGray(bgra + (i * width * 4), width, 1, width * 4, grey + (i * width), width);
803  }
804  }
805  else {
806 #endif
807  // if we have to flip the image, we start from the end last scanline so
808  // the step is negative
809  int lineStep = flip ? -static_cast<int>(width * 4) : static_cast<int>(width * 4);
810 
811  // starting source address = last line if we need to flip the image
812  unsigned char *src = flip ? (bgra + (width * height * 4) + lineStep) : bgra;
813 
814  for (unsigned int i = 0; i < height; ++i) {
815  unsigned char *line = src;
816  for (unsigned int j = 0; j < width; ++j) {
817  *grey++ = static_cast<unsigned char>((0.2126 * *(line + 2)) + (0.7152 * *(line + 1)) + (0.0722 * *(line + 0)));
818  line += 4;
819  }
820 
821  // go to the next line
822  src += lineStep;
823  }
824 #if defined(VISP_HAVE_SIMDLIB)
825  }
826 #endif
827 #if !defined(VISP_HAVE_SIMDLIB) && defined(_OPENMP)
828  (void)nThreads;
829 #endif
830 }
831 
835 void vpImageConvert::computeYCbCrLUT()
836 {
837  if (YCbCrLUTcomputed == false) {
838  int index = 256;
839 
840  while (index--) {
841 
842  int aux = index - 128;
843  vpImageConvert::vpCrr[index] = static_cast<int>((364.6610 * aux) / 256);
844  vpImageConvert::vpCgb[index] = static_cast<int>((-89.8779 * aux) / 256);
845  vpImageConvert::vpCgr[index] = static_cast<int>((-185.8154 * aux) / 256);
846  vpImageConvert::vpCbb[index] = static_cast<int>((460.5724 * aux) / 256);
847  }
848 
849  YCbCrLUTcomputed = true;
850  }
851 }
852 
874 void vpImageConvert::YCbCrToRGB(unsigned char *ycbcr, unsigned char *rgb, unsigned int size)
875 {
876  unsigned char *cbv;
877  unsigned char *crv;
878  unsigned char *pt_ycbcr = ycbcr;
879  unsigned char *pt_rgb = rgb;
880  cbv = pt_ycbcr + 1;
881  crv = pt_ycbcr + 3;
882 
883  vpImageConvert::computeYCbCrLUT();
884 
885  int col = 0;
886 
887  while (size--) {
888  int val_r, val_g, val_b;
889  if (!(col % 2)) {
890  cbv = pt_ycbcr + 1;
891  crv = pt_ycbcr + 3;
892  }
893 
894  val_r = *pt_ycbcr + vpImageConvert::vpCrr[*crv];
895  val_g = *pt_ycbcr + vpImageConvert::vpCgb[*cbv] + vpImageConvert::vpCgr[*crv];
896  val_b = *pt_ycbcr + vpImageConvert::vpCbb[*cbv];
897 
898  *pt_rgb++ = (val_r < 0) ? 0u : ((val_r > 255) ? 255u : static_cast<unsigned char>(val_r)); // Red component.
899  *pt_rgb++ = (val_g < 0) ? 0u : ((val_g > 255) ? 255u : static_cast<unsigned char>(val_g)); // Green component.
900  *pt_rgb++ = (val_b < 0) ? 0u : ((val_b > 255) ? 255u : static_cast<unsigned char>(val_b)); // Blue component.
901 
902  pt_ycbcr += 2;
903  ++col;
904  }
905 }
906 
932 void vpImageConvert::YCbCrToRGBa(unsigned char *ycbcr, unsigned char *rgba, unsigned int size)
933 {
934  unsigned char *cbv;
935  unsigned char *crv;
936  unsigned char *pt_ycbcr = ycbcr;
937  unsigned char *pt_rgba = rgba;
938  cbv = pt_ycbcr + 1;
939  crv = pt_ycbcr + 3;
940 
941  vpImageConvert::computeYCbCrLUT();
942 
943  int col = 0;
944 
945  while (size--) {
946  int val_r, val_g, val_b;
947  if (!(col % 2)) {
948  cbv = pt_ycbcr + 1;
949  crv = pt_ycbcr + 3;
950  }
951 
952  val_r = *pt_ycbcr + vpImageConvert::vpCrr[*crv];
953  val_g = *pt_ycbcr + vpImageConvert::vpCgb[*cbv] + vpImageConvert::vpCgr[*crv];
954  val_b = *pt_ycbcr + vpImageConvert::vpCbb[*cbv];
955 
956  *pt_rgba++ = (val_r < 0) ? 0u : ((val_r > 255) ? 255u : static_cast<unsigned char>(val_r)); // Red component.
957  *pt_rgba++ = (val_g < 0) ? 0u : ((val_g > 255) ? 255u : static_cast<unsigned char>(val_g)); // Green component.
958  *pt_rgba++ = (val_b < 0) ? 0u : ((val_b > 255) ? 255u : static_cast<unsigned char>(val_b)); // Blue component.
959  *pt_rgba++ = vpRGBa::alpha_default;
960 
961  pt_ycbcr += 2;
962  ++col;
963  }
964 }
965 
985 void vpImageConvert::YCbCrToGrey(unsigned char *ycbcr, unsigned char *grey, unsigned int size)
986 {
987  unsigned int i = 0, j = 0;
988  const unsigned int doubleSize = size * 2;
989  while (j < doubleSize) {
990  grey[i++] = ycbcr[j];
991  grey[i++] = ycbcr[j + 2];
992  j += 4;
993  }
994 }
995 
1017 void vpImageConvert::YCrCbToRGB(unsigned char *ycrcb, unsigned char *rgb, unsigned int size)
1018 {
1019  unsigned char *cbv;
1020  unsigned char *crv;
1021  unsigned char *pt_ycbcr = ycrcb;
1022  unsigned char *pt_rgb = rgb;
1023  crv = pt_ycbcr + 1;
1024  cbv = pt_ycbcr + 3;
1025 
1026  vpImageConvert::computeYCbCrLUT();
1027 
1028  int col = 0;
1029 
1030  while (size--) {
1031  int val_r, val_g, val_b;
1032  if (!(col % 2)) {
1033  crv = pt_ycbcr + 1;
1034  cbv = pt_ycbcr + 3;
1035  }
1036 
1037  val_r = *pt_ycbcr + vpImageConvert::vpCrr[*crv];
1038  val_g = *pt_ycbcr + vpImageConvert::vpCgb[*cbv] + vpImageConvert::vpCgr[*crv];
1039  val_b = *pt_ycbcr + vpImageConvert::vpCbb[*cbv];
1040 
1041  *pt_rgb++ = (val_r < 0) ? 0u : ((val_r > 255) ? 255u : static_cast<unsigned char>(val_r)); // Red component.
1042  *pt_rgb++ = (val_g < 0) ? 0u : ((val_g > 255) ? 255u : static_cast<unsigned char>(val_g)); // Green component.
1043  *pt_rgb++ = (val_b < 0) ? 0u : ((val_b > 255) ? 255u : static_cast<unsigned char>(val_b)); // Blue component.
1044 
1045  pt_ycbcr += 2;
1046  ++col;
1047  }
1048 }
1049 
1074 void vpImageConvert::YCrCbToRGBa(unsigned char *ycrcb, unsigned char *rgba, unsigned int size)
1075 {
1076  unsigned char *cbv;
1077  unsigned char *crv;
1078  unsigned char *pt_ycbcr = ycrcb;
1079  unsigned char *pt_rgba = rgba;
1080  crv = pt_ycbcr + 1;
1081  cbv = pt_ycbcr + 3;
1082 
1083  vpImageConvert::computeYCbCrLUT();
1084 
1085  int col = 0;
1086 
1087  while (size--) {
1088  int val_r, val_g, val_b;
1089  if (!(col % 2)) {
1090  crv = pt_ycbcr + 1;
1091  cbv = pt_ycbcr + 3;
1092  }
1093 
1094  val_r = *pt_ycbcr + vpImageConvert::vpCrr[*crv];
1095  val_g = *pt_ycbcr + vpImageConvert::vpCgb[*cbv] + vpImageConvert::vpCgr[*crv];
1096  val_b = *pt_ycbcr + vpImageConvert::vpCbb[*cbv];
1097 
1098  *pt_rgba++ = (val_r < 0) ? 0u : ((val_r > 255) ? 255u : static_cast<unsigned char>(val_r)); // Red component.
1099  *pt_rgba++ = (val_g < 0) ? 0u : ((val_g > 255) ? 255u : static_cast<unsigned char>(val_g)); // Green component.
1100  *pt_rgba++ = (val_b < 0) ? 0u : ((val_b > 255) ? 255u : static_cast<unsigned char>(val_b)); // Blue component.
1101  *pt_rgba++ = vpRGBa::alpha_default;
1102 
1103  pt_ycbcr += 2;
1104  ++col;
1105  }
1106 }
1107 
1152 {
1153 #if defined(VISP_HAVE_SIMDLIB)
1154  if (src.getSize() > 0) {
1155  if (pR) {
1156  pR->resize(src.getHeight(), src.getWidth());
1157  }
1158  if (pG) {
1159  pG->resize(src.getHeight(), src.getWidth());
1160  }
1161  if (pB) {
1162  pB->resize(src.getHeight(), src.getWidth());
1163  }
1164  if (pa) {
1165  pa->resize(src.getHeight(), src.getWidth());
1166  }
1167 
1168  unsigned char *ptrR = pR ? pR->bitmap : new unsigned char[src.getSize()];
1169  unsigned char *ptrG = pG ? pG->bitmap : new unsigned char[src.getSize()];
1170  unsigned char *ptrB = pB ? pB->bitmap : new unsigned char[src.getSize()];
1171  unsigned char *ptrA = pa ? pa->bitmap : new unsigned char[src.getSize()];
1172 
1173  SimdDeinterleaveBgra(reinterpret_cast<unsigned char *>(src.bitmap), src.getWidth() * sizeof(vpRGBa), src.getWidth(),
1174  src.getHeight(), ptrR, src.getWidth(), ptrG, src.getWidth(), ptrB, src.getWidth(), ptrA,
1175  src.getWidth());
1176 
1177  if (!pR) {
1178  delete[] ptrR;
1179  }
1180  if (!pG) {
1181  delete[] ptrG;
1182  }
1183  if (!pB) {
1184  delete[] ptrB;
1185  }
1186  if (!pa) {
1187  delete[] ptrA;
1188  }
1189  }
1190 #else
1191  size_t n = src.getNumberOfPixel();
1192  unsigned int height = src.getHeight();
1193  unsigned int width = src.getWidth();
1194  unsigned char *input;
1195  unsigned char *dst;
1196  const unsigned int index_0 = 0;
1197  const unsigned int index_1 = 1;
1198  const unsigned int index_2 = 2;
1199  const unsigned int index_3 = 3;
1200 
1201  vpImage<unsigned char> *tabChannel[4];
1202 
1203  tabChannel[index_0] = pR;
1204  tabChannel[index_1] = pG;
1205  tabChannel[index_2] = pB;
1206  tabChannel[index_3] = pa;
1207 
1208  size_t i; /* ordre */
1209  const unsigned int val_4 = 4;
1210  for (unsigned int j = 0; j < val_4; ++j) {
1211  if (tabChannel[j] != nullptr) {
1212  if ((tabChannel[j]->getHeight() != height) || (tabChannel[j]->getWidth() != width)) {
1213  tabChannel[j]->resize(height, width);
1214  }
1215  dst = static_cast<unsigned char *>(tabChannel[j]->bitmap);
1216 
1217  input = (unsigned char *)src.bitmap + j;
1218  i = 0;
1219  // optimization
1220  if (n >= 4) {
1221  n -= 3;
1222  for (; i < n; i += 4) {
1223  *dst = *input;
1224  input += 4;
1225  ++dst;
1226  *dst = *input;
1227  input += 4;
1228  ++dst;
1229  *dst = *input;
1230  input += 4;
1231  ++dst;
1232  *dst = *input;
1233  input += 4;
1234  ++dst;
1235  }
1236  n += 3;
1237  }
1238 
1239  for (; i < n; ++i) {
1240  *dst = *input;
1241  input += 4;
1242  ++dst;
1243  }
1244  }
1245  }
1246 #endif
1247 }
1248 
1261 {
1262  // Check if the input channels have all the same dimensions
1263  std::map<unsigned int, unsigned int> mapOfWidths, mapOfHeights;
1264  if (R != nullptr) {
1265  ++mapOfWidths[R->getWidth()];
1266  ++mapOfHeights[R->getHeight()];
1267  }
1268 
1269  if (G != nullptr) {
1270  ++mapOfWidths[G->getWidth()];
1271  ++mapOfHeights[G->getHeight()];
1272  }
1273 
1274  if (B != nullptr) {
1275  ++mapOfWidths[B->getWidth()];
1276  ++mapOfHeights[B->getHeight()];
1277  }
1278 
1279  if (a != nullptr) {
1280  ++mapOfWidths[a->getWidth()];
1281  ++mapOfHeights[a->getHeight()];
1282  }
1283 
1284  if ((mapOfWidths.size() == 1) && (mapOfHeights.size() == 1)) {
1285  unsigned int width = mapOfWidths.begin()->first;
1286  unsigned int height = mapOfHeights.begin()->first;
1287 
1288  RGBa.resize(height, width);
1289 
1290 
1291 #if defined(VISP_HAVE_SIMDLIB)
1292  if ((R != nullptr) && (G != nullptr) && (B != nullptr) && (a != nullptr)) {
1293  SimdInterleaveBgra(R->bitmap, width, G->bitmap, width, B->bitmap, width, a->bitmap, width, width, height,
1294  reinterpret_cast<uint8_t *>(RGBa.bitmap), width * sizeof(vpRGBa));
1295  }
1296  else {
1297 #endif
1298  unsigned int size = width * height;
1299  for (unsigned int i = 0; i < size; ++i) {
1300  if (R != nullptr) {
1301  RGBa.bitmap[i].R = R->bitmap[i];
1302  }
1303 
1304  if (G != nullptr) {
1305  RGBa.bitmap[i].G = G->bitmap[i];
1306  }
1307 
1308  if (B != nullptr) {
1309  RGBa.bitmap[i].B = B->bitmap[i];
1310  }
1311 
1312  if (a != nullptr) {
1313  RGBa.bitmap[i].A = a->bitmap[i];
1314  }
1315  }
1316 #if defined(VISP_HAVE_SIMDLIB)
1317  }
1318 #endif
1319  }
1320  else {
1321  throw vpException(vpException::dimensionError, "Mismatched dimensions!");
1322  }
1323 }
1324 
1335 void vpImageConvert::MONO16ToGrey(unsigned char *grey16, unsigned char *grey, unsigned int size)
1336 {
1337  int i = (static_cast<int>(size) * 2) - 1;
1338  int j = static_cast<int>(size) - 1;
1339 
1340  while (i >= 0) {
1341  int y = grey16[i--];
1342  grey[j--] = static_cast<unsigned char>((y + (grey16[i] * 256)) / 256);
1343  --i;
1344  }
1345 }
1346 
1358 void vpImageConvert::MONO16ToRGBa(unsigned char *grey16, unsigned char *rgba, unsigned int size)
1359 {
1360  int i = (static_cast<int>(size) * 2) - 1;
1361  int j = (static_cast<int>(size) * 4) - 1;
1362 
1363  while (i >= 0) {
1364  int y = grey16[i--];
1365  unsigned char v = static_cast<unsigned char>((y + (grey16[i] * 256)) / 256);
1366  --i;
1367  rgba[j--] = vpRGBa::alpha_default;
1368  rgba[j--] = v;
1369  rgba[j--] = v;
1370  rgba[j--] = v;
1371  }
1372 }
1373 
1374 // Bilinear
1375 #ifndef VISP_SKIP_BAYER_CONVERSION
1388 void vpImageConvert::demosaicBGGRToRGBaBilinear(const uint8_t *bggr, uint8_t *rgba, unsigned int width,
1389  unsigned int height, unsigned int nThreads)
1390 {
1391  demosaicBGGRToRGBaBilinearTpl(bggr, rgba, width, height, nThreads);
1392 }
1393 
1406 void vpImageConvert::demosaicBGGRToRGBaBilinear(const uint16_t *bggr, uint16_t *rgba, unsigned int width,
1407  unsigned int height, unsigned int nThreads)
1408 {
1409  demosaicBGGRToRGBaBilinearTpl(bggr, rgba, width, height, nThreads);
1410 }
1411 
1424 void vpImageConvert::demosaicGBRGToRGBaBilinear(const uint8_t *gbrg, uint8_t *rgba, unsigned int width,
1425  unsigned int height, unsigned int nThreads)
1426 {
1427  demosaicGBRGToRGBaBilinearTpl(gbrg, rgba, width, height, nThreads);
1428 }
1429 
1442 void vpImageConvert::demosaicGBRGToRGBaBilinear(const uint16_t *gbrg, uint16_t *rgba, unsigned int width,
1443  unsigned int height, unsigned int nThreads)
1444 {
1445  demosaicGBRGToRGBaBilinearTpl(gbrg, rgba, width, height, nThreads);
1446 }
1447 
1460 void vpImageConvert::demosaicGRBGToRGBaBilinear(const uint8_t *grbg, uint8_t *rgba, unsigned int width,
1461  unsigned int height, unsigned int nThreads)
1462 {
1463  demosaicGRBGToRGBaBilinearTpl(grbg, rgba, width, height, nThreads);
1464 }
1465 
1478 void vpImageConvert::demosaicGRBGToRGBaBilinear(const uint16_t *grbg, uint16_t *rgba, unsigned int width,
1479  unsigned int height, unsigned int nThreads)
1480 {
1481  demosaicGRBGToRGBaBilinearTpl(grbg, rgba, width, height, nThreads);
1482 }
1483 
1496 void vpImageConvert::demosaicRGGBToRGBaBilinear(const uint8_t *rggb, uint8_t *rgba, unsigned int width,
1497  unsigned int height, unsigned int nThreads)
1498 {
1499  demosaicRGGBToRGBaBilinearTpl(rggb, rgba, width, height, nThreads);
1500 }
1501 
1514 void vpImageConvert::demosaicRGGBToRGBaBilinear(const uint16_t *rggb, uint16_t *rgba, unsigned int width,
1515  unsigned int height, unsigned int nThreads)
1516 {
1517  demosaicRGGBToRGBaBilinearTpl(rggb, rgba, width, height, nThreads);
1518 }
1519 
1520 // Malvar
1521 
1534 void vpImageConvert::demosaicBGGRToRGBaMalvar(const uint8_t *bggr, uint8_t *rgba, unsigned int width,
1535  unsigned int height, unsigned int nThreads)
1536 {
1537  demosaicBGGRToRGBaMalvarTpl(bggr, rgba, width, height, nThreads);
1538 }
1539 
1552 void vpImageConvert::demosaicBGGRToRGBaMalvar(const uint16_t *bggr, uint16_t *rgba, unsigned int width,
1553  unsigned int height, unsigned int nThreads)
1554 {
1555  demosaicBGGRToRGBaMalvarTpl(bggr, rgba, width, height, nThreads);
1556 }
1557 
1570 void vpImageConvert::demosaicGBRGToRGBaMalvar(const uint8_t *gbrg, uint8_t *rgba, unsigned int width,
1571  unsigned int height, unsigned int nThreads)
1572 {
1573  demosaicGBRGToRGBaMalvarTpl(gbrg, rgba, width, height, nThreads);
1574 }
1575 
1588 void vpImageConvert::demosaicGBRGToRGBaMalvar(const uint16_t *gbrg, uint16_t *rgba, unsigned int width,
1589  unsigned int height, unsigned int nThreads)
1590 {
1591  demosaicGBRGToRGBaMalvarTpl(gbrg, rgba, width, height, nThreads);
1592 }
1593 
1606 void vpImageConvert::demosaicGRBGToRGBaMalvar(const uint8_t *grbg, uint8_t *rgba, unsigned int width,
1607  unsigned int height, unsigned int nThreads)
1608 {
1609  demosaicGRBGToRGBaMalvarTpl(grbg, rgba, width, height, nThreads);
1610 }
1611 
1624 void vpImageConvert::demosaicGRBGToRGBaMalvar(const uint16_t *grbg, uint16_t *rgba, unsigned int width,
1625  unsigned int height, unsigned int nThreads)
1626 {
1627  demosaicGRBGToRGBaMalvarTpl(grbg, rgba, width, height, nThreads);
1628 }
1629 
1642 void vpImageConvert::demosaicRGGBToRGBaMalvar(const uint8_t *rggb, uint8_t *rgba, unsigned int width,
1643  unsigned int height, unsigned int nThreads)
1644 {
1645  demosaicRGGBToRGBaMalvarTpl(rggb, rgba, width, height, nThreads);
1646 }
1647 
1660 void vpImageConvert::demosaicRGGBToRGBaMalvar(const uint16_t *rggb, uint16_t *rgba, unsigned int width,
1661  unsigned int height, unsigned int nThreads)
1662 {
1663  demosaicRGGBToRGBaMalvarTpl(rggb, rgba, width, height, nThreads);
1664 }
1665 #endif // VISP_SKIP_BAYER_CONVERSION
1666 
1667 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:542
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