Visual Servoing Platform
version 3.6.1 under development (2024-11-21)
|
#include <visp3/core/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 | createDepthHistogram (const vpImage< float > &src_depth, vpImage< vpRGBa > &dest_depth) |
static void | createDepthHistogram (const vpImage< float > &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< vpRGBf > &src, vpImage< vpRGBa > &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, unsigned char bitshift=8) |
static void | convert (const vpImage< unsigned char > &src, vpImage< uint16_t > &dest, unsigned char bitshift=8) |
template<typename Type > | |
static void | convert (const vpImage< Type > &src, vpImage< Type > &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 cv::Mat &src, vpImage< float > &dest, bool flip=false) |
static void | convert (const cv::Mat &src, vpImage< double > &dest, bool flip=false) |
static void | convert (const cv::Mat &src, vpImage< vpRGBf > &dest, bool flip=false) |
static void | convert (const cv::Mat &src, vpImage< uint16_t > &dest, bool flip=false) |
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< float > &src, cv::Mat &dest, bool copyData=true) |
static void | convert (const vpImage< double > &src, cv::Mat &dest, bool copyData=true) |
static void | convert (const vpImage< vpRGBf > &src, cv::Mat &dest) |
static int | depthToPointCloud (const vpImage< uint16_t > &depth_raw, float depth_scale, const vpCameraParameters &cam_depth, pcl::PointCloud< pcl::PointXYZ >::Ptr pointcloud, std::mutex *pointcloud_mutex=nullptr, const vpImage< unsigned char > *mask=nullptr, float Z_min=0.2, float Z_max=2.5) |
static int | depthToPointCloud (const vpImage< vpRGBa > &color, const vpImage< uint16_t > &depth_raw, float depth_scale, const vpCameraParameters &cam_depth, pcl::PointCloud< pcl::PointXYZRGB >::Ptr pointcloud, std::mutex *pointcloud_mutex=nullptr, const vpImage< unsigned char > *mask=nullptr, float Z_min=0.2, float Z_max=2.5) |
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 | 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 | YCbCrToGrey (unsigned char *ycbcr, unsigned char *grey, unsigned int size) |
static void | YCrCbToRGB (unsigned char *ycrcb, unsigned char *rgb, unsigned int size) |
static void | YCrCbToRGBa (unsigned char *ycrcb, unsigned char *rgb, 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, bool h_full=true) |
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, bool h_full=true) |
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, bool h_full=true) |
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, bool h_full=true) |
static void | demosaicBGGRToRGBaBilinear (const uint8_t *bggr, uint8_t *rgba, unsigned int width, unsigned int height, unsigned int nThreads=0) |
static void | demosaicBGGRToRGBaBilinear (const uint16_t *bggr, uint16_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 | demosaicGBRGToRGBaBilinear (const uint16_t *gbrg, uint16_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 | demosaicGRBGToRGBaBilinear (const uint16_t *grbg, uint16_t *rgba, unsigned int width, unsigned int height, unsigned int nThreads=0) |
static void | demosaicRGGBToRGBaBilinear (const uint8_t *rggb, uint8_t *rgba, unsigned int width, unsigned int height, unsigned int nThreads=0) |
static void | demosaicRGGBToRGBaBilinear (const uint16_t *rggb, uint16_t *rgba, unsigned int width, unsigned int height, unsigned int nThreads=0) |
static void | demosaicBGGRToRGBaMalvar (const uint8_t *bggr, uint8_t *rgba, unsigned int width, unsigned int height, unsigned int nThreads=0) |
static void | demosaicBGGRToRGBaMalvar (const uint16_t *bggr, uint16_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 | demosaicGBRGToRGBaMalvar (const uint16_t *gbrg, uint16_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 | demosaicGRBGToRGBaMalvar (const uint16_t *grbg, uint16_t *rgba, unsigned int width, unsigned int height, unsigned int nThreads=0) |
static void | demosaicRGGBToRGBaMalvar (const uint8_t *rggb, uint8_t *rgba, unsigned int width, unsigned int height, unsigned int nThreads=0) |
static void | demosaicRGGBToRGBaMalvar (const uint16_t *rggb, uint16_t *rgba, unsigned int width, unsigned int height, unsigned int nThreads=0) |
Convert image types.
The following example available in tutorial-image-converter.cpp shows how to convert an OpenCV cv::Mat image into a vpImage:
Definition at line 91 of file vpImageConvert.h.
|
static |
Converts a BGRa image to greyscale. Flips the image vertically if needed. Assumes that grey is already resized.
[in] | bgra | : Pointer to the bitmap containing the 32-bits BGRa data. |
[out] | grey | : Pointer to the 8-bits grey bitmap that should be allocated with a size of width * height. |
[in] | width,height | : Image size. |
[in] | flip | : When true, image is flipped vertically. |
[in] | nThreads | : When > 0, the value is used to set the number of OpenMP threads used for the conversion. |
Definition at line 784 of file vpImageConvert.cpp.
Referenced by convert().
|
static |
Converts a BGRa image to RGBa.
Flips the image vertically if needed. Assumes that rgba is already resized before calling this function.
[in] | bgra | : Pointer to the bitmap containing the 32-bits BGRa data. |
[out] | rgba | : Pointer to the 32-bits RGBA bitmap that should be allocated with a size of width * height * 4. |
[in] | width,height | : Image size. |
[in] | flip | : When true, image is flipped vertically. |
Definition at line 674 of file vpImageConvert.cpp.
|
static |
Converts a BGR image to greyscale. Flips the image vertically if needed. Assumes that grey is already resized.
[in] | bgr | : Pointer to the bitmap containing the 24-bits BGR data. |
[out] | grey | : Pointer to the 8-bits grey bitmap that should be allocated with a size of width * height. |
[in] | width,height | : Image size. |
[in] | flip | : When true, image is flipped vertically. |
[in] | nThreads | : When > 0, the value is used to set the number of OpenMP threads used for the conversion. |
Definition at line 722 of file vpImageConvert.cpp.
Referenced by vpV4l2Grabber::acquire(), convert(), vpRobotBebop2::getGrayscaleImage(), and vpRealSense2::getGreyFrame().
|
static |
Converts a BGR image to RGBa. The alpha component is set to vpRGBa::alpha_default.
Flips the image vertically if needed. Assumes that rgba is already resized.
[in] | bgr | : Pointer to the bitmap containing the 24-bits BGR data. |
[out] | rgba | : Pointer to the 32-bits RGBA bitmap that should be allocated with a size of width * height * 4. |
[in] | width,height | : Image size. |
[in] | flip | : When true, image is flipped vertically. |
Definition at line 626 of file vpImageConvert.cpp.
References vpRGBa::alpha_default.
Referenced by vpV4l2Grabber::acquire(), vpRealSense2::getColorFrame(), and vpRobotBebop2::getRGBaImage().
|
static |
Converts cv::Mat CV_32FC1 format to ViSP vpImage<double>.
[in] | src | : OpenCV image in CV_32FC1 format. |
[out] | dest | : ViSP image in double format. |
[in] | flip | : When true during conversion flip image vertically. |
Definition at line 334 of file vpImageConvert_opencv.cpp.
References convert(), and vpImage< Type >::resize().
|
static |
Converts cv::Mat CV_32FC1 / CV_16SC1 format to ViSP vpImage<float>.
[in] | src | : OpenCV image in CV_32FC1 / CV_16SC1 format. |
[out] | dest | : ViSP image in float format. |
[in] | flip | : When true during conversion flip image vertically. |
Definition at line 292 of file vpImageConvert_opencv.cpp.
References vpException::badValue, vpImage< Type >::getCols(), vpImage< Type >::getRows(), and vpImage< Type >::resize().
|
static |
Converts cv::Mat CV_16UC1 format to ViSP vpImage<uint16_t>.
[in] | src | : OpenCV image in CV_16UC1 format. |
[out] | dest | : ViSP image in uint16_t format. |
[in] | flip | : When true during conversion flip image vertically. |
Definition at line 355 of file vpImageConvert_opencv.cpp.
References vpImage< Type >::bitmap, vpException::fatalError, vpImage< Type >::getCols(), vpImage< Type >::getRows(), and vpImage< Type >::resize().
|
static |
Convert a cv::Mat to a vpImage<unsigned char>.
A cv::Mat is an OpenCV image class.
[in] | src | : Source image in OpenCV format. |
[out] | dest | : Destination image in ViSP format. |
[in] | flip | : Set to true to vertically flip the converted image. |
[in] | nThreads | : number of threads to use if OpenMP is available. If 0 is passed, OpenMP will choose the number of threads. |
Definition at line 213 of file vpImageConvert_opencv.cpp.
References BGRaToGrey(), BGRToGrey(), vpImage< Type >::bitmap, vpImage< Type >::getCols(), vpImage< Type >::getRows(), and vpImage< Type >::resize().
|
static |
Convert a cv::Mat to a vpImage<vpRGBa>.
A cv::Mat is an OpenCV image class.
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).
[in] | src | : Source image in OpenCV format. |
[out] | dest | : Destination image in ViSP format. |
[in] | flip | : Set to true to vertically flip the converted image. |
Definition at line 93 of file vpImageConvert_opencv.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().
|
static |
Converts cv::Mat CV_32FC3 format to ViSP vpImage<vpRGBf>.
[in] | src | : OpenCV image in CV_32FC3 format. |
[out] | dest | : ViSP image in vpRGBf format. |
[in] | flip | : When true during conversion flip image vertically. |
Definition at line 390 of file vpImageConvert_opencv.cpp.
References vpRGBf::B, vpException::badValue, vpRGBf::G, vpImage< Type >::getCols(), vpImage< Type >::getRows(), vpRGBf::R, and vpImage< Type >::resize().
|
static |
Definition at line 530 of file vpImageConvert_opencv.cpp.
References convert(), vpImage< Type >::getCols(), and vpImage< Type >::getRows().
|
static |
Convert a vpImage<double> to a vpImage<unsigned char> by renormalizing between 0 and 255.
[in] | src | : Source image |
[out] | dest | : Destination image. |
Definition at line 177 of file vpImageConvert.cpp.
References vpImage< Type >::bitmap, vpImage< Type >::getHeight(), vpImage< Type >::getMinMaxValue(), vpImage< Type >::getWidth(), and vpImage< Type >::resize().
|
static |
Definition at line 519 of file vpImageConvert_opencv.cpp.
References vpImage< Type >::bitmap, vpImage< Type >::getCols(), and vpImage< Type >::getRows().
|
static |
Convert a vpImage<float> to a vpImage<unsigned char> by renormalizing between 0 and 255.
[in] | src | : Source image |
[out] | dest | : Destination image. |
Definition at line 102 of file vpImageConvert.cpp.
References vpImage< Type >::bitmap, vpImage< Type >::getHeight(), vpImage< Type >::getMinMaxValue(), vpImage< Type >::getWidth(), and vpImage< Type >::resize().
|
inlinestatic |
Make a copy of an image.
src | : source image. |
dest | : destination image. |
Definition at line 119 of file vpImageConvert.h.
|
static |
Convert a vpImage<uint16_t> to a vpImage<unsigned char>.
[in] | src | : Source image |
[out] | dest | : Destination image. |
[in] | bitshift | : Right bit shift applied to each source element. |
Definition at line 205 of file vpImageConvert.cpp.
References vpImage< Type >::bitmap, vpImage< Type >::getHeight(), vpImage< Type >::getSize(), vpImage< Type >::getWidth(), and vpImage< Type >::resize().
|
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.
[in] | src | : Source image. |
[out] | dest | : Destination image. |
[in] | copyData | : If true, the image is copied and modification in one object will not modified the other. |
Definition at line 508 of file vpImageConvert_opencv.cpp.
References vpImage< Type >::bitmap, vpImage< Type >::getCols(), and vpImage< Type >::getRows().
|
static |
Convert a vpImage<unsigned char> to a vpImage<double> by basic casting.
[in] | src | : Source image |
[out] | dest | : Destination image. |
Definition at line 236 of file vpImageConvert.cpp.
References vpImage< Type >::bitmap, vpImage< Type >::getHeight(), vpImage< Type >::getWidth(), and vpImage< Type >::resize().
|
static |
Convert a vpImage<unsigned char> to a vpImage<float> by basic casting.
[in] | src | : Source image |
[out] | dest | : Destination image. |
Definition at line 161 of file vpImageConvert.cpp.
References vpImage< Type >::bitmap, vpImage< Type >::getHeight(), vpImage< Type >::getWidth(), and vpImage< Type >::resize().
|
static |
Convert a vpImage<unsigned char> to a vpImage<uint16_t>.
[in] | src | : Source image |
[out] | dest | : Destination image. |
[in] | bitshift | : Left bit shift applied to each source element. |
Definition at line 221 of file vpImageConvert.cpp.
References vpImage< Type >::bitmap, vpImage< Type >::getHeight(), vpImage< Type >::getSize(), vpImage< Type >::getWidth(), and vpImage< Type >::resize().
|
static |
Convert a vpImage<unsigned char> to a vpImage<vpRGBa>. Tha alpha component is set to vpRGBa::alpha_default.
[in] | src | : Source image |
[out] | dest | : Destination image. |
Definition at line 73 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(), vpImageFilter::computePartialDerivatives(), convert(), vpDetectorFace::detect(), vpKeyPoint::detect(), vpCircleHoughTransform::detect(), vpCannyEdgeDetection::detect(), vpKeyPoint::detectExtractAffine(), vpKeyPoint::extract(), vpVideoReader::getFrame(), vpImageFilter::getGaussPyramidal(), vpDisplay::getImage(), vpDisplayOpenCV::getImage(), vpImageSimulator::init(), vpMbTracker::initFromPoints(), vpMbTracker::initFromPose(), vpKeyPoint::insertImageMatching(), vpKeyPoint::matchPoint(), vpImageFilter::median(), vpVideoWriter::saveFrame(), vpMbDepthDenseTracker::setPose(), vpMbDepthNormalTracker::setPose(), vpMbEdgeTracker::setPose(), vpMbGenericTracker::setPose(), vpImageTools::templateMatching(), vpMbEdgeTracker::track(), and vpMbGenericTracker::track().
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.
[in] | src | : Source image (vpRGBa format). |
[out] | dest | : Destination image (BGR format). |
Definition at line 460 of file vpImageConvert_opencv.cpp.
References vpImage< Type >::bitmap, vpImage< Type >::getCols(), and vpImage< Type >::getRows().
|
static |
Convert a vpImage<unsigned char> to a vpImage<vpRGBa>
[in] | src | : Source image |
[out] | dest | : Destination image. |
[in] | nThreads | : Number of threads to use if OpenMP is available. If 0 is passed, OpenMP will choose the number of threads. |
Definition at line 89 of file vpImageConvert.cpp.
References vpImage< Type >::bitmap, vpImage< Type >::getHeight(), vpImage< Type >::getWidth(), vpImage< Type >::resize(), and RGBaToGrey().
Definition at line 543 of file vpImageConvert_opencv.cpp.
References vpImage< Type >::bitmap, vpImage< Type >::getCols(), and vpImage< Type >::getRows().
Convert a vpImage<vpRGBf> to a vpImage<unsigned char> by renormalizing between 0 and 255.
[in] | src | : Source image |
[out] | dest | : Destination image. |
Definition at line 130 of file vpImageConvert.cpp.
References vpImage< Type >::getHeight(), vpImage< Type >::getMinMaxValue(), vpImage< Type >::getWidth(), and vpImage< Type >::resize().
|
static |
Convert the input float depth image to a 8-bits depth image. The input depth value is assigned a value proportional to its frequency.
[in] | src_depth | : Input float depth image. |
[out] | dest_depth | : Output grayscale depth image. |
Definition at line 287 of file vpImageConvert.cpp.
|
static |
Convert the input float depth image to a color depth image. The input depth value is assigned a color value proportional to its frequency. The alpha component of the resulting image is set to vpRGBa::alpha_default.
[in] | src_depth | : Input float depth image. |
[out] | dest_rgba | : Output color depth image. |
Definition at line 276 of file vpImageConvert.cpp.
|
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.
[in] | src_depth | : Input 16-bits depth image. |
[out] | dest_depth | : Output grayscale depth image. |
Definition at line 264 of file vpImageConvert.cpp.
|
static |
Convert the input 16-bits depth image to a color depth image. The input depth value is assigned a color value proportional to its frequency. Tha alpha component of the resulting image is set to vpRGBa::alpha_default.
[in] | src_depth | : Input 16-bits depth image. |
[out] | dest_rgba | : Output color depth image. |
Definition at line 253 of file vpImageConvert.cpp.
|
static |
Converts an array of uint16 Bayer data to an array of interleaved R, G, B and A values using bilinear demosaicing method.
[in] | bggr | : Array of Bayer data arranged into BGGR pattern. |
[out] | rgba | : Array of R, G, B and A values converted from Bayer image. |
[in] | width | : Bayer image width. |
[in] | height | : Bayer image height. |
[in] | nThreads | : Number of OpenMP threads to use if available. |
Definition at line 1406 of file vpImageConvert.cpp.
|
static |
Converts an array of uint8 Bayer data to an array of interleaved R, G, B and A values using bilinear demosaicing method.
[in] | bggr | : Array of Bayer data arranged into BGGR pattern. |
[out] | rgba | : Array of R, G, B and A values converted from Bayer image. |
[in] | width | : Bayer image width. |
[in] | height | : Bayer image height. |
[in] | nThreads | : Number of OpenMP threads to use if available. |
Definition at line 1388 of file vpImageConvert.cpp.
|
static |
Converts an array of uint16 Bayer data to an array of interleaved R, G, B and A values using Malvar [29] demosaicing method.
[in] | bggr | : Array of Bayer data arranged into BGGR pattern. |
[out] | rgba | : Array of R, G, B and A values converted from Bayer image. |
[in] | width | : Bayer image width. |
[in] | height | : Bayer image height. |
[in] | nThreads | : Number of OpenMP threads to use if available. |
Definition at line 1552 of file vpImageConvert.cpp.
|
static |
Converts an array of uint8 Bayer data to an array of interleaved R, G, B and A values using Malvar [29] demosaicing method.
[in] | bggr | : Array of Bayer data arranged into BGGR pattern. |
[out] | rgba | : Array of R, G, B and A values converted from Bayer image. |
[in] | width | : Bayer image width. |
[in] | height | : Bayer image height. |
[in] | nThreads | : Number of OpenMP threads to use if available. |
Definition at line 1534 of file vpImageConvert.cpp.
|
static |
Converts an array of uint16 Bayer data to an array of interleaved R, G, B and A values using bilinear demosaicing method.
[in] | gbrg | : Array of Bayer data arranged into GBRG pattern. |
[out] | rgba | : Array of R, G, B and A values converted from Bayer image. |
[in] | width | : Bayer image width. |
[in] | height | : Bayer image height. |
[in] | nThreads | : Number of OpenMP threads to use if available. |
Definition at line 1442 of file vpImageConvert.cpp.
|
static |
Converts an array of uint8 Bayer data to an array of interleaved R, G, B and A values using bilinear demosaicing method.
[in] | gbrg | : Array of Bayer data arranged into GBRG pattern. |
[out] | rgba | : Array of R, G, B and A values converted from Bayer image. |
[in] | width | : Bayer image width. |
[in] | height | : Bayer image height. |
[in] | nThreads | : Number of OpenMP threads to use if available. |
Definition at line 1424 of file vpImageConvert.cpp.
|
static |
Converts an array of uint16 Bayer data to an array of interleaved R, G, B and A values using Malvar [29] demosaicing method.
[in] | gbrg | : Array of Bayer data arranged into GBRG pattern. |
[out] | rgba | : Array of R, G, B and A values converted from Bayer image. |
[in] | width | : Bayer image width. |
[in] | height | : Bayer image height. |
[in] | nThreads | : Number of OpenMP threads to use if available. |
Definition at line 1588 of file vpImageConvert.cpp.
|
static |
Converts an array of uint8 Bayer data to an array of interleaved R, G, B and A values using Malvar [29] demosaicing method.
[in] | gbrg | : Array of Bayer data arranged into GBRG pattern. |
[out] | rgba | : Array of R, G, B and A values converted from Bayer image. |
[in] | width | : Bayer image width. |
[in] | height | : Bayer image height. |
[in] | nThreads | : Number of OpenMP threads to use if available. |
Definition at line 1570 of file vpImageConvert.cpp.
|
static |
Converts an array of uint16 Bayer data to an array of interleaved R, G, B and A values using bilinear demosaicing method.
[in] | grbg | : Array of Bayer data arranged into GRBG pattern. |
[out] | rgba | : Array of R, G, B and A values converted from Bayer image. |
[in] | width | : Bayer image width. |
[in] | height | : Bayer image height. |
[in] | nThreads | : Number of OpenMP threads to use if available. |
Definition at line 1478 of file vpImageConvert.cpp.
|
static |
Converts an array of uint8 Bayer data to an array of interleaved R, G, B and A values using bilinear demosaicing method.
[in] | grbg | : Array of Bayer data arranged into GRBG pattern. |
[out] | rgba | : Array of R, G, B and A values converted from Bayer image. |
[in] | width | : Bayer image width. |
[in] | height | : Bayer image height. |
[in] | nThreads | : Number of OpenMP threads to use if available. |
Definition at line 1460 of file vpImageConvert.cpp.
|
static |
Converts an array of uint16 Bayer data to an array of interleaved R, G, B and A values using Malvar [29] demosaicing method.
[in] | grbg | : Array of Bayer data arranged into GRBG pattern. |
[out] | rgba | : Array of R, G, B and A values converted from Bayer image. |
[in] | width | : Bayer image width. |
[in] | height | : Bayer image height. |
[in] | nThreads | : Number of OpenMP threads to use if available. |
Definition at line 1624 of file vpImageConvert.cpp.
|
static |
Converts an array of uint8 Bayer data to an array of interleaved R, G, B and A values using Malvar [29] demosaicing method.
[in] | grbg | : Array of Bayer data arranged into GRBG pattern. |
[out] | rgba | : Array of R, G, B and A values converted from Bayer image. |
[in] | width | : Bayer image width. |
[in] | height | : Bayer image height. |
[in] | nThreads | : Number of OpenMP threads to use if available. |
Definition at line 1606 of file vpImageConvert.cpp.
|
static |
Converts an array of uint16 Bayer data to an array of interleaved R, G, B and A values using bilinear demosaicing method.
[in] | rggb | : Array of Bayer data arranged into RGGB pattern. |
[out] | rgba | : Array of R, G, B and A values converted from Bayer image. |
[in] | width | : Bayer image width. |
[in] | height | : Bayer image height. |
[in] | nThreads | : Number of OpenMP threads to use if available. |
Definition at line 1514 of file vpImageConvert.cpp.
|
static |
Converts an array of uint8 Bayer data to an array of interleaved R, G, B and A values using bilinear demosaicing method.
[in] | rggb | : Array of Bayer data arranged into RGGB pattern. |
[out] | rgba | : Array of R, G, B and A values converted from Bayer image. |
[in] | width | : Bayer image width. |
[in] | height | : Bayer image height. |
[in] | nThreads | : Number of OpenMP threads to use if available. |
Definition at line 1496 of file vpImageConvert.cpp.
|
static |
Converts an array of uint16 Bayer data to an array of interleaved R, G, B and A values using Malvar [29] demosaicing method.
[in] | rggb | : Array of Bayer data arranged into RGGB pattern. |
[out] | rgba | : Array of R, G, B and A values converted from Bayer image. |
[in] | width | : Bayer image width. |
[in] | height | : Bayer image height. |
[in] | nThreads | : Number of OpenMP threads to use if available. |
Definition at line 1660 of file vpImageConvert.cpp.
|
static |
Converts an array of uint8 Bayer data to an array of interleaved R, G, B and A values using Malvar [29] demosaicing method.
[in] | rggb | : Array of Bayer data arranged into RGGB pattern. |
[out] | rgba | : Array of R, G, B and A values converted from Bayer image. |
[in] | width | : Bayer image width. |
[in] | height | : Bayer image height. |
[in] | nThreads | : Number of OpenMP threads to use if available. |
Definition at line 1642 of file vpImageConvert.cpp.
|
static |
Create a point cloud from a depth image.
[in] | depth_raw | : Depth raw image. |
[in] | depth_scale | : Depth scale to apply to data in depth_raw . |
[in] | cam_depth | : Depth camera intrinsics. |
[out] | pointcloud | : Computed 3D point cloud. The 3D points reconstructed from the raw depth image are those that have their corresponding 2D projection in the depth mask and have a Z value within ]Z_min, Z_max[ range. When the depth mask is set to nullptr, we reconstruct all 3D points from the complete depth raw image and retain only those whose Z value lies between ]Z_min, Z_max[ range. You must also ensure that the size of the depth mask and the size of the depth raw image are the same. |
[in,out] | pointcloud_mutex | : Optional mutex to protect from concurrent access to pointcloud . When set to nullptr, you should ensure that there is no thread that wants to access to pointcloud , like for example the one used in vpDisplayPCL. |
[in] | depth_mask | : Optional depth_mask. When set to nullptr, all the pixels in depth_raw are considered. Otherwise, we consider only pixels that have a mask value that differ from 0. |
[in] | Z_min | : Min Z value to retain the 3D point in the point cloud. |
[in] | Z_max | : Max Z value to retain the 3D point in the point cloud. |
Definition at line 73 of file vpImageConvert_pcl.cpp.
References vpImage< Type >::bitmap, vpPixelMeterConversion::convertPoint(), vpImage< Type >::getHeight(), vpImage< Type >::getSize(), vpImage< Type >::getWidth(), and vpImageException::notInitializedError.
|
static |
Create a textured point cloud from an aligned color and depth image.
[in] | color | : Color image. |
[in] | depth_raw | : Depth raw image. |
[in] | depth_scale | : Depth scale to apply to data in depth_raw . |
[in] | cam_depth | : Depth camera intrinsics. |
[out] | pointcloud | : Computed 3D point cloud with RGB information. The 3D points reconstructed from the raw depth image are those that have their corresponding 2D projection in the depth mask and have a Z value within ]Z_min, Z_max[ range. When the depth mask is set to nullptr, we reconstruct all 3D points from the complete depth raw image and retain only those whose Z value lies between ]Z_min, Z_max[ range. |
[in,out] | pointcloud_mutex | : Optional mutex to protect from concurrent access to pointcloud . When set to nullptr, you should ensure that there is no thread that wants to access to pointcloud , like for example the one used in vpDisplayPCL. |
[in] | depth_mask | : Optional depth_mask. When set to nullptr, all the pixels in depth_raw are considered. Otherwise, we consider only pixels that have a mask value that differ from 0 and that a Z value in ]Z_min, Z_max[] range. You should also ensure that mask size and depth_raw size are the same. |
[in] | Z_min | : Min Z value to retain the 3D point in the point cloud. |
[in] | Z_max | : Max Z value to retain the 3D point in the point cloud. |
Definition at line 185 of file vpImageConvert_pcl.cpp.
References vpRGBa::B, vpImage< Type >::bitmap, vpPixelMeterConversion::convertPoint(), vpRGBa::G, vpImage< Type >::getHeight(), vpImage< Type >::getSize(), vpImage< Type >::getWidth(), vpImageException::notInitializedError, and vpRGBa::R.
|
static |
Convert from grey image to linear RGB image.
[in] | grey | : Pointer to the bitmap containing the 8-bits grey data. |
[out] | rgb | : Pointer to the 24-bits RGB bitmap that should be allocated with a size of width * height * 3. |
[in] | size | : Image size corresponding to image width * height. |
Definition at line 590 of file vpImageConvert.cpp.
|
static |
Convert from grey image to linear RGBa image. The alpha component is set to vpRGBa::alpha_default.
[in] | grey | : Pointer to the bitmap containing the 8-bits grey data. |
[out] | rgba | : Pointer to the 32-bits RGBA bitmap that should be allocated with a size of width * height * 4. |
[in] | size | : Image size corresponding to image width * height. |
Definition at line 558 of file vpImageConvert.cpp.
References vpRGBa::alpha_default, and GreyToRGBa().
|
static |
Convert from grey image to linear RGBa image. The alpha component is set to vpRGBa::alpha_default.
[in] | grey | : Pointer to the bitmap containing the 8-bits grey data. |
[out] | rgba | : Pointer to the 32-bits RGBA bitmap that should be allocated with a size of width * height * 4. |
[in] | width,height | : Image size. |
Definition at line 537 of file vpImageConvert.cpp.
References vpRGBa::alpha_default.
Referenced by vp1394CMUGrabber::acquire(), vpV4l2Grabber::acquire(), vp1394TwoGrabber::acquire(), vpOccipitalStructure::acquire(), convert(), vp1394TwoGrabber::dequeue(), and GreyToRGBa().
|
static |
Converts an array of hue, saturation and value to an array of RGB values.
[in] | hue | : Array of hue values in range [0,1]. The dimension of this array corresponds to size parameter. |
[in] | saturation | : Array of saturation values in range [0,1]. The dimension of this array corresponds to size parameter. |
[in] | value | : Array of value values in range [0,1]. The dimension of this array corresponds to size parameter. |
[out] | rgb | : Pointer to the 24-bit RGB image that should be allocated prior to calling this function with a size of width * height * 3 where width * height corresponds to size parameter. |
[in] | size | : The image size or the number of pixels corresponding to the image width * height . |
Definition at line 498 of file vpImageConvert_hsv.cpp.
|
static |
Converts an array of hue, saturation and value to an array of RGB values.
[in] | hue | : Array of hue values. Range depends on h_full parameter. The dimension of this array corresponds to size parameter. |
[in] | saturation | : Array of saturation values in range [0,255]. The dimension of this array corresponds to size parameter. |
[in] | value | : Array of value values in range [0,255]. The dimension of this array corresponds to size parameter. |
[out] | rgb | : Pointer to the 24-bit RGB image that should be allocated prior to calling this function with a size of width * height * 3 where width * height corresponds to size parameter. |
[in] | size | : The image size or the number of pixels corresponding to the image width * height . |
[in] | h_full | : When true, hue range is in [0, 255]. When false, hue range is in [0, 180]. |
Definition at line 518 of file vpImageConvert_hsv.cpp.
|
static |
Converts an array of hue, saturation and value (HSV) to an array of RGBa values.
Alpha component of the converted image is set to vpRGBa::alpha_default.
[in] | hue | : Array of hue values in range [0,1]. |
[in] | saturation | : Array of saturation values in range [0,1]. |
[in] | value | : Array of value values in range [0,1]. |
[out] | rgba | : Pointer to the 32-bit RGBa image that should be allocated prior to calling this function with a size of width * height * 4. Alpha channel is here set to vpRGBa::alpha_default. |
[in] | size | : The image size or the number of pixels corresponding to the image width * height. |
Definition at line 418 of file vpImageConvert_hsv.cpp.
Referenced by VISP_NAMESPACE_NAME::equalizeHistogram(), VISP_NAMESPACE_NAME::gammaCorrection(), and VISP_NAMESPACE_NAME::stretchContrastHSV().
|
static |
Converts an array of hue, saturation and value (HSV) to an array of RGBa values.
Alpha component of the converted image is set to vpRGBa::alpha_default.
[in] | hue | : Array of hue values. Range depends on h_full parameter. |
[in] | saturation | : Array of saturation values in range [0,255]. |
[in] | value | : Array of value values in range [0,255]. |
[out] | rgba | : Pointer to the 32-bit RGBa image that should be allocated prior to calling this function with a size of width * height * 4. Alpha channel is here set to vpRGBa::alpha_default. |
[in] | size | : The image size or the number of pixels corresponding to the image width * height. |
[in] | h_full | : When true, hue range is in [0, 255]. When false, hue range is in [0, 180]. |
Definition at line 438 of file vpImageConvert_hsv.cpp.
|
static |
Merge 4 channels into an RGBa image.
[in] | R | : Red channel. |
[in] | G | : Green channel. |
[in] | B | : Blue channel. |
[in] | a | : Alpha channel. |
[out] | RGBa | : Destination RGBa image. Image is resized internally if needed. |
Definition at line 1259 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().
Referenced by VISP_NAMESPACE_NAME::gammaCorrection().
|
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.
[in] | grey16 | : Input image to convert (two bytes per pixel). |
[out] | grey | : Pointer to the 8-bit grey image (one byte per pixel) that should be allocated with a size of width * height. |
[in] | size | : The image size or the number of pixels corresponding to the image width * height. |
Definition at line 1335 of file vpImageConvert.cpp.
Referenced by vp1394CMUGrabber::acquire(), and vp1394TwoGrabber::dequeue().
|
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.
[in] | grey16 | : Pointer to the bitmap containing the input image to convert (two bytes per pixel). |
[out] | rgba | : Pointer to the 32-bit RGBA image that should be allocated with a size of width * height * 4. |
[in] | size | : The image size or the number of pixels corresponding to the image width * height. |
Definition at line 1358 of file vpImageConvert.cpp.
References vpRGBa::alpha_default.
Referenced by vp1394CMUGrabber::acquire(), and vp1394TwoGrabber::dequeue().
|
static |
Convert a RGBa image to a greyscale one.
See Charles Pontyon's Colour FAQ http://www.poynton.com/notes/colour_and_gamma/ColorFAQ.html
[in] | rgba | : Pointer to the 32-bits RGBA bitmap. |
[out] | grey | : Pointer to the bitmap containing the 8-bits grey data that should be allocated with a size of width * height. |
[in] | size | : Image size corresponding to image width * height. |
Definition at line 509 of file vpImageConvert.cpp.
|
static |
Convert a RGBa image to a grey scale one.
See Charles Pontyon's Colour FAQ http://www.poynton.com/notes/colour_and_gamma/ColorFAQ.html
[in] | rgba | : Pointer to the 32-bits RGBA bitmap. |
[out] | grey | : Pointer to the bitmap containing the 8-bits grey data that should be allocated with a size of width * height. |
[in] | width,height | : Image size. |
[in] | nThreads | : When > 0, the value is used to set the number of OpenMP threads used for the conversion. |
Definition at line 469 of file vpImageConvert.cpp.
Referenced by vpV4l2Grabber::acquire(), convert(), and vpRealSense2::getGreyFrame().
|
static |
Converts an array of RGBa to an array of hue, saturation, value (HSV) values. The alpha channel is not used.
[in] | rgba | : Pointer to the 32-bits RGBa bitmap. |
[out] | hue | : Array of hue values converted from RGB color space in range [0 - 1]. This array of dimension size should be allocated prior to calling this function. |
[out] | saturation | : Array of saturation values converted from RGB color space in range [0 - 1]. This array of dimension size should be allocated prior to calling this function. |
[out] | value | : Array of value values converted from RGB color space in range [0 - 1]. This array of dimension size should be allocated prior to calling this function. |
[in] | size | : The image size or the number of pixels corresponding to the image width * height. |
Definition at line 457 of file vpImageConvert_hsv.cpp.
Referenced by VISP_NAMESPACE_NAME::equalizeHistogram(), VISP_NAMESPACE_NAME::gammaCorrection(), and VISP_NAMESPACE_NAME::stretchContrastHSV().
|
static |
Converts an array of RGBa to an array of hue, saturation, value (HSV) values. The alpha channel is not used.
[in] | rgba | : Pointer to the 32-bits RGBA bitmap that has a dimension of size * 4 . |
[out] | hue | : Array of hue values converted from RGB color space. Range depends on h_full parameter. This array of dimension size should be allocated prior to calling this function. |
[out] | saturation | : Array of saturation values converted from RGB color space in range [0 - 255]. This array of dimension size should be allocated prior to calling this function. |
[out] | value | : Array of value values converted from RGB color space in range [0 - 255]. This array of dimension size should be allocated prior to calling this function. |
[in] | size | : The image size or the number of pixels corresponding to the image width * height. |
[in] | h_full | : When true, hue range is in [0, 255]. When false, hue range is in [0, 180]. |
Definition at line 479 of file vpImageConvert_hsv.cpp.
|
static |
Convert RGB image into RGBa image.
The alpha component of the converted image is set to vpRGBa::alpha_default.
[in] | rgba | : Pointer to the 32-bits RGBA bitmap. |
[out] | rgb | : Pointer to the bitmap containing the 24-bits RGB data that should be allocated with a size of width * height * 4. |
[in] | size | : Image size corresponding to image width * height. |
Definition at line 368 of file vpImageConvert.cpp.
|
static |
Convert an RGB image to a grey scale one.
See Charles Pontyon's Colour FAQ http://www.poynton.com/notes/colour_and_gamma/ColorFAQ.html
[in] | rgb | : Pointer to the 24-bits RGB bitmap. |
[out] | grey | : Pointer to the bitmap containing the 8-bits grey data that should be allocated with a size of width * height. |
[in] | size | : Image size corresponding to image width * height. |
Definition at line 398 of file vpImageConvert.cpp.
References RGBToGrey().
|
static |
Converts a RGB image to a grey scale one. Flips the image vertically if needed. Assumes that grey is already resized.
[in] | rgb | : Pointer to the 24-bits RGB bitmap. |
[out] | grey | : Pointer to the bitmap containing the 8-bits grey data that should be allocated with a size of width * height. |
[in] | width,height | : Image size. |
[in] | flip | : When true, image is flipped vertically. |
Definition at line 416 of file vpImageConvert.cpp.
Referenced by vp1394CMUGrabber::acquire(), vpV4l2Grabber::acquire(), vp1394TwoGrabber::dequeue(), vpRealSense2::getGreyFrame(), vpSimulator::getInternalImage(), and RGBToGrey().
|
static |
Converts an array of RGB to an array of hue, saturation, value values.
[in] | rgb | : Pointer to the 24-bits RGB bitmap. Its size corresponds to size * 3 . |
[out] | hue | : Array of hue values in range [0,1] converted from RGB color space. This array should be allocated prior to calling this function. Its size corresponds to size parameter. |
[out] | saturation | : Array of saturation values in range [0,1] converted from RGB color space. This array should be allocated prior to calling this function. Its size corresponds to size parameter. |
[out] | value | : Array of value values in range [0,1] converted from RGB color space. This array should be allocated prior to calling this function. Its size corresponds to size parameter. |
[in] | size | : The image size or the number of pixels corresponding to the image width * height. |
Definition at line 536 of file vpImageConvert_hsv.cpp.
|
static |
Converts an array of RGB to an array of hue, saturation, value values.
[in] | rgb | : Pointer to the 24-bits RGB bitmap. Its size corresponds to size * 3 . |
[out] | hue | : Array of hue values converted from RGB color space. Range depends on h_full parameter. This array should be allocated prior to calling this function. Its size corresponds to size parameter. |
[out] | saturation | : Array of saturation values in range [0,255] converted from RGB color space. This array should be allocated prior to calling this function. Its size corresponds to size parameter. |
[out] | value | : Array of value values in range [0,255] converted from RGB color space. This array should be allocated prior to calling this function. Its size corresponds to size parameter. |
[in] | size | : The image size or the number of pixels corresponding to the image width * height. |
[in] | h_full | : When true, hue range is in [0, 255]. When false, hue range is in [0, 180]. |
Definition at line 557 of file vpImageConvert_hsv.cpp.
|
static |
Convert RGB into RGBa.
Alpha component is set to vpRGBa::alpha_default.
[in] | rgb | : Pointer to the bitmap containing the 24-bits RGB data. |
[out] | rgba | : Pointer to the 32-bits RGBA bitmap that should be allocated with a size of width * height * 4. |
[in] | size | : Image size corresponding to image width * height. |
Definition at line 301 of file vpImageConvert.cpp.
Referenced by vp1394CMUGrabber::acquire(), vpV4l2Grabber::acquire(), vp1394TwoGrabber::acquire(), vpOccipitalStructure::acquire(), vp1394TwoGrabber::dequeue(), vpRealSense2::getColorFrame(), and vpSimulator::getInternalImage().
|
static |
Converts a RGB image to RGBa. Alpha component is set to vpRGBa::alpha_default.
Flips the image vertically if needed. Assumes that rgba is already resized.
[in] | rgb | : Pointer to the bitmap containing the 24-bits RGB data. |
[out] | rgba | : Pointer to the 32-bits RGBA bitmap that should be allocated with a size of width * height * 4. |
[in] | width,height | : Image size. |
[in] | flip | : When true, image is flipped vertically. |
Definition at line 321 of file vpImageConvert.cpp.
References vpRGBa::alpha_default.
|
static |
Split an image from vpRGBa format to monochrome channels.
[in] | src | : source image. |
[out] | pR | : red channel. Set as nullptr if not needed. |
[out] | pG | : green channel. Set as nullptr if not needed. |
[out] | pB | : blue channel. Set as nullptr if not needed. |
[out] | pa | : alpha channel. Set as nullptr if not needed. |
Output channels are resized if needed.
Example code using split:
Definition at line 1150 of file vpImageConvert.cpp.
References vpImage< Type >::bitmap, vpImage< Type >::getHeight(), vpImage< Type >::getNumberOfPixel(), vpImage< Type >::getSize(), vpImage< Type >::getWidth(), and vpImage< Type >::resize().
Referenced by VISP_NAMESPACE_NAME::clahe(), VISP_NAMESPACE_NAME::equalizeHistogram(), VISP_NAMESPACE_NAME::gammaCorrection(), VISP_NAMESPACE_NAME::stretchContrast(), and VISP_NAMESPACE_NAME::unsharpMask().
|
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] | ycbcr | : Pointer to the bitmap containing the YCbCr 4:2:2 data. |
[out] | grey | : Pointer to the 8-bits grey bitmap that should be allocated with a size of width * height. |
[in] | size | : Image size corresponding to image width * height. |
Definition at line 985 of file vpImageConvert.cpp.
|
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 | : Pointer to the bitmap containing the YCbCr 4:2:2 data. |
[out] | rgb | : Pointer to the 24-bits RGB bitmap that should be allocated with a size of width * height * 3. |
[in] | size | : Image size corresponding to image width * height. |
Definition at line 874 of file vpImageConvert.cpp.
|
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 | : Pointer to the bitmap containing the YCbCr 4:2:2 data. |
[out] | rgba | : Pointer to the 32-bits RGBA bitmap that should be allocated with a size of width * height * 4. |
[in] | size | : Image size corresponding to image width * height. |
Definition at line 932 of file vpImageConvert.cpp.
References vpRGBa::alpha_default.
|
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 | : Pointer to the bitmap containing the YCbCr 4:2:2 data. |
[out] | rgb | : Pointer to the 24-bits RGB bitmap that should be allocated with a size of width * height * 3. |
[in] | size | : Image size corresponding to image width * height. |
Definition at line 1017 of file vpImageConvert.cpp.
|
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 | : Pointer to the bitmap containing the YCrCb 4:2:2 data. |
[out] | rgba | : Pointer to the 32-bits RGBA bitmap that should be allocated with a size of width * height * 4. |
[in] | size | : Image size corresponding to image width * height. |
Definition at line 1074 of file vpImageConvert.cpp.
References vpRGBa::alpha_default.
|
static |
Convert YUV 4:1:1 (u y1 y2 v y3 y4) into a grey image.
[in] | yuv | : Pointer to the bitmap containing the YUV 4:1:1 data. |
[out] | grey | : Pointer to the 8-bits grey bitmap that should be allocated with a size of width * height. |
[in] | size | : Image size corresponding to width * height. |
Definition at line 381 of file vpImageConvert_yuv.cpp.
Referenced by vp1394CMUGrabber::acquire(), and vp1394TwoGrabber::dequeue().
|
static |
Convert YUV 4:1:1 (u y1 y2 v y3 y4) into a RGB 24bits image.
[in] | yuv | : Pointer to the bitmap containing the YUV 4:1:1 data. |
[out] | rgb | : Pointer to the 24-bits RGB bitmap that should be allocated with a size of width * height * 3. |
[in] | size | : Image size corresponding to width * height. |
Definition at line 485 of file vpImageConvert_yuv.cpp.
|
static |
Convert YUV 4:1:1 (u y1 y2 v y3 y4) images into RGBa images. The alpha component of the converted image is set to vpRGBa::alpha_default.
[in] | yuv | : Pointer to the bitmap containing the YUV 4:1:1 data. |
[out] | rgba | : Pointer to the RGBA 32-bits bitmap that should be allocated with a size of width * height * 4. |
[in] | size | : Image size corresponding to width * height. |
Definition at line 227 of file vpImageConvert_yuv.cpp.
References vpRGBa::alpha_default.
Referenced by vp1394CMUGrabber::acquire(), vp1394TwoGrabber::acquire(), and vp1394TwoGrabber::dequeue().
|
static |
Convert YUV 4:2:0 [Y(NxM), U(N/2xM/2), V(N/2xM/2)] image into a grey image.
[in] | yuv | : Pointer to the bitmap containing the YUV 4:2:0 data. |
[out] | grey | : Pointer to the 8-bits grey bitmap that should be allocated with a size of width * height. |
[in] | size | : Image size corresponding to image width * height. |
Definition at line 789 of file vpImageConvert_yuv.cpp.
|
static |
Convert YUV 4:2:0 [Y(NxM), U(N/2xM/2), V(N/2xM/2)] image into a RGB image.
[in] | yuv | : Pointer to the bitmap containing the YUV 4:2:0 data. |
[out] | rgb | : Pointer to the 24-bits RGB bitmap that should be allocated with a size of width * height * 3. |
[in] | width,height | : Image size. |
Definition at line 685 of file vpImageConvert_yuv.cpp.
|
static |
Convert YUV 4:2:0 [Y(NxM), U(N/2xM/2), V(N/2xM/2)] image into a RGBa image.
The alpha component of the converted image is set to vpRGBa::alpha_default.
[in] | yuv | : Pointer to the bitmap containing the YUV 4:2:0 data. |
[out] | rgba | : Pointer to the 32-bits RGBA bitmap that should be allocated with a size of width * height * 4. |
[in] | width,height | : Image size. |
Definition at line 576 of file vpImageConvert_yuv.cpp.
References vpRGBa::alpha_default.
|
static |
Convert YUV 4:2:2 (u01 y0 v01 y1 u23 y2 v23 y3 ...) images into a grey image. Destination grey memory area has to be allocated before.
[in] | yuv | : Pointer to the bitmap containing the YUV 4:2:2 data. |
[out] | grey | : Pointer to the 8-bits grey bitmap that should be allocated with a size of width * height. |
[in] | size | : Image size corresponding to width * height. |
Definition at line 465 of file vpImageConvert_yuv.cpp.
Referenced by vp1394CMUGrabber::acquire(), and vp1394TwoGrabber::dequeue().
|
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.
[in] | yuv | : Pointer to the bitmap containing the YUV 4:2:2 data. |
[out] | rgb | : Pointer to the 24-bits RGB bitmap that should be allocated with a size of width * height * 3. |
[in] | size | : Image size corresponding to width * height. |
Definition at line 408 of file vpImageConvert_yuv.cpp.
|
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.
[in] | yuv | : Pointer to the bitmap containing the YUV 4:2:2 data. |
[out] | rgba | : Pointer to the RGBA 32-bits bitmap that should be allocated with a size of width * height * 4. |
[in] | size | : Image size corresponding to width * height. |
Definition at line 324 of file vpImageConvert_yuv.cpp.
References vpRGBa::alpha_default.
Referenced by vp1394CMUGrabber::acquire(), vp1394TwoGrabber::acquire(), and vp1394TwoGrabber::dequeue().
|
static |
Convert YUV 4:4:4 (u y v) image into a grey image.
[in] | yuv | : Pointer to the bitmap containing the YUV 4:4:4 data. |
[out] | grey | : Pointer to the 8-bits grey bitmap that should be allocated with a size of width * height. |
[in] | size | Image size corresponding to image width * height. |
Definition at line 887 of file vpImageConvert_yuv.cpp.
Referenced by vp1394CMUGrabber::acquire(), and vp1394TwoGrabber::dequeue().
|
static |
Convert YUV 4:4:4 (u y v) image into RGB image.
[in] | yuv | : Pointer to the bitmap containing the YUV 4:4:4 data. |
[out] | rgb | : Pointer to the 24-bits RGB bitmap that should be allocated with a size of width * height * 3. |
[in] | size | Image size corresponding to image width * height. |
Definition at line 847 of file vpImageConvert_yuv.cpp.
|
static |
Convert YUV 4:4:4 (u y v) image into a RGBa image.
The alpha component of the converted image is set to vpRGBa::alpha_default.
[in] | yuv | : Pointer to the bitmap containing the YUV 4:4:4 data. |
[out] | rgba | : Pointer to the 32-bits RGBA bitmap that should be allocated with a size of width * height * 4. |
[in] | size | : Image size corresponding to image width * height. |
Definition at line 806 of file vpImageConvert_yuv.cpp.
References vpRGBa::alpha_default.
Referenced by vp1394CMUGrabber::acquire(), vp1394TwoGrabber::acquire(), and vp1394TwoGrabber::dequeue().
|
inlinestatic |
Converts a yuv pixel value in rgb format.
y | Y component of a pixel. |
u | U component of a pixel. |
v | V component of a pixel. |
r | Red component from the YUV coding format. This value is computed using:
|
g | Green component from the YUV coding format. This value is computed using:
|
b | Blue component from the YUV coding format. This value is computed using:
|
Definition at line 181 of file vpImageConvert.h.
|
static |
Convert an image from YUYV 4:2:2 (y0 u01 y1 v01 y2 u23 y3 v23 ...) to grey. Destination grey memory area has to be allocated before.
[in] | yuyv | : Pointer to the bitmap containing the YUYV 4:2:2 data. |
[out] | grey | : Pointer to the 8-bits grey bitmap that should be allocated with a size of width * height. |
[in] | size | : Image size corresponding to width * height. |
Definition at line 207 of file vpImageConvert_yuv.cpp.
Referenced by vpV4l2Grabber::acquire().
|
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.
[in] | yuyv | : Pointer to the bitmap containing the YUYV 4:2:2 data. |
[out] | rgb | : Pointer to the RGB32 bitmap that should be allocated with a size of width * height * 3. |
[in] | width,height | : Image size. |
Definition at line 140 of file vpImageConvert_yuv.cpp.
|
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.
[in] | yuyv | : Pointer to the bitmap containing the YUYV 4:2:2 data. |
[out] | rgba | : Pointer to the RGB32 bitmap that should be allocated with a size of width * height * 4. |
[in] | width,height | : Image size. |
Definition at line 71 of file vpImageConvert_yuv.cpp.
References vpRGBa::alpha_default.
Referenced by vpV4l2Grabber::acquire().
|
static |
Convert YV12 [Y(NxM), V(N/2xM/2), U(N/2xM/2)] image into RGB image.
[in] | yuv | : Pointer to the bitmap containing the YV 1:2 data. |
[out] | rgb | : Pointer to the 24-bits RGB bitmap that should be allocated with a size of width * height * 3. |
[in] | width,height | : Image size. |
Definition at line 1015 of file vpImageConvert_yuv.cpp.
|
static |
Convert YV 1:2 [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.
[in] | yuv | : Pointer to the bitmap containing the YV 1:2 data. |
[out] | rgba | : Pointer to the 32-bits RGBA bitmap that should be allocated with a size of width * height * 4. |
[in] | width,height | : Image size. |
Definition at line 906 of file vpImageConvert_yuv.cpp.
References vpRGBa::alpha_default.
|
static |
Convert YV 1:2 [Y(NxM), V(N/4xM/4), U(N/4xM/4)] image into RGB image.
[in] | yuv | : Pointer to the bitmap containing the YV 1:2 data. |
[out] | rgb | : Pointer to the 24-bits RGB bitmap that should be allocated with a size of width * height * 3. |
[in] | width,height | : Image size. |
Definition at line 1338 of file vpImageConvert_yuv.cpp.
|
static |
Convert YVU 9 [Y(NxM), V(N/4xM/4), U(N/4xM/4)] image into a RGBa image.
The alpha component of the converted image is set to vpRGBa::alpha_default.
[in] | yuv | : Pointer to the bitmap containing the YVU 9 data. |
[out] | rgba | : Pointer to the 32-bits RGBA bitmap that should be allocated with a size of width * height * 4. |
[in] | width,height | : Image size. |
Definition at line 1145 of file vpImageConvert_yuv.cpp.
References vpRGBa::alpha_default.