Visual Servoing Platform  version 3.4.0
vpImageConvert Class Reference

#include <vpImageConvert.h>

Static Public Member Functions

static void createDepthHistogram (const vpImage< uint16_t > &src_depth, vpImage< vpRGBa > &dest_rgba)
 
static void createDepthHistogram (const vpImage< uint16_t > &src_depth, vpImage< unsigned char > &dest_depth)
 
static void convert (const vpImage< unsigned char > &src, vpImage< vpRGBa > &dest)
 
static void convert (const vpImage< vpRGBa > &src, vpImage< unsigned char > &dest, unsigned int nThreads=0)
 
static void convert (const vpImage< float > &src, vpImage< unsigned char > &dest)
 
static void convert (const vpImage< unsigned char > &src, vpImage< float > &dest)
 
static void convert (const vpImage< double > &src, vpImage< unsigned char > &dest)
 
static void convert (const vpImage< unsigned char > &src, vpImage< double > &dest)
 
static void convert (const vpImage< uint16_t > &src, vpImage< unsigned char > &dest)
 
static void convert (const vpImage< unsigned char > &src, vpImage< uint16_t > &dest)
 
template<typename Type >
static void convert (const vpImage< Type > &src, vpImage< Type > &dest)
 
static void convert (const IplImage *src, vpImage< vpRGBa > &dest, bool flip=false)
 
static void convert (const IplImage *src, vpImage< unsigned char > &dest, bool flip=false)
 
static void convert (const vpImage< vpRGBa > &src, IplImage *&dest)
 
static void convert (const vpImage< unsigned char > &src, IplImage *&dest)
 
static void convert (const cv::Mat &src, vpImage< vpRGBa > &dest, bool flip=false)
 
static void convert (const cv::Mat &src, vpImage< unsigned char > &dest, bool flip=false, unsigned int nThreads=0)
 
static void convert (const vpImage< vpRGBa > &src, cv::Mat &dest)
 
static void convert (const vpImage< unsigned char > &src, cv::Mat &dest, bool copyData=true)
 
static void convert (const vpImage< unsigned char > &src, yarp::sig::ImageOf< yarp::sig::PixelMono > *dest, bool copyData=true)
 
static void convert (const yarp::sig::ImageOf< yarp::sig::PixelMono > *src, vpImage< unsigned char > &dest, bool copyData=true)
 
static void convert (const vpImage< vpRGBa > &src, yarp::sig::ImageOf< yarp::sig::PixelRgba > *dest, bool copyData=true)
 
static void convert (const yarp::sig::ImageOf< yarp::sig::PixelRgba > *src, vpImage< vpRGBa > &dest, bool copyData=true)
 
static void convert (const vpImage< vpRGBa > &src, yarp::sig::ImageOf< yarp::sig::PixelRgb > *dest)
 
static void convert (const yarp::sig::ImageOf< yarp::sig::PixelRgb > *src, vpImage< vpRGBa > &dest)
 
static void split (const vpImage< vpRGBa > &src, vpImage< unsigned char > *pR, vpImage< unsigned char > *pG, vpImage< unsigned char > *pB, vpImage< unsigned char > *pa=NULL)
 
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 YUVToRGB (unsigned char y, unsigned char u, unsigned char v, unsigned char &r, unsigned char &g, unsigned char &b)
 
static void YUYVToRGBa (unsigned char *yuyv, unsigned char *rgba, unsigned int width, unsigned int height)
 
static void YUYVToRGB (unsigned char *yuyv, unsigned char *rgb, unsigned int width, unsigned int height)
 
static void YUYVToGrey (unsigned char *yuyv, unsigned char *grey, unsigned int size)
 
static void YUV411ToRGBa (unsigned char *yuv, unsigned char *rgba, unsigned int size)
 
static void YUV411ToRGB (unsigned char *yuv, unsigned char *rgb, unsigned int size)
 
static void YUV411ToGrey (unsigned char *yuv, unsigned char *grey, unsigned int size)
 
static void YUV422ToRGBa (unsigned char *yuv, unsigned char *rgba, unsigned int size)
 
static void YUV422ToRGB (unsigned char *yuv, unsigned char *rgb, unsigned int size)
 
static void YUV422ToGrey (unsigned char *yuv, unsigned char *grey, unsigned int size)
 
static void YUV420ToRGBa (unsigned char *yuv, unsigned char *rgba, unsigned int width, unsigned int height)
 
static void YUV420ToRGB (unsigned char *yuv, unsigned char *rgb, unsigned int width, unsigned int height)
 
static void YUV420ToGrey (unsigned char *yuv, unsigned char *grey, unsigned int size)
 
static void YUV444ToRGBa (unsigned char *yuv, unsigned char *rgba, unsigned int size)
 
static void YUV444ToRGB (unsigned char *yuv, unsigned char *rgb, unsigned int size)
 
static void YUV444ToGrey (unsigned char *yuv, unsigned char *grey, unsigned int size)
 
static void YV12ToRGBa (unsigned char *yuv, unsigned char *rgba, unsigned int width, unsigned int height)
 
static void YV12ToRGB (unsigned char *yuv, unsigned char *rgb, unsigned int width, unsigned int height)
 
static void YVU9ToRGBa (unsigned char *yuv, unsigned char *rgba, unsigned int width, unsigned int height)
 
static void YVU9ToRGB (unsigned char *yuv, unsigned char *rgb, unsigned int width, unsigned int height)
 
static void RGBToRGBa (unsigned char *rgb, unsigned char *rgba, unsigned int size)
 
static void RGBaToRGB (unsigned char *rgba, unsigned char *rgb, unsigned int size)
 
static void RGBToGrey (unsigned char *rgb, unsigned char *grey, unsigned int width, unsigned int height, bool flip=false)
 
static void RGBToGrey (unsigned char *rgb, unsigned char *grey, unsigned int size)
 
static void RGBaToGrey (unsigned char *rgba, unsigned char *grey, unsigned int width, unsigned int height, unsigned int nThreads=0)
 
static void RGBaToGrey (unsigned char *rgba, unsigned char *grey, unsigned int size)
 
static void RGBToRGBa (unsigned char *rgb, unsigned char *rgba, unsigned int width, unsigned int height, bool flip=false)
 
static void GreyToRGBa (unsigned char *grey, unsigned char *rgba, unsigned int width, unsigned int height)
 
static void GreyToRGBa (unsigned char *grey, unsigned char *rgba, unsigned int size)
 
static void GreyToRGB (unsigned char *grey, unsigned char *rgb, unsigned int size)
 
static void BGRToRGBa (unsigned char *bgr, unsigned char *rgba, unsigned int width, unsigned int height, bool flip=false)
 
static void BGRToGrey (unsigned char *bgr, unsigned char *grey, unsigned int width, unsigned int height, bool flip=false, unsigned int nThreads=0)
 
static void BGRaToGrey (unsigned char *bgra, unsigned char *grey, unsigned int width, unsigned int height, bool flip=false, unsigned int nThreads=0)
 
static void BGRaToRGBa (unsigned char *bgra, unsigned char *rgba, unsigned int width, unsigned int height, bool flip=false)
 
static void YCbCrToRGB (unsigned char *ycbcr, unsigned char *rgb, unsigned int size)
 
static void YCbCrToRGBa (unsigned char *ycbcr, unsigned char *rgb, unsigned int size)
 
static void YCrCbToRGB (unsigned char *ycbcr, unsigned char *rgb, unsigned int size)
 
static void YCrCbToRGBa (unsigned char *ycbcr, unsigned char *rgb, unsigned int size)
 
static void YCbCrToGrey (unsigned char *ycbcr, unsigned char *grey, unsigned int size)
 
static void MONO16ToGrey (unsigned char *grey16, unsigned char *grey, unsigned int size)
 
static void MONO16ToRGBa (unsigned char *grey16, unsigned char *rgba, unsigned int size)
 
static void HSVToRGBa (const double *hue, const double *saturation, const double *value, unsigned char *rgba, unsigned int size)
 
static void HSVToRGBa (const unsigned char *hue, const unsigned char *saturation, const unsigned char *value, unsigned char *rgba, unsigned int size)
 
static void RGBaToHSV (const unsigned char *rgba, double *hue, double *saturation, double *value, unsigned int size)
 
static void RGBaToHSV (const unsigned char *rgba, unsigned char *hue, unsigned char *saturation, unsigned char *value, unsigned int size)
 
static void HSVToRGB (const double *hue, const double *saturation, const double *value, unsigned char *rgb, unsigned int size)
 
static void HSVToRGB (const unsigned char *hue, const unsigned char *saturation, const unsigned char *value, unsigned char *rgb, unsigned int size)
 
static void RGBToHSV (const unsigned char *rgb, double *hue, double *saturation, double *value, unsigned int size)
 
static void RGBToHSV (const unsigned char *rgb, unsigned char *hue, unsigned char *saturation, unsigned char *value, unsigned int size)
 

Detailed Description

Convert image types.

The following example available in tutorial-image-converter.cpp shows how to convert an OpenCV cv::Mat image into a vpImage:

#include <visp3/core/vpImageConvert.h>
#include <visp3/io/vpImageIo.h>
int main()
{
#if defined(VISP_HAVE_OPENCV) && (VISP_HAVE_OPENCV_VERSION >= 0x020100)
try {
cv::Mat A;
#if VISP_HAVE_OPENCV_VERSION >= 0x030200
int flags = cv::IMREAD_GRAYSCALE | cv::IMREAD_IGNORE_ORIENTATION;
#elif VISP_HAVE_OPENCV_VERSION >= 0x030000
int flags = cv::IMREAD_GRAYSCALE;
#elif VISP_HAVE_OPENCV_VERSION >= 0x020100
int flags = CV_LOAD_IMAGE_GRAYSCALE;
#endif
A = cv::imread("monkey.bmp", flags);
#ifdef VISP_HAVE_PNG
vpImageIo::write(I, "monkey.png"); // Gray
#endif
} catch (const vpException &e) {
std::cout << "Catch an exception: " << e << std::endl;
}
#endif
}

Definition at line 105 of file vpImageConvert.h.

Member Function Documentation

void vpImageConvert::BGRaToGrey ( unsigned char *  bgra,
unsigned char *  grey,
unsigned int  width,
unsigned int  height,
bool  flip = false,
unsigned int  nThreads = 0 
)
static

Converts a BGRa image to greyscale. Flips the image verticaly if needed. Assumes that grey is already resized.

Note
If flip is false, the SIMD lib is used to accelerate processing on x86 and ARM architecture.
Examples:
testColorConversion.cpp.

Definition at line 3636 of file vpImageConvert.cpp.

Referenced by convert().

void vpImageConvert::BGRaToRGBa ( unsigned char *  bgra,
unsigned char *  rgba,
unsigned int  width,
unsigned int  height,
bool  flip = false 
)
static

Converts a BGRa image to RGBa.

Flips the image verticaly if needed. Assumes that rgba is already resized before caling this function.

Note
If flip is false, the SIMD lib is used to accelerate processing on x86 and ARM architecture.
Examples:
testColorConversion.cpp.

Definition at line 3555 of file vpImageConvert.cpp.

void vpImageConvert::BGRToGrey ( unsigned char *  bgr,
unsigned char *  grey,
unsigned int  width,
unsigned int  height,
bool  flip = false,
unsigned int  nThreads = 0 
)
static

Converts a BGR image to greyscale. Flips the image verticaly if needed. Assumes that grey is already resized.

Note
If flip is false, the SIMD lib is used to accelerate processing on x86 and ARM architecture.
Examples:
testColorConversion.cpp.

Definition at line 3591 of file vpImageConvert.cpp.

Referenced by vpV4l2Grabber::acquire(), convert(), vpRobotBebop2::getGrayscaleImage(), and vpRealSense2::getGreyFrame().

void vpImageConvert::BGRToRGBa ( unsigned char *  bgr,
unsigned char *  rgba,
unsigned int  width,
unsigned int  height,
bool  flip = false 
)
static

Converts a BGR image to RGBa. The alpha component is set to vpRGBa::alpha_default.

Flips the image verticaly if needed. Assumes that rgba is already resized.

Note
If flip is false, the SIMD lib is used to accelerate processing on x86 and ARM architecture.

Definition at line 3518 of file vpImageConvert.cpp.

References vpRGBa::alpha_default.

Referenced by vpV4l2Grabber::acquire(), vpRealSense2::getColorFrame(), and vpRobotBebop2::getRGBaImage().

void vpImageConvert::convert ( const vpImage< unsigned char > &  src,
vpImage< vpRGBa > &  dest 
)
static

Convert a vpImage<unsigned char> to a vpImage<vpRGBa>. Tha alpha component is set to vpRGBa::alpha_default.

Parameters
src: source image
dest: destination image
See also
GreyToRGBa()
Examples:
AROgre.cpp, AROgreBasic.cpp, grabOpenCV.cpp, grabRealSense.cpp, grabV4l2MultiCpp11Thread.cpp, HelloWorldOgre.cpp, HelloWorldOgreAdvanced.cpp, servoPioneerPoint2DDepth.cpp, servoPioneerPoint2DDepthWithoutVpServo.cpp, servoViper850FourPointsKinect.cpp, testColorConversion.cpp, testConnectedComponents.cpp, testContours.cpp, testConversion.cpp, testFloodFill.cpp, testGaussianFilter.cpp, testGenericTracker.cpp, testImageFilter.cpp, testImageNormalizedCorrelation.cpp, testKeyPoint-3.cpp, testKeyPoint-4.cpp, testRealSense2_SR300.cpp, testRealSense_R200.cpp, testRealSense_SR300.cpp, testUndistortImage.cpp, trackKltOpencv.cpp, tutorial-apriltag-detector-live-rgbd-realsense.cpp, tutorial-apriltag-detector-live.cpp, tutorial-barcode-detector-live.cpp, tutorial-blob-tracker-live-firewire.cpp, tutorial-blob-tracker-live-v4l2.cpp, tutorial-bridge-opencv.cpp, tutorial-chessboard-pose.cpp, tutorial-dnn-object-detection-live.cpp, tutorial-face-detector-live-threaded.cpp, tutorial-face-detector-live.cpp, tutorial-grabber-opencv-threaded.cpp, tutorial-grabber-opencv.cpp, tutorial-ibvs-4pts-ogre-tracking.cpp, tutorial-image-converter.cpp, tutorial-image-filter.cpp, tutorial-klt-tracker-live-v4l2.cpp, tutorial-klt-tracker-with-reinit.cpp, tutorial-klt-tracker.cpp, tutorial-mb-generic-tracker-apriltag-rs2.cpp, tutorial-mb-generic-tracker-apriltag-webcam.cpp, tutorial-mb-generic-tracker-live.cpp, tutorial-mb-generic-tracker-rgbd-realsense.cpp, tutorial-mb-generic-tracker-rgbd.cpp, tutorial-me-ellipse-tracker.cpp, tutorial-me-line-tracker.cpp, tutorial-pose-from-points-live.cpp, and tutorial-video-recorder.cpp.

Definition at line 71 of file vpImageConvert.cpp.

References vpImage< Type >::bitmap, vpImage< Type >::getHeight(), vpImage< Type >::getWidth(), GreyToRGBa(), and vpImage< Type >::resize().

Referenced by vpVideoReader::acquire(), vpKeyPoint::buildReference(), vpImageFilter::canny(), vpMbGenericTracker::computeCurrentProjectionError(), vpDetectorDNN::detect(), vpKeyPoint::detect(), vpKeyPoint::detectExtractAffine(), vpKeyPoint::extract(), vpVideoReader::getFrame(), vpImageFilter::getGaussPyramidal(), vpDisplayOpenCV::getImage(), vpDisplay::getImage(), vpImageSimulator::init(), vpMbGenericTracker::initClick(), vpMbTracker::initClick(), vpMbTracker::initFromPoints(), vpMbTracker::initFromPose(), vpMbEdgeTracker::initPyramid(), vpKeyPoint::insertImageMatching(), vpKeyPoint::matchPoint(), vpMbKltTracker::preTracking(), vpImageIo::read(), vpImageIo::readJPEG(), vpImageIo::readPGM(), vpImageIo::readPNG(), vpImageIo::readPPM(), vpMbKltTracker::reinit(), vpVideoWriter::saveFrame(), vpMeNurbs::seekExtremitiesCanny(), vpMbDepthDenseTracker::setPose(), vpMbDepthNormalTracker::setPose(), vpMbEdgeKltTracker::setPose(), vpMbGenericTracker::setPose(), vpMbEdgeTracker::setPose(), vpMbKltTracker::setPose(), vpImageTools::templateMatching(), vpMbEdgeKltTracker::track(), vpMbKltTracker::track(), vpMbGenericTracker::track(), vpMbEdgeTracker::track(), vpImageIo::write(), vpImageIo::writePGM(), and vpImageIo::writePPM().

void vpImageConvert::convert ( const vpImage< vpRGBa > &  src,
vpImage< unsigned char > &  dest,
unsigned int  nThreads = 0 
)
static

Convert a vpImage<unsigned char> to a vpImage<vpRGBa>

Parameters
src: source image
dest: destination image
nThreads: number of threads to use if OpenMP is available. If 0 is passed, OpenMP will choose the number of threads.
See also
RGBaToGrey()

Definition at line 87 of file vpImageConvert.cpp.

References vpImage< Type >::bitmap, vpImage< Type >::getHeight(), vpImage< Type >::getWidth(), vpImage< Type >::resize(), and RGBaToGrey().

void vpImageConvert::convert ( const vpImage< float > &  src,
vpImage< unsigned char > &  dest 
)
static

Convert a vpImage<float> to a vpImage<unsigend char> by renormalizing between 0 and 255.

Parameters
src: source image
dest: destination image

Definition at line 101 of file vpImageConvert.cpp.

References vpImage< Type >::bitmap, vpImage< Type >::getHeight(), vpImage< Type >::getMinMaxValue(), vpImage< Type >::getWidth(), and vpImage< Type >::resize().

void vpImageConvert::convert ( const vpImage< unsigned char > &  src,
vpImage< float > &  dest 
)
static

Convert a vpImage<unsigned char> to a vpImage<float> by basic casting.

Parameters
src: source image
dest: destination image

Definition at line 125 of file vpImageConvert.cpp.

References vpImage< Type >::bitmap, vpImage< Type >::getHeight(), vpImage< Type >::getWidth(), and vpImage< Type >::resize().

void vpImageConvert::convert ( const vpImage< double > &  src,
vpImage< unsigned char > &  dest 
)
static

Convert a vpImage<double> to a vpImage<unsigned char> by renormalizing between 0 and 255.

Parameters
src: source image
dest: destination image

Definition at line 138 of file vpImageConvert.cpp.

References vpImage< Type >::bitmap, vpImage< Type >::getHeight(), vpImage< Type >::getMinMaxValue(), vpImage< Type >::getWidth(), and vpImage< Type >::resize().

void vpImageConvert::convert ( const vpImage< unsigned char > &  src,
vpImage< double > &  dest 
)
static

Convert a vpImage<unsigned char> to a vpImage<double> by basic casting.

Parameters
src: source image
dest: destination image

Definition at line 188 of file vpImageConvert.cpp.

References vpImage< Type >::bitmap, vpImage< Type >::getHeight(), vpImage< Type >::getWidth(), and vpImage< Type >::resize().

void vpImageConvert::convert ( const vpImage< uint16_t > &  src,
vpImage< unsigned char > &  dest 
)
static

Convert a vpImage<uint16_t> to a vpImage<unsigned char>.

Parameters
src: source image
dest: destination image

Definition at line 162 of file vpImageConvert.cpp.

References vpImage< Type >::bitmap, vpImage< Type >::getHeight(), vpImage< Type >::getSize(), vpImage< Type >::getWidth(), and vpImage< Type >::resize().

void vpImageConvert::convert ( const vpImage< unsigned char > &  src,
vpImage< uint16_t > &  dest 
)
static

Convert a vpImage<unsigned char> to a vpImage<uint16_t>.

Parameters
src: source image
dest: destination image

Definition at line 175 of file vpImageConvert.cpp.

References vpImage< Type >::bitmap, vpImage< Type >::getHeight(), vpImage< Type >::getSize(), vpImage< Type >::getWidth(), and vpImage< Type >::resize().

template<typename Type >
static void vpImageConvert::convert ( const vpImage< Type > &  src,
vpImage< Type > &  dest 
)
inlinestatic

Make a copy of an image.

Parameters
src: source image.
dest: destination image.

Definition at line 129 of file vpImageConvert.h.

void vpImageConvert::convert ( const IplImage *  src,
vpImage< vpRGBa > &  dest,
bool  flip = false 
)
static
Deprecated:
Rather then using OpenCV IplImage you should use cv::Mat images. IplImage structure will be removed with OpenCV transcient from C to C++ api.

Convert an IplImage to a vpImage<vpRGBa>.

An IplImage is an OpenCV (Intel's Open source Computer Vision Library) image structure. See http://opencvlibrary.sourceforge.net/ for general OpenCV documentation, or http://opencvlibrary.sourceforge.net/CxCore for the specific IplImage structure documentation.

If the input image has only 1 or 3 channels, the alpha channel is set to vpRGBa::alpha_default.

Warning
This function is only available if OpenCV was detected during the configuration step.
Parameters
src: Source image in OpenCV format.
dest: Destination image in ViSP format.
flip: Set to true to vertically flip the converted image.
#include <visp3/core/vpImage.h>
#include <visp3/core/vpImageConvert.h>
#include <visp3/io/vpImageIo.h>
int main()
{
#if defined(VISP_HAVE_OPENCV) && (VISP_HAVE_OPENCV_VERSION < 0x020408)
vpImage<vpRGBa> Ic; // A color image
IplImage* Ip;
// Read an image on a disk with openCV library
Ip = cvLoadImage("image.ppm", CV_LOAD_IMAGE_COLOR);
// Convert the grayscale IplImage into vpImage<vpRGBa>
// ...
// Release Ip header and data
cvReleaseImage(&Ip);
#endif
}

Definition at line 307 of file vpImageConvert.cpp.

References vpRGBa::alpha_default, vpImage< Type >::bitmap, and vpImage< Type >::resize().

void vpImageConvert::convert ( const IplImage *  src,
vpImage< unsigned char > &  dest,
bool  flip = false 
)
static
Deprecated:
Rather then using OpenCV IplImage you should use cv::Mat images. IplImage structure will be removed with OpenCV transcient from C to C++ api.

Convert an IplImage to a vpImage<unsigned char>.

An IplImage is an OpenCV (Intel's Open source Computer Vision Library) image structure. See http://opencvlibrary.sourceforge.net/ for general OpenCV documentation, or http://opencvlibrary.sourceforge.net/CxCore for the specific IplImage structure documentation.

Warning
This function is only available if OpenCV was detected during the configuration step.
Parameters
src: Source image in OpenCV format.
dest: Destination image in ViSP format.
flip: Set to true to vertically flip the converted image.
#include <visp3/core/vpImage.h>
#include <visp3/core/vpImageConvert.h>
#include <visp3/io/vpImageIo.h>
int main()
{
#if defined(VISP_HAVE_OPENCV) && (VISP_HAVE_OPENCV_VERSION < 0x020408)
vpImage<unsigned char> Ig; // A grayscale image
IplImage* Ip;
// Read an image on a disk with openCV library
Ip = cvLoadImage("image.pgm", CV_LOAD_IMAGE_GRAYSCALE);
// Convert the grayscale IplImage into vpImage<unsigned char>
// ...
// Release Ip header and data
cvReleaseImage(&Ip);
#endif
}

Definition at line 402 of file vpImageConvert.cpp.

References BGRToGrey(), vpImage< Type >::bitmap, and vpImage< Type >::resize().

void vpImageConvert::convert ( const vpImage< vpRGBa > &  src,
IplImage *&  dest 
)
static
Deprecated:
Rather then using OpenCV IplImage you should use cv::Mat images. IplImage structure will be removed with OpenCV transcient from C to C++ api.

Convert a vpImage<vpRGBa> to a IplImage.

An IplImage is an OpenCV (Intel's Open source Computer Vision Library) image structure. See http://opencvlibrary.sourceforge.net/ for general OpenCV documentation, or http://opencvlibrary.sourceforge.net/CxCore for the specific IplImage structure documentation.

Warning
This function is only available if OpenCV was detected during the configuration step.
Parameters
src: source image
dest: destination image
#include <visp3/core/vpImage.h>
#include <visp3/core/vpImageConvert.h>
#include <visp3/io/vpImageIo.h>
int main()
{
#if defined(VISP_HAVE_OPENCV) && (VISP_HAVE_OPENCV_VERSION < 0x020408)
vpImage<vpRGBa> Ic; // A color image
IplImage* Ip = NULL;
// Read an image on a disk
vpImageIo::read(Ic, "image.ppm");
// Convert the vpImage<vpRGBa> in to color IplImage
// Treatments on IplImage
//...
// Save the IplImage on the disk
cvSaveImage("Ipl.ppm", Ip);
//Release Ip header and data
cvReleaseImage(&Ip);
#endif
}

Definition at line 497 of file vpImageConvert.cpp.

References vpImage< Type >::bitmap, vpImage< Type >::getHeight(), and vpImage< Type >::getWidth().

void vpImageConvert::convert ( const vpImage< unsigned char > &  src,
IplImage *&  dest 
)
static
Deprecated:
Rather then using OpenCV IplImage you should use cv::Mat images. IplImage structure will be removed with OpenCV transcient from C to C++ api.

Convert a vpImage<unsigned char> to a IplImage.

An IplImage is an OpenCV (Intel's Open source Computer Vision Library) image structure. See http://opencvlibrary.sourceforge.net/ for general OpenCV documentation, or http://opencvlibrary.sourceforge.net/CxCore for the specific IplImage structure documentation.

Warning
This function is only available if OpenCV was detected during the configuration step.
Parameters
src: source image
dest: destination image
#include <visp3/core/vpImage.h>
#include <visp3/core/vpImageConvert.h>
#include <visp3/io/vpImageIo.h>
int main()
{
#if defined(VISP_HAVE_OPENCV) && (VISP_HAVE_OPENCV_VERSION < 0x020408)
vpImage<unsigned char> Ig; // A greyscale image
IplImage* Ip = NULL;
// Read an image on a disk
vpImageIo::read(Ig, "image.pgm");
// Convert the vpImage<unsigned char> in to greyscale IplImage
// Treatments on IplImage Ip
//...
// Save the IplImage on the disk
cvSaveImage("Ipl.pgm", Ip);
//Release Ip header and data
cvReleaseImage(&Ip);
#endif
}

Definition at line 579 of file vpImageConvert.cpp.

References vpImage< Type >::bitmap, vpImage< Type >::getHeight(), and vpImage< Type >::getWidth().

void vpImageConvert::convert ( const cv::Mat &  src,
vpImage< vpRGBa > &  dest,
bool  flip = false 
)
static

Convert a cv::Mat to a vpImage<vpRGBa>.

A cv::Mat is an OpenCV image class. See http://opencv.willowgarage.com for the general OpenCV documentation, or http://opencv.willowgarage.com/documentation/cpp/core_basic_structures.html for the specific Mat structure documentation.

Similarily to the convert(const IplImage* src, vpImage<vpRGBa> & dest, bool flip) method, only cv::Mat with a depth equal to 8 and a channel between 1 and 3 are converted.

If the input image is of type CV_8UC1 or CV_8UC3, the alpha channel is set to vpRGBa::alpha_default, or 0 in certain case (see the warning below).

Warning
This function is only available if OpenCV (version 2.1.0 or greater) was detected during the configuration step.
If ViSP is built with SSSE3 flag and the CPU supports this intrinsics set, alpha channel will be set to 0, otherwise it will be set to vpRGBa::alpha_default (255).
Parameters
src: Source image in OpenCV format.
dest: Destination image in ViSP format.
flip: Set to true to vertically flip the converted image.
#include <visp3/core/vpImage.h>
#include <visp3/core/vpImageConvert.h>
#include <visp3/core/vpRGBa.h>
#include <visp3/io/vpImageIo.h>
int main()
{
#if defined(VISP_HAVE_OPENCV) && (VISP_HAVE_OPENCV_VERSION >= 0x020100)
vpImage<vpRGBa> Ic; // A color image
cv::Mat Ip;
// Read an image on a disk with openCV library
Ip = cv::imread("image.pgm", cv::IMREAD_COLOR); // Second parameter for a BGR encoding.
// Convert the grayscale cv::Mat into vpImage<vpRGBa>
// ...
#endif
}

Definition at line 656 of file vpImageConvert.cpp.

References vpRGBa::A, vpRGBa::alpha_default, vpRGBa::B, vpImage< Type >::bitmap, vpRGBa::G, vpImage< Type >::getCols(), vpImage< Type >::getRows(), vpImage< Type >::getWidth(), vpRGBa::R, and vpImage< Type >::resize().

void vpImageConvert::convert ( const cv::Mat &  src,
vpImage< unsigned char > &  dest,
bool  flip = false,
unsigned int  nThreads = 0 
)
static

Convert a cv::Mat to a vpImage<unsigned char>.

A cv::Mat is an OpenCV image class. See http://opencv.willowgarage.com for the general OpenCV documentation, or http://opencv.willowgarage.com/documentation/cpp/core_basic_structures.html for the specific Mat structure documentation.

Similarily to the convert(const IplImage* src, vpImage<vpRGBa> & dest, bool flip) method, only Mat with a depth equal to 8 and a channel between 1 and 3 are converted.

Warning
This function is only available if OpenCV was detected during the configuration step.
Parameters
src: Source image in OpenCV format.
dest: Destination image in ViSP format.
flip: Set to true to vertically flip the converted image.
nThreads: number of threads to use if OpenMP is available. If 0 is passed, OpenMP will choose the number of threads.
#include <visp3/core/vpImage.h>
#include <visp3/core/vpImageConvert.h>
#include <visp3/io/vpImageIo.h>
int main()
{
#if defined(VISP_HAVE_OPENCV) && (VISP_HAVE_OPENCV_VERSION >= 0x020100)
vpImage<unsigned char> Ig; // A grayscale image
cv::Mat Ip;
// Read an image on a disk with openCV library
Ip = cv::imread("image.pgm", cv::IMREAD_GRAYSCALE); // Second parameter for a gray level.
// Convert the grayscale cv::Mat into vpImage<unsigned char>
// ...
#endif
}

Definition at line 757 of file vpImageConvert.cpp.

References BGRaToGrey(), BGRToGrey(), vpImage< Type >::bitmap, vpImage< Type >::getCols(), vpImage< Type >::getRows(), and vpImage< Type >::resize().

void vpImageConvert::convert ( const vpImage< vpRGBa > &  src,
cv::Mat &  dest 
)
static

Convert a vpImage<vpRGBa> to a cv::Mat color image.

A cv::Mat is an OpenCV image class. See http://opencv.willowgarage.com for the general OpenCV documentation, or http://opencv.willowgarage.com/documentation/cpp/core_basic_structures.html for the specific Mat structure documentation.

Warning
This function is only available if OpenCV version 2.1.0 or greater was detected during the configuration step.
Parameters
src: source image (vpRGBa format)
dest: destination image (BGR format)
#include <visp3/core/vpImageConvert.h>
#include <visp3/io/vpImageIo.h>
int main()
{
#if defined(VISP_HAVE_OPENCV) && (VISP_HAVE_OPENCV_VERSION >= 0x020100)
vpImage<vpRGBa> I; // A color image
cv::Mat Icv;
// Read an image on a disk
vpImageIo::read(I, "image.ppm");
// Convert the image into color cv::Mat.
// Treatments on cv::Mat Icv
//...
// Save the cv::Mat on the disk
cv::imwrite("image-cv.ppm", Icv);
#endif
}

Definition at line 853 of file vpImageConvert.cpp.

References vpImage< Type >::bitmap, vpImage< Type >::getCols(), and vpImage< Type >::getRows().

void vpImageConvert::convert ( const vpImage< unsigned char > &  src,
cv::Mat &  dest,
bool  copyData = true 
)
static

Convert a vpImage<unsigned char> to a cv::Mat grey level image.

A cv::Mat is an OpenCV image class. See http://opencv.willowgarage.com for the general OpenCV documentation, or http://opencv.willowgarage.com/documentation/cpp/core_basic_structures.html for the specific Mat structure documentation.

Warning
This function is only available if OpenCV version 2.1.0 or greater was detected during the configuration step.
Parameters
src: source image
dest: destination image
copyData: if true, the image is copied and modification in one object will not modified the other.
#include <visp3/core/vpImageConvert.h>
#include <visp3/io/vpImageIo.h>
int main()
{
#if defined(VISP_HAVE_OPENCV) && (VISP_HAVE_OPENCV_VERSION >= 0x020100)
vpImage<unsigned char> Ig; // A greyscale image
cv::Mat Ip;
// Read an image on a disk
vpImageIo::read(Ig, "image.pgm");
// Convert the vpImage<unsigned char> in to greyscale cv::Mat
// Treatments on cv::Mat Ip
//...
// Save the cv::Mat on the disk
cv::imwrite("image-cv.pgm", Ip);
#endif
}

Definition at line 897 of file vpImageConvert.cpp.

References vpImage< Type >::bitmap, vpImage< Type >::getCols(), and vpImage< Type >::getRows().

void vpImageConvert::convert ( const vpImage< unsigned char > &  src,
yarp::sig::ImageOf< yarp::sig::PixelMono > *  dest,
bool  copyData = true 
)
static

Convert a vpImage<unsigned char> to a yarp::sig::ImageOf<yarp::sig::PixelMono>

A yarp::sig::Image is a YARP image class. See http://eris.liralab.it/yarpdoc/df/d15/classyarp_1_1sig_1_1Image.html for the YARP image class documentation.

Parameters
src: Source image in ViSP format.
dest: Destination image in YARP format.
copyData: Set to true to copy all the image content. If false we only update the image pointer.
#include <visp3/core/vpImage.h>
#include <visp3/core/vpImageConvert.h>
#include <visp3/io/vpImageIo.h>
int main()
{
#if defined(VISP_HAVE_YARP)
vpImage<unsigned char> I; // A mocochrome image
// Read an image on a disk
vpImageIo::read(I, "image.pgm");
yarp::sig::ImageOf< yarp::sig::PixelMono > *Iyarp = new yarp::sig::ImageOf<yarp::sig::PixelMono >();
// Convert the vpImage<unsigned char> to a yarp::sig::ImageOf<yarp::sig::PixelMono>
// ...
#endif
}

Definition at line 945 of file vpImageConvert.cpp.

References vpImage< Type >::bitmap, vpImage< Type >::getCols(), vpImage< Type >::getHeight(), vpImage< Type >::getRows(), and vpImage< Type >::getWidth().

void vpImageConvert::convert ( const yarp::sig::ImageOf< yarp::sig::PixelMono > *  src,
vpImage< unsigned char > &  dest,
bool  copyData = true 
)
static

Convert a yarp::sig::ImageOf<yarp::sig::PixelMono> to a vpImage<unsigned char>

A yarp::sig::Image is a YARP image class. See http://eris.liralab.it/yarpdoc/df/d15/classyarp_1_1sig_1_1Image.html for the YARP image class documentation.

Parameters
src: Source image in YARP format.
dest: Destination image in ViSP format.
copyData: Set to true to copy all the image content. If false we only update the image pointer.
#include <visp3/core/vpImage.h>
#include <visp3/core/vpImageConvert.h>
#include <visp3/io/vpImageIo.h>
#if defined(VISP_HAVE_YARP)
#include <yarp/sig/ImageFile.h>
#endif
int main()
{
#if defined(VISP_HAVE_YARP)
yarp::sig::ImageOf< yarp::sig::PixelMono > *Iyarp = new yarp::sig::ImageOf<yarp::sig::PixelMono >();
// Read an image on a disk
yarp::sig::file::read(*Iyarp, "image.pgm");
// Convert the yarp::sig::ImageOf<yarp::sig::PixelMono> to a vpImage<unsigned char>
// ...
#endif
}

Definition at line 993 of file vpImageConvert.cpp.

References vpImage< Type >::bitmap, and vpImage< Type >::resize().

void vpImageConvert::convert ( const vpImage< vpRGBa > &  src,
yarp::sig::ImageOf< yarp::sig::PixelRgba > *  dest,
bool  copyData = true 
)
static

Convert a vpImage<vpRGBa> to a yarp::sig::ImageOf<yarp::sig::PixelRgba>

A yarp::sig::Image is a YARP image class. See http://eris.liralab.it/yarpdoc/df/d15/classyarp_1_1sig_1_1Image.html for the YARP image class documentation.

Parameters
src: Source image in ViSP format.
dest: Destination image in YARP format.
copyData: Set to true to copy all the image content. If false we only update the image pointer.
#include <visp3/core/vpImage.h>
#include <visp3/core/vpImageConvert.h>
#include <visp3/core/vpRGBa.h>
#include <visp3/io/vpImageIo.h>
int main()
{
#if defined(VISP_HAVE_YARP)
vpImage<vpRGBa> I; // A color image
// Read an image on a disk
vpImageIo::read(I,"image.jpg");
yarp::sig::ImageOf< yarp::sig::PixelRgba > *Iyarp = new yarp::sig::ImageOf<yarp::sig::PixelRgba >();
// Convert the vpImage<vpRGBa> to a yarp::sig::ImageOf<yarp::sig::PixelRgba>
// ...
#endif
}

Definition at line 1037 of file vpImageConvert.cpp.

References vpImage< Type >::bitmap, vpImage< Type >::getCols(), vpImage< Type >::getHeight(), vpImage< Type >::getRows(), and vpImage< Type >::getWidth().

void vpImageConvert::convert ( const yarp::sig::ImageOf< yarp::sig::PixelRgba > *  src,
vpImage< vpRGBa > &  dest,
bool  copyData = true 
)
static

Convert a yarp::sig::ImageOf<yarp::sig::PixelRgba> to a vpImage<vpRGBa>

A yarp::sig::Image is a YARP image class. See http://eris.liralab.it/yarpdoc/df/d15/classyarp_1_1sig_1_1Image.html for the YARP image class documentation.

Parameters
src: Source image in YARP format.
dest: Destination image in ViSP format.
copyData: Set to true to copy all the image content. If false we only update the image pointer.
#include <visp3/core/vpImage.h>
#include <visp3/core/vpImageConvert.h>
#include <visp3/core/vpRGBa.h>
#include <visp3/io/vpImageIo.h>
#if defined(VISP_HAVE_YARP)
#include <yarp/sig/ImageFile.h>
#endif
int main()
{
#if defined(VISP_HAVE_YARP)
yarp::sig::ImageOf< yarp::sig::PixelRgba > *Iyarp = new yarp::sig::ImageOf<yarp::sig::PixelRgba >();
// Read an image on a disk
yarp::sig::file::read(*Iyarp,"image.pgm");
// Convert the yarp::sig::ImageOf<yarp::sig::PixelRgba> to a vpImage<vpRGBa>
// ...
#endif
}

Definition at line 1085 of file vpImageConvert.cpp.

References vpImage< Type >::bitmap, and vpImage< Type >::resize().

void vpImageConvert::convert ( const vpImage< vpRGBa > &  src,
yarp::sig::ImageOf< yarp::sig::PixelRgb > *  dest 
)
static

Convert a vpImage<vpRGBa> to a yarp::sig::ImageOf<yarp::sig::PixelRgb>

A yarp::sig::Image is a YARP image class. See http://eris.liralab.it/yarpdoc/df/d15/classyarp_1_1sig_1_1Image.html for the YARP image class documentation.

Parameters
src: Source image in ViSP format.
dest: Destination image in YARP format.
#include <visp3/core/vpImage.h>
#include <visp3/core/vpImageConvert.h>
#include <visp3/core/vpRGBa.h>
#include <visp3/io/vpImageIo.h>
int main()
{
#if defined(VISP_HAVE_YARP)
vpImage<vpRGBa> I; // A color image
// Read an image on a disk
vpImageIo::read(I,"image.jpg");
yarp::sig::ImageOf< yarp::sig::PixelRgb > *Iyarp = new yarp::sig::ImageOf<yarp::sig::PixelRgb >();
// Convert the vpImage<vpRGBa> to a yarp::sig::ImageOf<yarp::sig::PixelRgb>
// ...
#endif
}

Definition at line 1127 of file vpImageConvert.cpp.

References vpImage< Type >::getHeight(), vpImage< Type >::getRows(), and vpImage< Type >::getWidth().

void vpImageConvert::convert ( const yarp::sig::ImageOf< yarp::sig::PixelRgb > *  src,
vpImage< vpRGBa > &  dest 
)
static

Convert a yarp::sig::ImageOf<yarp::sig::PixelRgb> to a vpImage<vpRGBa>

A yarp::sig::Image is a YARP image class. See http://eris.liralab.it/yarpdoc/df/d15/classyarp_1_1sig_1_1Image.html for the YARP image class documentation.

The alpha component of the resulting image is set to vpRGBa::alpha_default.

Parameters
src: Source image in YARP format.
dest: Destination image in ViSP format.
#include <visp3/core/vpImage.h>
#include <visp3/core/vpImageConvert.h>
#include <visp3/core/vpRGBa.h>
#include <visp3/io/vpImageIo.h>
#if defined(VISP_HAVE_YARP)
#include <yarp/sig/ImageFile.h>
#endif
int main()
{
#if defined(VISP_HAVE_YARP)
yarp::sig::ImageOf< yarp::sig::PixelRgb > *Iyarp = new yarp::sig::ImageOf<yarp::sig::PixelRgb >();
// Read an image on a disk
yarp::sig::file::read(*Iyarp,"image.pgm");
// Convert the yarp::sig::ImageOf<yarp::sig::PixelRgb> to a vpImage<vpRGBa>
// ...
#endif
}

Definition at line 1177 of file vpImageConvert.cpp.

References vpRGBa::alpha_default, and vpImage< Type >::resize().

void vpImageConvert::createDepthHistogram ( const vpImage< uint16_t > &  src_depth,
vpImage< unsigned char > &  dest_depth 
)
static

Convert the input 16-bits depth image to a 8-bits depth image. The input depth value is assigned a value proportional to its frequency.

Parameters
src_depth: input 16-bits depth image.
dest_depth: output grayscale depth image.

Definition at line 237 of file vpImageConvert.cpp.

References vpImage< Type >::bitmap, vpImage< Type >::getHeight(), vpImage< Type >::getSize(), vpImage< Type >::getWidth(), and vpImage< Type >::resize().

void vpImageConvert::GreyToRGB ( unsigned char *  grey,
unsigned char *  rgb,
unsigned int  size 
)
static

Convert from grey image to linear RGB image.

Note
The SIMD lib is used to accelerate processing on x86 and ARM architecture.

Definition at line 3504 of file vpImageConvert.cpp.

void vpImageConvert::GreyToRGBa ( unsigned char *  grey,
unsigned char *  rgba,
unsigned int  width,
unsigned int  height 
)
static

Convert from grey image to linear RGBa image. The alpha component is set to vpRGBa::alpha_default.

Note
The SIMD lib is used to accelerate processing on x86 and ARM architecture.

Definition at line 3483 of file vpImageConvert.cpp.

References vpRGBa::alpha_default.

Referenced by vp1394CMUGrabber::acquire(), vpV4l2Grabber::acquire(), vp1394TwoGrabber::acquire(), convert(), vp1394TwoGrabber::dequeue(), and GreyToRGBa().

void vpImageConvert::GreyToRGBa ( unsigned char *  grey,
unsigned char *  rgba,
unsigned int  size 
)
static

Convert from grey image to linear RGBa image. The alpha component is set to vpRGBa::alpha_default.

Note
The SIMD lib is used to accelerate processing on x86 and ARM architecture.

Definition at line 3494 of file vpImageConvert.cpp.

References GreyToRGBa().

void vpImageConvert::HSVToRGB ( const double *  hue,
const double *  saturation,
const double *  value,
unsigned char *  rgb,
unsigned int  size 
)
static

Converts an array of hue, saturation and value to an array of RGB values.

Parameters
hue: Array of hue values (range between [0 - 1]).
saturation: Array of saturation values (range between [0 - 1]).
value: Array of value values (range between [0 - 1]).
rgb: RGB array values converted from RGB color space.
size: The total image size or the number of pixels.
Examples:
testDisplayPolygonLines.cpp.

Definition at line 4342 of file vpImageConvert.cpp.

Referenced by HSVToRGB().

void vpImageConvert::HSVToRGB ( const unsigned char *  hue,
const unsigned char *  saturation,
const unsigned char *  value,
unsigned char *  rgb,
unsigned int  size 
)
static

Converts an array of hue, saturation and value to an array of RGB values.

Parameters
hue: Array of hue values (range between [0 - 255]).
saturation: Array of saturation values (range between [0 - 255]).
value: Array of value values (range between [0 - 255]).
rgb: RGB array values converted from HSV color space.
size: The total image size or the number of pixels.

Definition at line 4357 of file vpImageConvert.cpp.

References HSVToRGB().

void vpImageConvert::HSVToRGBa ( const double *  hue,
const double *  saturation,
const double *  value,
unsigned char *  rgba,
unsigned int  size 
)
static

Converts an array of hue, saturation and value to an array of RGBa values.

Alpha component of the converted image is set to vpRGBa::alpha_default.

Parameters
hue: Array of hue values (range between [0 - 1]).
saturation: Array of saturation values (range between [0 - 1]).
value: Array of value values (range between [0 - 1]).
rgba: RGBa array values (with alpha channel set to zero) converted from HSV color space.
size: The total image size or the number of pixels.
Examples:
testConversion.cpp.

Definition at line 4263 of file vpImageConvert.cpp.

Referenced by vp::equalizeHistogram(), HSVToRGBa(), and vp::stretchContrastHSV().

void vpImageConvert::HSVToRGBa ( const unsigned char *  hue,
const unsigned char *  saturation,
const unsigned char *  value,
unsigned char *  rgba,
unsigned int  size 
)
static

Converts an array of hue, saturation and value to an array of RGBa values.

Alpha component of the converted image is set to vpRGBa::alpha_default.

Parameters
hue: Array of hue values (range between [0 - 255]).
saturation: Array of saturation values (range between [0 - 255]).
value: Array of value values (range between [0 - 255]).
rgba: RGBa array values (with alpha channel set to zero) converted from HSV color space.
size: The total image size or the number of pixels.

Definition at line 4281 of file vpImageConvert.cpp.

References HSVToRGBa().

void vpImageConvert::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

Merge 4 channels into an RGBa image.

Parameters
R: Red channel.
G: Green channel.
B: Blue channel.
a: Alpha channel.
RGBa: Destination RGBa image.
Note
If R, G, B, a are provided, the SIMD lib is used to accelerate processing on x86 and ARM architecture.
Examples:
grabV4l2MultiCpp11Thread.cpp, testColorConversion.cpp, and testConversion.cpp.

Definition at line 4019 of file vpImageConvert.cpp.

References vpRGBa::A, vpRGBa::B, vpImage< Type >::bitmap, vpException::dimensionError, vpRGBa::G, vpImage< Type >::getHeight(), vpImage< Type >::getWidth(), vpRGBa::R, and vpImage< Type >::resize().

void vpImageConvert::MONO16ToGrey ( unsigned char *  grey16,
unsigned char *  grey,
unsigned int  size 
)
static

Converts a MONO16 grey scale image (each pixel is coded by two bytes) into a grey image where each pixels are coded on one byte.

Parameters
grey16: Input image to convert (two bytes per pixel).
grey: Output image (one byte per pixel)
size: The image size or the number of pixels.

Definition at line 4087 of file vpImageConvert.cpp.

Referenced by vp1394CMUGrabber::acquire(), and vp1394TwoGrabber::dequeue().

void vpImageConvert::MONO16ToRGBa ( unsigned char *  grey16,
unsigned char *  rgba,
unsigned int  size 
)
static

Converts a MONO16 grey scale image (each pixel is coded by two bytes) into a grey image where each pixels are coded on one byte.

Alpha component is set to vpRGBa::alpha_default.

Parameters
grey16: Input image to convert (two bytes per pixel).
rgba: Output image.
size: The image size or the number of pixels.

Definition at line 4108 of file vpImageConvert.cpp.

References vpRGBa::alpha_default, vpMath::equal(), and vpMath::round().

Referenced by vp1394CMUGrabber::acquire(), and vp1394TwoGrabber::dequeue().

void vpImageConvert::RGBaToGrey ( unsigned char *  rgba,
unsigned char *  grey,
unsigned int  width,
unsigned int  height,
unsigned int  nThreads = 0 
)
static

Weights convert from linear RGBa to CIE luminance assuming a modern monitor. See Charles Pontyon's Colour FAQ http://www.poynton.com/notes/colour_and_gamma/ColorFAQ.html

Note
The SIMD lib is used to accelerate processing on x86 and ARM architecture.

Definition at line 3448 of file vpImageConvert.cpp.

Referenced by vpV4l2Grabber::acquire(), convert(), and vpRealSense2::getGreyFrame().

void vpImageConvert::RGBaToGrey ( unsigned char *  rgba,
unsigned char *  grey,
unsigned int  size 
)
static

Weights convert from linear RGBa to CIE luminance assuming a modern monitor. See Charles Pontyon's Colour FAQ http://www.poynton.com/notes/colour_and_gamma/ColorFAQ.html

Note
The SIMD lib is used to accelerate processing on x86 and ARM architecture.

Definition at line 3472 of file vpImageConvert.cpp.

void vpImageConvert::RGBaToHSV ( const unsigned char *  rgba,
double *  hue,
double *  saturation,
double *  value,
unsigned int  size 
)
static

Converts an array of RGBa to an array of hue, saturation, value values. The alpha channel is not used.

Parameters
rgba: RGBa array values.
hue: Array of hue values converted from RGB color space (range between [0 - 1]).
saturation: Array of saturation values converted from RGB color space (range between [0 - 1]).
value: Array of value values converted from RGB color space (range between [0 - 1]).
size: The total image size or the number of pixels.
Examples:
testConversion.cpp.

Definition at line 4303 of file vpImageConvert.cpp.

Referenced by vp::equalizeHistogram(), RGBaToHSV(), and vp::stretchContrastHSV().

void vpImageConvert::RGBaToHSV ( const unsigned char *  rgba,
unsigned char *  hue,
unsigned char *  saturation,
unsigned char *  value,
unsigned int  size 
)
static

Converts an array of RGBa to an array of hue, saturation, value values. The alpha channel is not used.

Parameters
rgba: RGBa array values.
hue: Array of hue values converted from RGB color space (range between [0 - 255]).
saturation: Array of saturation values converted from RGB color space (range between [0 - 255]).
value: Array of value values converted from RGB color space (range between [0 - 255]).
size: The total image size or the number of pixels.

Definition at line 4320 of file vpImageConvert.cpp.

References RGBaToHSV().

void vpImageConvert::RGBaToRGB ( unsigned char *  rgba,
unsigned char *  rgb,
unsigned int  size 
)
static

Convert RGB image into RGBa image.

The alpha component of the converted image is set to vpRGBa::alpha_default.

Note
The SIMD lib is used to accelerate processing on x86 and ARM architecture.
Examples:
testColorConversion.cpp, and testConversion.cpp.

Definition at line 3386 of file vpImageConvert.cpp.

void vpImageConvert::RGBToGrey ( unsigned char *  rgb,
unsigned char *  grey,
unsigned int  width,
unsigned int  height,
bool  flip = false 
)
static

Converts a RGB image to greyscale. Flips the image verticaly if needed. Assumes that grey is already resized.

Note
If flip is false, the SIMD lib is used to accelerate processing on x86 and ARM architecture.
Examples:
testColorConversion.cpp, and testConversion.cpp.

Definition at line 3408 of file vpImageConvert.cpp.

Referenced by vp1394CMUGrabber::acquire(), vpV4l2Grabber::acquire(), vp1394TwoGrabber::dequeue(), vpRealSense2::getGreyFrame(), vpSimulator::getInternalImage(), and RGBToGrey().

void vpImageConvert::RGBToGrey ( unsigned char *  rgb,
unsigned char *  grey,
unsigned int  size 
)
static

Weights convert from linear RGB to CIE luminance assuming a modern monitor. See Charles Pontyon's Colour FAQ http://www.poynton.com/notes/colour_and_gamma/ColorFAQ.html

Definition at line 3396 of file vpImageConvert.cpp.

References RGBToGrey().

void vpImageConvert::RGBToHSV ( const unsigned char *  rgb,
double *  hue,
double *  saturation,
double *  value,
unsigned int  size 
)
static

Converts an array of RGB to an array of hue, saturation, value values.

Parameters
rgb: RGB array values.
hue: Array of hue values converted from RGB color space (range between [0 - 1]).
saturation: Array of saturation values converted from RGB color space (range between [0 - 1]).
value: Array of value values converted from RGB color space (range between [0 - 1]).
size: The total image size or the number of pixels.

Definition at line 4378 of file vpImageConvert.cpp.

Referenced by RGBToHSV().

void vpImageConvert::RGBToHSV ( const unsigned char *  rgb,
unsigned char *  hue,
unsigned char *  saturation,
unsigned char *  value,
unsigned int  size 
)
static

Converts an array of RGB to an array of hue, saturation, value values.

Parameters
rgb: RGB array values.
hue: Array of hue values converted from RGB color space (range between [0 - 255]).
saturation: Array of saturation values converted from RGB color space (range between [0 - 255]).
value: Array of value values converted from RGB color space (range between [0 - 255]).
size: The total image size or the number of pixels.

Definition at line 4394 of file vpImageConvert.cpp.

References RGBToHSV().

void vpImageConvert::RGBToRGBa ( unsigned char *  rgb,
unsigned char *  rgba,
unsigned int  size 
)
static
void vpImageConvert::RGBToRGBa ( unsigned char *  rgb,
unsigned char *  rgba,
unsigned int  width,
unsigned int  height,
bool  flip = false 
)
static

Converts a RGB image to RGBa. Alpha component is set to vpRGBa::alpha_default.

Flips the image verticaly if needed. Assumes that rgba is already resized.

Note
If flip is false, the SIMD lib is used to accelerate processing on x86 and ARM architecture.

Definition at line 3349 of file vpImageConvert.cpp.

References vpRGBa::alpha_default.

void vpImageConvert::split ( const vpImage< vpRGBa > &  src,
vpImage< unsigned char > *  pR,
vpImage< unsigned char > *  pG,
vpImage< unsigned char > *  pB,
vpImage< unsigned char > *  pa = NULL 
)
static

Split an image from vpRGBa format to monochrome channels.

Parameters
src: source image.
pR: red channel. Set as NULL if not needed.
pG: green channel. Set as NULL if not needed.
pB: blue channel. Set as NULL if not needed.
pa: alpha channel. Set as NULL if not needed.
Note
The SIMD lib is used to accelerate processing on x86 and ARM architecture.

Example code using split:

#include <visp3/core/vpImage.h>
#include <visp3/core/vpImageConvert.h>
#include <visp3/io/vpImageIo.h>
int main()
{
vpImage<vpRGBa> Ic; // A color image
// Load a color image from the disk
vpImageIo::read(Ic,"image.ppm");
// Only R and B Channels are desired.
// Split Ic color image
// R and B will be resized in split function if needed
vpImageConvert::split(Ic, &R, NULL, &B, NULL);
// Save the the R Channel.
vpImageIo::write(R, "RChannel.pgm");
}
Examples:
grabV4l2MultiCpp11Thread.cpp, testColorConversion.cpp, testConversion.cpp, and testGaussianFilter.cpp.

Definition at line 3965 of file vpImageConvert.cpp.

References vpImage< Type >::bitmap, vpImage< Type >::getHeight(), vpImage< Type >::getSize(), vpImage< Type >::getWidth(), and vpImage< Type >::resize().

Referenced by vp::clahe(), vp::equalizeHistogram(), vp::stretchContrast(), and vp::unsharpMask().

void vpImageConvert::YCbCrToGrey ( unsigned char *  yuv,
unsigned char *  grey,
unsigned int  size 
)
static

Convert an image from YCrCb 4:2:2 (Y0 Cr01 Y1 Cb01 Y2 Cr23 Y3 ...) to grey format. Destination grey image memory area has to be allocated before.

  • In YCrCb (4:2:2) format each pixel is coded using 16 bytes. Byte 0: YO (Luma for Pixel 0) Byte 1: Chroma Red Cr (Red Chroma for Pixel 0 and 1) Byte 2: Y1 (Luma for Pixel 1) Byte 3: Chroma blue Cb (Blue Chroma for Pixel 0 and 1) Byte 4: Y2 (Luma for Pixel 2)
  • In grey format, each pixel is coded using 8 bytes.

Definition at line 3814 of file vpImageConvert.cpp.

void vpImageConvert::YCbCrToRGB ( unsigned char *  ycbcr,
unsigned char *  rgb,
unsigned int  size 
)
static

Convert an image from YCbCr 4:2:2 (Y0 Cb01 Y1 Cr01 Y2 Cb23 Y3 ...) to RGB format. Destination rgb memory area has to be allocated before.

  • In YCbCr (4:2:2) format each pixel is coded using 16 bytes. Byte 0: YO (Luma for Pixel 0) Byte 1: Chroma Blue Cb (Blue Chroma for Pixel 0 and 1) Byte 2: Y1 (Luma for Pixel 1) Byte 3: Chroma Red Cr (Red Chroma for Pixel 0 and 1) Byte 4: Y2 (Luma for Pixel 2)
  • In RGB format, each pixel is coded using 24 bytes. Byte 0: Red Byte 1: Green Byte 2: Blue

Definition at line 3711 of file vpImageConvert.cpp.

References vpDEBUG_TRACE.

void vpImageConvert::YCbCrToRGBa ( unsigned char *  ycbcr,
unsigned char *  rgba,
unsigned int  size 
)
static

Convert an image from YCbCr 4:2:2 (Y0 Cb01 Y1 Cr01 Y2 Cb23 Y3...) to RGBa format. Destination rgba memory area has to be allocated before.

The alpha component of the converted image is set to vpRGBa::alpha_default.

  • In YCbCr (4:2:2) format each pixel is coded using 16 bytes. Byte 0: YO (Luma for Pixel 0) Byte 1: Chroma Blue Cb (Blue Chroma for Pixel 0 and 1) Byte 2: Y1 (Luma for Pixel 1) Byte 3: Chroma Red Cr (Red Chroma for Pixel 0 and 1) Byte 4: Y2 (Luma for Pixel 2)
  • In RGBa format, each pixel is coded using 24 bytes. Byte 0: Red Byte 1: Green Byte 2: Blue Byte 3: -

Definition at line 3765 of file vpImageConvert.cpp.

References vpRGBa::alpha_default, and vpDEBUG_TRACE.

void vpImageConvert::YCrCbToRGB ( unsigned char *  ycrcb,
unsigned char *  rgb,
unsigned int  size 
)
static

Convert an image from YCrCb 4:2:2 (Y0 Cr01 Y1 Cb01 Y2 Cr23 Y3 ...) to RGB format. Destination rgb memory area has to be allocated before.

  • In YCrCb (4:2:2) format each pixel is coded using 16 bytes. Byte 0: YO (Luma for Pixel 0) Byte 1: Chroma Red Cr (Red Chroma for Pixel 0 and 1) Byte 2: Y1 (Luma for Pixel 1) Byte 3: Chroma blue Cb (Blue Chroma for Pixel 0 and 1) Byte 4: Y2 (Luma for Pixel 2)
  • In RGB format, each pixel is coded using 24 bytes. Byte 0: Red Byte 1: Green Byte 2: Blue

Definition at line 3841 of file vpImageConvert.cpp.

References vpDEBUG_TRACE.

void vpImageConvert::YCrCbToRGBa ( unsigned char *  ycrcb,
unsigned char *  rgba,
unsigned int  size 
)
static

Convert an image from YCrCb 4:2:2 (Y0 Cr01 Y1 Cb01 Y2 Cr23 Y3 ...) to RGBa format. Destination rgba memory area has to be allocated before.

The alpha component of the resulting image is set to vpRGBa::alpha_default.

  • In YCrCb (4:2:2) format each pixel is coded using 16 bytes. Byte 0: YO (Luma for Pixel 0) Byte 1: Chroma Red Cr (Red Chroma for Pixel 0 and 1) Byte 2: Y1 (Luma for Pixel 1) Byte 3: Chroma blue Cb (Blue Chroma for Pixel 0 and 1) Byte 4: Y2 (Luma for Pixel 2)
  • In RGBa format, each pixel is coded using 24 bytes. Byte 0: Red Byte 1: Green Byte 2: Blue Byte 3: -

Definition at line 3894 of file vpImageConvert.cpp.

References vpRGBa::alpha_default, and vpDEBUG_TRACE.

void vpImageConvert::YUV411ToGrey ( unsigned char *  yuv,
unsigned char *  grey,
unsigned int  size 
)
static

Convert YUV411 into Grey yuv411 : u y1 y2 v y3 y4

Definition at line 1581 of file vpImageConvert.cpp.

Referenced by vp1394CMUGrabber::acquire(), and vp1394TwoGrabber::dequeue().

void vpImageConvert::YUV411ToRGB ( unsigned char *  yuv,
unsigned char *  rgb,
unsigned int  size 
)
static

Convert YUV411 into RGB yuv411 : u y1 y2 v y3 y4

Definition at line 1706 of file vpImageConvert.cpp.

References YUVToRGB().

void vpImageConvert::YUV411ToRGBa ( unsigned char *  yuv,
unsigned char *  rgba,
unsigned int  size 
)
static

Convert YUV411 (u y1 y2 v y3 y4) images into RGBa images. The alpha component of the converted image is set to vpRGBa::alpha_default.

Definition at line 1328 of file vpImageConvert.cpp.

References vpRGBa::alpha_default, and YUVToRGB().

Referenced by vp1394CMUGrabber::acquire(), vp1394TwoGrabber::acquire(), and vp1394TwoGrabber::dequeue().

void vpImageConvert::YUV420ToGrey ( unsigned char *  yuv,
unsigned char *  grey,
unsigned int  size 
)
static

Convert YUV420 [Y(NxM), U(N/2xM/2), V(N/2xM/2)] image into grey image.

Definition at line 2116 of file vpImageConvert.cpp.

void vpImageConvert::YUV420ToRGB ( unsigned char *  yuv,
unsigned char *  rgb,
unsigned int  width,
unsigned int  height 
)
static

Convert YUV420 [Y(NxM), U(N/2xM/2), V(N/2xM/2)] image into RGB image.

Definition at line 1989 of file vpImageConvert.cpp.

void vpImageConvert::YUV420ToRGBa ( unsigned char *  yuv,
unsigned char *  rgba,
unsigned int  width,
unsigned int  height 
)
static

Convert YUV420 [Y(NxM), U(N/2xM/2), V(N/2xM/2)] image into RGBa image.

The alpha component of the converted image is set to vpRGBa::alpha_default.

Definition at line 1858 of file vpImageConvert.cpp.

References vpRGBa::alpha_default.

void vpImageConvert::YUV422ToGrey ( unsigned char *  yuv,
unsigned char *  grey,
unsigned int  size 
)
static

Convert YUV 4:2:2 (u01 y0 v01 y1 u23 y2 v23 y3 ...) images into Grey. Destination grey memory area has to be allocated before.

See also
YUYVToGrey()

Definition at line 1691 of file vpImageConvert.cpp.

Referenced by vp1394CMUGrabber::acquire(), and vp1394TwoGrabber::dequeue().

void vpImageConvert::YUV422ToRGB ( unsigned char *  yuv,
unsigned char *  rgb,
unsigned int  size 
)
static

Convert YUV 4:2:2 (u01 y0 v01 y1 u23 y2 v23 y3 ...) images into RGB images. Destination rgb memory area has to be allocated before.

See also
YUYVToRGB()

Definition at line 1602 of file vpImageConvert.cpp.

References YUVToRGB().

void vpImageConvert::YUV422ToRGBa ( unsigned char *  yuv,
unsigned char *  rgba,
unsigned int  size 
)
static

Convert YUV 4:2:2 (u01 y0 v01 y1 u23 y2 v23 y3 ...) images into RGBa images. Destination rgba memory area has to be allocated before.

The alpha component of the converted image is set to vpRGBa::alpha_default.

See also
YUYVToRGBa()

Definition at line 1489 of file vpImageConvert.cpp.

References vpRGBa::alpha_default, and YUVToRGB().

Referenced by vp1394CMUGrabber::acquire(), vp1394TwoGrabber::acquire(), and vp1394TwoGrabber::dequeue().

void vpImageConvert::YUV444ToGrey ( unsigned char *  yuv,
unsigned char *  grey,
unsigned int  size 
)
static

Convert YUV444 (u y v) image into grey image.

Definition at line 2211 of file vpImageConvert.cpp.

Referenced by vp1394CMUGrabber::acquire(), and vp1394TwoGrabber::dequeue().

void vpImageConvert::YUV444ToRGB ( unsigned char *  yuv,
unsigned char *  rgb,
unsigned int  size 
)
static

Convert YUV444 (u y v) image into RGB image.

Definition at line 2170 of file vpImageConvert.cpp.

void vpImageConvert::YUV444ToRGBa ( unsigned char *  yuv,
unsigned char *  rgba,
unsigned int  size 
)
static

Convert YUV444 (u y v) image into RGBa image.

The alpha component of the converted image is set to vpRGBa::alpha_default.

Definition at line 2128 of file vpImageConvert.cpp.

References vpRGBa::alpha_default.

Referenced by vp1394CMUGrabber::acquire(), vp1394TwoGrabber::acquire(), and vp1394TwoGrabber::dequeue().

static void vpImageConvert::YUVToRGB ( unsigned char  y,
unsigned char  u,
unsigned char  v,
unsigned char &  r,
unsigned char &  g,
unsigned char &  b 
)
inlinestatic

Converts a yuv pixel value in rgb format.

Parameters
yY component of a pixel.
uU component of a pixel.
vV component of a pixel.
rRed component from the YUV coding format. This value is computed using:

\[ r = 0.9999695*y - 0.0009508*(u-128) + 1.1359061*(v-128) \]

gGreen component from the YUV coding format. This value is computed using:

\[g = 0.9999695*y - 0.3959609*(u-128) - 0.5782955*(v-128) \]

bBlue component from the YUV coding format. This value is computed using:

\[b = 0.9999695*y + 2.04112*(u-128) - 0.0016314*(v-128) \]

Examples:
testConversion.cpp.

Definition at line 182 of file vpImageConvert.h.

Referenced by YUV411ToRGB(), YUV411ToRGBa(), YUV422ToRGB(), and YUV422ToRGBa().

void vpImageConvert::YUYVToGrey ( unsigned char *  yuyv,
unsigned char *  grey,
unsigned int  size 
)
static

Convert an image from YUYV 4:2:2 (y0 u01 y1 v01 y2 u23 y3 v23 ...) to grey. Destination rgb memory area has to be allocated before.

See also
YUV422ToGrey()

Definition at line 1313 of file vpImageConvert.cpp.

Referenced by vpV4l2Grabber::acquire().

void vpImageConvert::YUYVToRGB ( unsigned char *  yuyv,
unsigned char *  rgb,
unsigned int  width,
unsigned int  height 
)
static

Convert an image from YUYV 4:2:2 (y0 u01 y1 v01 y2 u23 y3 v23 ...) to RGB24. Destination rgb memory area has to be allocated before.

See also
YUV422ToRGB()

Definition at line 1261 of file vpImageConvert.cpp.

void vpImageConvert::YUYVToRGBa ( unsigned char *  yuyv,
unsigned char *  rgba,
unsigned int  width,
unsigned int  height 
)
static

Convert an image from YUYV 4:2:2 (y0 u01 y1 v01 y2 u23 y3 v23 ...) to RGB32. Destination rgba memory area has to be allocated before.

The alpha component of the converted image is set to vpRGBa::alpha_default.

See also
YUV422ToRGBa()

Definition at line 1207 of file vpImageConvert.cpp.

References vpRGBa::alpha_default.

Referenced by vpV4l2Grabber::acquire().

void vpImageConvert::YV12ToRGB ( unsigned char *  yuv,
unsigned char *  rgb,
unsigned int  height,
unsigned int  width 
)
static

Convert YV12 [Y(NxM), V(N/2xM/2), U(N/2xM/2)] image into RGB image.

Definition at line 2356 of file vpImageConvert.cpp.

void vpImageConvert::YV12ToRGBa ( unsigned char *  yuv,
unsigned char *  rgba,
unsigned int  width,
unsigned int  height 
)
static

Convert YV12 [Y(NxM), V(N/2xM/2), U(N/2xM/2)] image into RGBa image.

The alpha component of the converted image is set to vpRGBa::alpha_default.

Definition at line 2225 of file vpImageConvert.cpp.

References vpRGBa::alpha_default.

void vpImageConvert::YVU9ToRGB ( unsigned char *  yuv,
unsigned char *  rgb,
unsigned int  height,
unsigned int  width 
)
static

Convert YV12 [Y(NxM), V(N/4xM/4), U(N/4xM/4)] image into RGB image.

Definition at line 2917 of file vpImageConvert.cpp.

void vpImageConvert::YVU9ToRGBa ( unsigned char *  yuv,
unsigned char *  rgba,
unsigned int  width,
unsigned int  height 
)
static

Convert YVU9 [Y(NxM), V(N/4xM/4), U(N/4xM/4)] image into RGBa image.

The alpha component of the converted image is set to vpRGBa::alpha_default.

Definition at line 2485 of file vpImageConvert.cpp.

References vpRGBa::alpha_default.