Classes | |
| class | CameraIntrinsics |
| This abstract base class defines an interface for classes that describe camera projection and distortion parameters. More... | |
| class | CameraIntrinsicsPinhole |
| This class represents calibration parameters for a simple pinhole camera model, as described in [1]. More... | |
| class | CameraIntrinsicsPlumbBob |
| This class represents calibration parameters for cameras conforming to Brown-Conrady "plumb bob" camera model, as described in [1]. More... | |
| class | ColorspaceConverter |
| class | ExtendedKalmanFilter |
| This class template implements the ExtendedKalman Filter[??]. More... | |
| class | Image |
| This class template represents a 2D image. More... | |
| class | ImageFormatTraits |
| The ImageFormatTraits class template specifies the characteristics of the available image formats. More... | |
| class | ImageFormatTraits< GRAY1 > |
| class | ImageFormatTraits< GRAY8 > |
| class | ImageFormatTraits< GRAY16 > |
| class | ImageFormatTraits< GRAY32 > |
| class | ImageFormatTraits< GRAY64 > |
| class | ImageFormatTraits< GRAY_SIGNED16 > |
| class | ImageFormatTraits< GRAY_SIGNED32 > |
| class | ImageFormatTraits< GRAY_FLOAT32 > |
| class | ImageFormatTraits< GRAY_FLOAT64 > |
| class | ImageFormatTraits< RGB8 > |
| class | ImageFormatTraits< RGB16 > |
| class | ImageFormatTraits< RGB_SIGNED16 > |
| class | ImageFormatTraits< RGB_SIGNED32 > |
| class | ImageFormatTraits< RGB_FLOAT32 > |
| class | ImageFormatTraits< RGB_FLOAT64 > |
| class | ImageFormatTraits< HSV_FLOAT64 > |
| class | ImageFormatTraits< YIQ_FLOAT64 > |
| class | ImageFormatTraits< RGBA8 > |
| class | ImageFormatTraits< BGRA8 > |
| class | ImageWarper |
| class | KDComparator |
| This class template is used by the KDTree class template to interact with the data points to be stored in the KD-Tree. More... | |
| class | KDTree |
| This class implements a basic KD-Tree data structure. More... | |
| class | Kernel |
| This class template represents a 2D convolution kernel. More... | |
| class | Snake |
| class | NChooseKSampleSelector |
| This class template provides capabilities to exhaustively select sequences of samples from a pool of candidates. More... | |
| class | OpticalFlow |
| This class uses the method of Lucas and Kanade[1] to estimate the optical flow between two images. More... | |
| struct | PixelBGRA |
| struct | PixelHSV |
| struct | PixelRGB |
| struct | PixelRGBA |
| struct | PixelYIQ |
| class | QuadMapComparator |
| This class template is used by the QuadMap class template to interact with the data points to be stored in the map. More... | |
| class | QuadMap |
| This class implements a QuadMap data structure that tessellates 2D space into square regions, and stores an approximately uniform distribution of 2D points in such a way that finding points within the space has complexity approximately logarithmic in the number of points. More... | |
| class | RandomSampleSelector |
| This class template provides capabilities to randomly select sequences of samples from a pool of candidates. More... | |
| class | Ransac |
| This class template implements the RANSAC algorithm[1]. More... | |
| class | RansacProblem |
| This class template implements the "Problem" interface required by the Ransac class, above. More... | |
| class | EdgeDefaultFunctor |
| struct | Edge |
| class | SegmenterFelzenszwalb |
| This class implements the image segmentation algorithm described [1]. More... | |
Typedefs | |
| typedef PixelBGRA< UnsignedInt8 > | PixelBGRA8 |
| typedef PixelBGRA< UnsignedInt16 > | PixelBGRA16 |
| typedef PixelBGRA< Int16 > | PixelBGRASigned16 |
| typedef PixelBGRA< Int32 > | PixelBGRASigned32 |
| typedef PixelBGRA< Float32 > | PixelBGRAFloat32 |
| typedef PixelBGRA< Float64 > | PixelBGRAFloat64 |
| typedef PixelHSV< UnsignedInt8 > | PixelHSV8 |
| typedef PixelHSV< UnsignedInt16 > | PixelHSV16 |
| typedef PixelHSV< Int16 > | PixelHSVSigned16 |
| typedef PixelHSV< Int32 > | PixelHSVSigned32 |
| typedef PixelHSV< Float32 > | PixelHSVFloat32 |
| typedef PixelHSV< Float64 > | PixelHSVFloat64 |
| typedef PixelRGB< UnsignedInt8 > | PixelRGB8 |
| typedef PixelRGB< UnsignedInt16 > | PixelRGB16 |
| typedef PixelRGB< Int16 > | PixelRGBSigned16 |
| typedef PixelRGB< Int32 > | PixelRGBSigned32 |
| typedef PixelRGB< Float32 > | PixelRGBFloat32 |
| typedef PixelRGB< Float64 > | PixelRGBFloat64 |
| typedef PixelRGBA< UnsignedInt8 > | PixelRGBA8 |
| typedef PixelRGBA< UnsignedInt16 > | PixelRGBA16 |
| typedef PixelRGBA< Int16 > | PixelRGBASigned16 |
| typedef PixelRGBA< Int32 > | PixelRGBASigned32 |
| typedef PixelRGBA< Float32 > | PixelRGBAFloat32 |
| typedef PixelRGBA< Float64 > | PixelRGBAFloat64 |
| typedef PixelYIQ< UnsignedInt8 > | PixelYIQ8 |
| typedef PixelYIQ< UnsignedInt16 > | PixelYIQ16 |
| typedef PixelYIQ< Int16 > | PixelYIQSigned16 |
| typedef PixelYIQ< Int32 > | PixelYIQSigned32 |
| typedef PixelYIQ< Float32 > | PixelYIQFloat32 |
| typedef PixelYIQ< Float64 > | PixelYIQFloat64 |
Enumerations | |
| enum | ImageFormat { GRAY1, GRAY8, GRAY16, GRAY32, GRAY64, GRAY_SIGNED16, GRAY_SIGNED32, GRAY_FLOAT32, GRAY_FLOAT64, RGB8, RGB16, RGB_SIGNED16, RGB_SIGNED32, RGB_FLOAT32, RGB_FLOAT64, HSV_FLOAT64, YIQ_FLOAT64, BGRA8, RGBA8, YUV420 } |
| This enum indicates the acceptable image format values. More... | |
| enum | SnakeStrategy { SNAKE_EUCLIDEAN_DISTANCE } |
| enum | RansacInlierStrategy { DLR_CV_NAIVE_ERROR_THRESHOLD } |
| This enum is used by the RANSAC algorithm to select between the various ways of deciding whether a particular sample matches the current model. More... | |
Functions | |
| template<class Iter3D , class Iter2D > | |
| CameraIntrinsicsPinhole | estimateCameraIntrinsicsPinhole (size_t numPixelsX, size_t numPixelsY, Iter3D points3DBegin, Iter3D points3DEnd, Iter2D points2DBegin) |
| This function estimates pinhole camera intrinsic parameters based on corresponding points in 2D image coordinates and 3D camera coordinates. | |
| std::ostream & | operator<< (std::ostream &stream, const CameraIntrinsicsPinhole &intrinsics) |
| This function outputs a text representation of a CameraIntrinsicsPinhole instance to a std::ostream. | |
| std::istream & | operator>> (std::istream &stream, CameraIntrinsicsPinhole &intrinsics) |
| This function sets the value of a CameraIntrinsicsPinhole instance from a std::istream. | |
| std::ostream & | operator<< (std::ostream &stream, const CameraIntrinsicsPlumbBob &intrinsics) |
| This function outputs a text representation of a CameraIntrinsicsPlumbBob instance to a std::ostream. | |
| std::istream & | operator>> (std::istream &stream, CameraIntrinsicsPlumbBob &intrinsics) |
| This function sets the value of a CameraIntrinsicsPlumbBob instance from a std::istream. | |
| template<ImageFormat FORMAT> | |
| Image< GRAY1 > | applyCanny (const Image< FORMAT > &inputImage, size_t gaussianSize=5, double upperThreshold=0.0, double lowerThreshold=0.0, double autoUpperThresholdFactor=3.0, double autoLowerThresholdFactor=0.0) |
| This function applies the canny edge detector to the input image. | |
| template<ImageFormat FORMAT_OUT, ImageFormat FORMAT_IN> | |
| Image< FORMAT_OUT > | connectedComponents (const Image< FORMAT_IN > &inputImage) |
| This function does connected components analysis on a previously segmented image. | |
| template<ImageFormat FORMAT_OUT, ImageFormat FORMAT_IN> | |
| Image< FORMAT_OUT > | connectedComponents (const Image< FORMAT_IN > &inputImage, size_t &numberOfComponents) |
| This function is just like connectedComponents(const Image&), except that it also returns (by reference) the number of components in the image. | |
| template<ImageFormat FORMAT> | |
| Image< FORMAT > | dilate (const Image< FORMAT > &inputImage) |
| template<ImageFormat FORMAT> | |
| Image< FORMAT > | dilate (const Image< FORMAT > &inputImage, size_t radius) |
| void | normalizePointSequence (dlr::numeric::Array2D< double > const &inputPoints, dlr::numeric::Array2D< double > &outputPoints, dlr::numeric::Array2D< double > &transform) |
| This function is used internally by eightPointAlgorithm() to translate and scale input points so that their mean lies at the origin and they have isotropic unit variance. | |
| template<class Iterator > | |
| dlr::numeric::Array2D< double > | eightPointAlgorithm (Iterator sequence0Begin, Iterator sequence0End, Iterator sequence1Begin) |
| This function implements the "eight point algorithm"[1] for recovering the fundamental matrix of a pair of cameras from a sequence of at least eight pairs of corresponding image points. | |
| template<class Iterator > | |
| dlr::numeric::Array2D< double > | eightPointAlgorithm (Iterator sequence0Begin, Iterator sequence0End, Iterator sequence1Begin, dlr::numeric::Array1D< double > &eigenvalues) |
| WARNING: This function may go away at some point, or be replaced with a slightly different interface. | |
| template<ImageFormat FORMAT> | |
| Image< FORMAT > | erode (const Image< FORMAT > &inputImage) |
| template<class Iterator0 , class Iterator1 , class Functor > | |
| std::vector< std::pair< size_t, size_t > > | associateFeaturesScott91 (Iterator0 sequence0Begin, Iterator0 sequence0End, Iterator1 sequence1Begin, Iterator1 sequence1End, Functor similarityFunctor) |
| This function template implements the feature association algorithm of Guy Scott and H. | |
| template<ImageFormat OutputFormat, ImageFormat IntermediateFormat, ImageFormat ImageFormat, class KernelType > | |
| Image< OutputFormat > | filter2D (const Kernel< KernelType > &kernel, const Image< ImageFormat > &image, const typename ImageFormatTraits< OutputFormat >::PixelType fillValue, ConvolutionStrategy convolutionStrategy=DLR_CONVOLVE_PAD_RESULT) |
| This function filters an image with the given kernel. | |
| template<ImageFormat OutputFormat, ImageFormat IntermediateFormat, ImageFormat ImageFormat, class KernelType > | |
| void | filter2D (Image< OutputFormat > &outputImage, const Kernel< KernelType > &kernel, const Image< ImageFormat > &image, const typename ImageFormatTraits< OutputFormat >::PixelType fillValue, ConvolutionStrategy convolutionStrategy=DLR_CONVOLVE_PAD_RESULT) |
| This function filters an image with the given kernel, placing the result into a pre-constructed Image instance. | |
| double | checkEpipolarConstraint (dlr::numeric::Array2D< double > const &fundamentalMx, dlr::numeric::Vector2D &point0, dlr::numeric::Vector2D &point1) |
| dlr::numeric::Transform3D | getCameraMotionFromEssentialMatrix (dlr::numeric::Array2D< double > const &EE, dlr::numeric::Vector2D const &testPointCamera0, dlr::numeric::Vector2D const &testPointCamera1) |
| dlr::numeric::Vector3D | triangulateCalibratedImagePoint (dlr::numeric::Transform3D const &c0Tc1, dlr::numeric::Vector2D const &testPointCamera0, dlr::numeric::Vector2D const &testPointCamera1) |
| dlr::numeric::Array2D< double > | generateFivePointConstraintMatrix (dlr::numeric::Array2D< double > const &E0Array, dlr::numeric::Array2D< double > const &E1Array, dlr::numeric::Array2D< double > const &E2Array, dlr::numeric::Array2D< double > const &E3Array) |
| This function is used internally by fivePointAlgorithm() to generate a 10x20 matrix of coefficients of polynomial constraints. | |
| template<class Iterator > | |
| std::vector < dlr::numeric::Array2D < double > > | fivePointAlgorithm (Iterator sequence0Begin, Iterator sequence0End, Iterator sequence1Begin) |
| WARNING(xxx): The essential matrix returned by this funtion is currently not normalized to reasonable magnitude. | |
| template<class Iterator > | |
| dlr::numeric::Array2D< double > | fivePointAlgorithmRobust (Iterator sequence0Begin, Iterator sequence0End, Iterator sequence1Begin, size_t iterations, double inlierProportion, double &score, dlr::random::PseudoRandom pRandom=dlr::random::PseudoRandom()) |
| WARNING(xxx): The essential matrix returned by this funtion is currently not normalized to reasonable magnitude. | |
| template<class Iterator > | |
| void | fivePointAlgorithmRobust (Iterator sequence0Begin, Iterator sequence0End, Iterator sequence1Begin, Iterator sequence2Begin, size_t iterations, double inlierProportion, dlr::numeric::Array2D< double > &cam2Ecam0, dlr::numeric::Transform3D &cam0Tcam2, dlr::numeric::Transform3D &cam1Tcam2, double &score, dlr::random::PseudoRandom pRandom=dlr::random::PseudoRandom()) |
| Warning: this interface may change. | |
| template<ImageFormat FORMAT> | |
| Array2D< double > | getEuclideanDistance (const Image< FORMAT > &inputImage, size_t maxNumberOfPasses) |
| template<ImageFormat FORMAT> | |
| Array2D< double > | getEuclideanDistance (const Image< FORMAT > &inputImage, size_t maxNumberOfPasses, size_t &numberOfPassesUsed) |
| Array1D< unsigned int > | getHistogram (const Image< GRAY8 > &inputImage) |
| This function computes the histogram of an image. | |
| Image< GRAY8 > | histogramEqualize (const Image< GRAY8 > &inputImage) |
| This function remaps the pixel values of the input image in such a way that output pixel value increases monotonically with input pixel value, and the histogram of the output image is nearly flat. | |
| Image< GRAY8 > | readPGM8 (const std::string &fileName) |
| Image< GRAY8 > | readPGM8 (const std::string &fileName, std::string &commentString) |
| Image< GRAY16 > | readPGM16 (const std::string &fileName) |
| Image< RGB8 > | readPPM8 (const std::string &fileName) |
| Image< RGB8 > | readPPM8 (const std::string &fileName, std::string &commentString) |
| void | writePGM8 (const std::string &fileName, const Image< GRAY8 > &outputImage, const std::string &comment) |
| void | writePGM16 (const std::string &fileName, const Image< GRAY16 > &outputImage, const std::string &comment) |
| void | writePPM8 (const std::string &fileName, const Image< RGB8 > &outputImage, const std::string &comment) |
| Image< GRAY8 > | readPNG8 (const std::string &fileName, std::string &commentString) |
| WARNING: This routine may not stick around for long. | |
| void | writePNG8 (const std::string &fileName, const Image< GRAY8 > &outputImage, const std::string &comment="") |
| WARNING: This routine may not stick around for long. | |
| template<class KERNEL_TYPE > | |
| Kernel< KERNEL_TYPE > | getGaussianKernel (double rowSigma, double columnSigma) |
| This function generates and returns a separable Gaussian kernel of user-specified standard deviation. | |
| template<class KERNEL_TYPE > | |
| Kernel< KERNEL_TYPE > | getGaussianKernel (size_t rows, size_t columns, double rowSigma=-1.0, double columnSigma=-1.0) |
| This function generates and returns a separable Gaussian kernel with the same variance along each axis. | |
| template<ImageFormat FORMAT> | |
| Image< FORMAT > | nonMaximumSuppress (const Image< FORMAT > &inputImage, const Array2D< Float64 > &gradX, const Array2D< Float64 > &gradY) |
| This function zeros any pixels of the input image which are not plausible edges. | |
| template<class TYPE > | |
| PixelBGRA< TYPE > | operator- (const PixelBGRA< TYPE > &pixel0, const PixelBGRA< TYPE > &pixel1) |
| This operator subtracts the values of the individual color components of its arguments. | |
| template<class TYPE > | |
| bool | operator== (const PixelBGRA< TYPE > &pixel0, const PixelBGRA< TYPE > &pixel1) |
| This operator returns true if the contents of the two argments are identical, false otherwise. | |
| template<class TYPE > | |
| PixelHSV< TYPE > | operator- (const PixelHSV< TYPE > &pixel0, const PixelHSV< TYPE > &pixel1) |
| This operator subtracts the values of the individual color components of its arguments. | |
| template<class TYPE > | |
| bool | operator== (const PixelHSV< TYPE > &pixel0, const PixelHSV< TYPE > &pixel1) |
| This operator returns true if the contents of the two argments are identical, false otherwise. | |
| template<class Scalar , class Type > | |
| PixelRGB< typename dlr::common::TypePromoter < Scalar, Type >::ResultType > | operator* (Scalar scalar, const PixelRGB< Type > &pixel1) |
| This operator multiplies the color component values of a pixel by a scalar. | |
| template<class Type0 , class Type1 > | |
| PixelRGB< typename dlr::common::TypePromoter < Type0, Type1 >::ResultType > | operator+ (const PixelRGB< Type0 > &pixel0, const PixelRGB< Type1 > &pixel1) |
| This operator adds the values of the individual color components of its arguments. | |
| template<class Type0 , class Type1 > | |
| PixelRGB< typename dlr::common::TypePromoter < Type0, Type1 >::ResultType > | operator- (const PixelRGB< Type0 > &pixel0, const PixelRGB< Type1 > &pixel1) |
| This operator subtracts the values of the individual color components of its arguments. | |
| template<class Type0 , class Type1 > | |
| PixelRGB< typename dlr::common::TypePromoter < Type0, Type1 >::ResultType > | operator* (const PixelRGB< Type0 > &pixel0, const PixelRGB< Type1 > &pixel1) |
| This operator multiplies the values of the individual color components of its arguments. | |
| template<class Type0 , class Type1 > | |
| PixelRGB< typename dlr::common::TypePromoter < Type0, Type1 >::ResultType > | operator/ (const PixelRGB< Type0 > &pixel0, const PixelRGB< Type1 > &pixel1) |
| This operator divides the values of the individual color components of its arguments. | |
| template<class Type > | |
| bool | operator== (const PixelRGB< Type > &pixel0, const PixelRGB< Type > &pixel1) |
| This operator returns true if the contents of the two argments are identical, false otherwise. | |
| template<class TYPE > | |
| PixelRGBA< TYPE > | operator- (const PixelRGBA< TYPE > &pixel0, const PixelRGBA< TYPE > &pixel1) |
| This operator subtracts the values of the individual color components of its arguments. | |
| template<class TYPE > | |
| bool | operator== (const PixelRGBA< TYPE > &pixel0, const PixelRGBA< TYPE > &pixel1) |
| This operator returns true if the contents of the two argments are identical, false otherwise. | |
| template<class TYPE > | |
| PixelYIQ< TYPE > | operator- (const PixelYIQ< TYPE > &pixel0, const PixelYIQ< TYPE > &pixel1) |
| This operator subtracts the values of the individual color components of its arguments. | |
| template<class TYPE > | |
| bool | operator== (const PixelYIQ< TYPE > &pixel0, const PixelYIQ< TYPE > &pixel1) |
| This operator returns true if the contents of the two argments are identical, false otherwise. | |
| template<class InIter0 , class InIter1 > | |
| Transform3D | registerPoints3D (InIter0 fromPointsBegin, InIter0 fromPointsEnd, InIter1 toPointsBegin) |
| Using Horn's method, from "Closed-form solution of absolute orientation using unit quaternions", J. | |
| template<class InIter0 , class InIter1 , class InIter2 > | |
| Transform3D | registerPoints3D (InIter0 fromPointsBegin, InIter0 fromPointsEnd, InIter1 toPointsBegin, InIter2 selectedFlagsBegin) |
| This function works just like the three-argument form of registerPoints3D(), except that only selected points are considered in the registration. | |
| template<class InIter0 , class InIter1 , class OutIter0 > | |
| Transform3D | registerPoints3D (InIter0 fromPointsBegin, InIter0 fromPointsEnd, InIter1 toPointsBegin, OutIter0 selectedFlagsBegin, double inclusion, double maximumResidual=-1.0, size_t maximumIterations=5) |
| This function calls the four-argument form of registerPoints3D() repeatedly while trying to identify and ignore outliers. | |
| bool | operator< (Edge const &arg0, Edge const &arg1) |
| template<ImageFormat FORMAT> | |
| Image< FORMAT > | applySobelX (const Image< FORMAT > &inputImage, bool normalizeResult=false) |
| This function applies the sobel edge operator in the X direction. | |
| template<ImageFormat FORMAT> | |
| Image< FORMAT > | applySobelY (const Image< FORMAT > &inputImage, bool normalizeResult=false) |
| This function applies the sobel edge operator in the Y direction. | |
| void | stereoRectify (CameraIntrinsicsPinhole const &intrinsics0, CameraIntrinsicsPinhole const &intrinsics1, numeric::Transform3D const &camera0Tworld, numeric::Transform3D const &camera1Tworld, CameraIntrinsicsPinhole &rectifiedIntrinsics0, CameraIntrinsicsPinhole &rectifiedIntrinsics1, numeric::Transform3D &rcamera0Tworld, numeric::Transform3D &rcamera1Tworld, numeric::Transform2D &image0Trimage0, numeric::Transform2D &image1Trimage1) |
| A. | |
| template<class IterType > | |
| unsigned int | threePointAlgorithm (dlr::numeric::Vector3D const &w0, dlr::numeric::Vector3D const &w1, dlr::numeric::Vector3D const &w2, dlr::numeric::Vector2D const &u0, dlr::numeric::Vector2D const &u1, dlr::numeric::Vector2D const &u2, CameraIntrinsicsPinhole const &intrinsics, IterType p0OutputIter, IterType p1OutputIter, IterType p2OutputIter, double epsilon=1.0E-8) |
| This function implements the "three point perspective pose estimation algorithm" of Grunert[1][2] for recovering the camera-frame coordinates of the corners of a triangle of known size, given the projections of those corners in the camera image. | |
| template<class InIter3D , class InIter2D , class OutIter3D > | |
| dlr::numeric::Transform3D | threePointAlgorithmRobust (InIter3D worldPointsBegin, InIter3D worldPointsEnd, InIter2D imagePointsBegin, CameraIntrinsicsPinhole const &intrinsics, size_t iterations, double inlierProportion, double &score, dlr::random::PseudoRandom &pRandom=dlr::random::PseudoRandom()) |
| This function implements the "robust" version of threePointAlgorithm(). | |
| template<class OutIter > | |
| unsigned int | solveThreePointAlgorithmQuarticSystem (double cosAlpha, double cosBeta, double cosGamma, double a2, double b2, double c2, double epsilon, OutIter s0Iter, OutIter s1Iter, OutIter s2Iter, double &condition) |
| template<ImageFormat FORMAT> | |
| bool | associateColorComponents (Array2D< typename ImageFormatTraits< FORMAT >::ComponentType > &inputArray, Image< FORMAT > &outputImage) |
| This function returns by reference an image which either shares or copies the data from the input array. | |
| template<ImageFormat FORMAT> | |
| Image< FORMAT > | associateColorComponents (Array2D< typename ImageFormatTraits< FORMAT >::ComponentType > &inputArray) |
| template<ImageFormat OUTPUT_FORMAT, ImageFormat INPUT_FORMAT> | |
| Image< OUTPUT_FORMAT > | convertColorspace (const Image< INPUT_FORMAT > &inputImage) |
| This function takes an image in one colorspace and generates a corresponding image in a second colorspace. | |
| template<ImageFormat FORMAT> | |
| bool | dissociateColorComponents (Image< FORMAT > &inputImage, Array2D< typename ImageFormatTraits< FORMAT >::ComponentType > &outputArray) |
| This function returns by reference an array which either shares or copies the data from the input image. | |
| template<ImageFormat FORMAT> | |
| Array2D< typename ImageFormatTraits< FORMAT > ::ComponentType > | dissociateColorComponents (Image< FORMAT > &inputImage) |
| template<ImageFormat Format> | |
| Image< Format > | subsample (const Image< Format > &inputImage, size_t rowStep=2, size_t columnStep=2) |
| This function subsamples its input to create a new, smaller image. | |
| template<ImageFormat InputFormat, ImageFormat OutputFormat, ImageFormat IntermediateFormat> | |
| Image< OutputFormat > | supersample (const Image< InputFormat > &inputImage) |
| This function interpolates its input to create a new, larger image. | |
| template<class Type , ImageFormat FORMAT> | |
| Array2D< Type > | toArray (const Image< FORMAT > &inputImage) |
| This function creates a new array and copies into it the pixel data from the input image. | |
Feel free to play around with it, but please bear in mind that its interface is not stable.
This enum indicates the acceptable image format values.
Please see the ImageFormatTraits class template for the characteristics of these image formats.
Definition at line 27 of file imageFormat.h.
| Image< GRAY1 > dlr::computerVision::applyCanny | ( | const Image< FORMAT > & | inputImage, | |
| size_t | gaussianSize = 5, |
|||
| double | upperThreshold = 0.0, |
|||
| double | lowerThreshold = 0.0, |
|||
| double | autoUpperThresholdFactor = 3.0, |
|||
| double | autoLowerThresholdFactor = 0.0 | |||
| ) | [inline] |
This function applies the canny edge detector to the input image.
| inputImage | This argument is the image to be edge-detected. | |
| gaussianSize | This argument specifies the size, in pixels, of the blurring filter to be applied to the image prior to edge detection. The sigma of the blurring filter will be set to 1/6 of this size. This argument must be zero or an odd number. Setting this argument to zero disables the pre-filter. | |
| upperThreshold | This argument specifies the gradient magnitude necessary for a pixel to be considered a "seed" point from which to grow a new edge. If this argument is less than or equal to 0.0, it will be calculated automatically using the value of argument autoUpperThresholdFactor. | |
| lowerThreshold | This argument specifies the gradient magnitude necessary for a pixel to be considered as part of an existing edge. If this argument is less than or equal to 0.0, it will be calculated automatically using the value of argument autoUpperThresholdFactor. | |
| autoUpperThresholdFactor | If upperThreshold is less than or equal to zero, then this argument is used to set calculate the threshold automatically. Smaller values (and increasingly large negative values) make it easier to start an edge. If argument upperThreshold is greater than 0.0, then this argument is ignored. | |
| autoLowerThresholdFactor | If lowerThreshold is less than or equal to zero, then this argument is used to calculate the threshold automatically. Its value should be positive and less than or equal to autoUpperThresholdFactor. Larger values make edges shorter. Smaller values (and increasingly large negative values) make edges tend to stretch out longer. If argument lowerThreshold is greater than 0.0, then this argument is ignored. |
Definition at line 213 of file canny.h.
References applySobelX(), applySobelY(), and nonMaximumSuppress().
| Image< FORMAT > dlr::computerVision::applySobelX | ( | const Image< FORMAT > & | inputImage, | |
| bool | normalizeResult = false | |||
| ) | [inline] |
This function applies the sobel edge operator in the X direction.
Specifically, convolves the image with the 3x3 kernel
[[-1, 0, 1],
[-2, 0, 2],
[-1, 0, 1]]
and then optionally rescales the result to be proportional to the image gradient with scale factor 1.0.
| inputImage | This argument is the image to be convolved. | |
| normalizeResult | This argument specifies whether or not to divide the resulting pixel values by 8. Setting this argument to true will result in lost precision on integer types. This feature is currently not implemented, so please leave normalizeResult at its default value of false. |
Definition at line 96 of file sobel.h.
Referenced by applyCanny().
| Image< FORMAT > dlr::computerVision::applySobelY | ( | const Image< FORMAT > & | inputImage, | |
| bool | normalizeResult = false | |||
| ) | [inline] |
This function applies the sobel edge operator in the Y direction.
Specifically, convolves the image with the 3x3 kernel
[[-1, -2, -1],
[ 0, 0, 0],
[ 1, 2, 1]]
and then optionally rescales the result to be proportional to the image gradient with scale factor 1.0.
| inputImage | This argument is the image to be convolved. | |
| normalizeResult | This argument specifies whether or not to divide the resulting pixel values by 8. Setting this argument to true will result in lost precision on integer types. This feature is currently not implemented, so please leave normalizeResult at its default value of false. |
Definition at line 192 of file sobel.h.
Referenced by applyCanny().
| Image< FORMAT > dlr::computerVision::associateColorComponents | ( | Array2D< typename ImageFormatTraits< FORMAT >::ComponentType > & | inputArray | ) | [inline] |
WARNING: The returned image does no memory management. It is only valid until the original input image is destroyed.
| inputArray | This argument is the array from which to construct the return image. |
Definition at line 588 of file utilities.h.
References associateColorComponents().
| bool dlr::computerVision::associateColorComponents | ( | Array2D< typename ImageFormatTraits< FORMAT >::ComponentType > & | inputArray, | |
| Image< FORMAT > & | outputImage | |||
| ) | [inline] |
This function returns by reference an image which either shares or copies the data from the input array.
If possible, this function returns an Image which references the same memory as the input array, but in which each pixel is the aggregate of the appropriate number of elements from the array. For example, if this function is called with template argument RGB8, and an Nx(3*M) array of UnsignedInt8 is passed as the argument, then the return value will be an NxM Image<RGB8> which references the same memory as the argument. Imagine that the first three elements of the first row of the argument are 12, 14, and 72. In this case, the upper-left RGB value of the returned image image is {12, 14, 72}. This memory sharing only works if the compiler does not "pad" the pixel struct to byte align its members.
If memory sharing is not possible, then this function tests the size of argument outputImage, reinitializes it only if the size does not match the size of the input array, and then copies the data from inputArray to outputImage.
WARNING: If data sharing is possible, the returned image does no memory management. It is only valid until the original input data is destroyed.
If you use this function in conjunction with dissociateColorComponents(), you can simply ignore the question of whether the data sharing works or not. For example, you might use associateColorComponents to get an Image to operate on, do all of your image processing, and then use dissocateColorComponents to get back to a flat array. If data sharing is possible, all of your operations will have taken place in the original array. If data sharing isn't possible, then the two functions will take care of copying back and forth between the image and the flat array.
| inputArray | This argument is the array from which to construct the return image. | |
| outputImage | This argument is the image which will be modified or copied to. |
Definition at line 574 of file utilities.h.
Referenced by associateColorComponents().
| std::vector< std::pair< size_t, size_t > > dlr::computerVision::associateFeaturesScott91 | ( | Iterator0 | sequence0Begin, | |
| Iterator0 | sequence0End, | |||
| Iterator1 | sequence1Begin, | |||
| Iterator1 | sequence1End, | |||
| Functor | similarityFunctor | |||
| ) | [inline] |
This function template implements the feature association algorithm of Guy Scott and H.
Christopher Longuet-Higgins, as described in [1].
Template argument Functor must implement a similarity measure for compariing pairs of features. For example, calling
similarityFunctor(*sequenc0Begin, *sequence1Begin)
Should return a double precision similarity measure between 0.0 and 1.0. Scott's suggested similarity measure is:
g = exp(-r_ij^2 / 2*sigma^2),
where g is the similarity result, r_ij is the distance between point i in the first feature set and point j in the second feature set, and sigma is a parameter setting how sensitive the algorithm is to increasing distance between matched features (large alpha gives low sensitivity, small alpha gives high sensitivity).
[1] G. L. Scott and H. C. Longuet Higgins, "An Algorithm for Associating the Features of Two Images," Proceedings of Biological Sciences, Vol. 244, No. 1309, pp. 21-26, April, 1991.
| sequence0Begin | This argument is an STL style iterator pointing to the first element of the first feature sequence. | |
| sequence0End | This argument is an STL style iterator pointing one-past-the-last element of the first feature sequence. | |
| sequence1Begin | This argument is an STL style iterator pointing to the first element of the second feature sequence. | |
| sequence1End | This argument is an STL style iterator pointing one-past-the-last element of the second feature sequence. | |
| similarityFunctor | This argument specifies a functor that takes two features and computes their similarity. |
Definition at line 108 of file featureAssociation.h.
| Image< FORMAT_OUT > dlr::computerVision::connectedComponents | ( | const Image< FORMAT_IN > & | inputImage, | |
| size_t & | numberOfComponents | |||
| ) | [inline] |
This function is just like connectedComponents(const Image&), except that it also returns (by reference) the number of components in the image.
| inputImage | This argument is the segmented image. Pixels which are not part of a blob must have value of 0. All other values are considered to be blob pixels. All non-zero pixels are considered to be part of the same class. That is, adjacent pixels with different non-zero values will be considered to be part of the same blob. | |
| numberOfComponents | This argument returns by reference how many distinct components were identified in the image, not counting the background. |
Definition at line 156 of file connectedComponents.h.
| Image< FORMAT_OUT > dlr::computerVision::connectedComponents | ( | const Image< FORMAT_IN > & | inputImage | ) | [inline] |
This function does connected components analysis on a previously segmented image.
| inputImage | This argument is the segmented image. Pixels which are not part of a blob must have value of 0. All other values are considered to be blob pixels. All non-zero pixels are considered to be part of the same class. That is, adjacent pixels with different non-zero values will be considered to be part of the same blob. |
Definition at line 145 of file connectedComponents.h.
| Image< OUTPUT_FORMAT > dlr::computerVision::convertColorspace | ( | const Image< INPUT_FORMAT > & | inputImage | ) | [inline] |
This function takes an image in one colorspace and generates a corresponding image in a second colorspace.
Use this function as follows:
Image<GRAY8> = convertColorspace<GRAY8, RGB16>(myRGB16Image);
or equivalently, the second template argument can be left implicit,
Image<GRAY8> = convertColorspace<GRAY8>(myRGB16Image);
This function only works for image formats in which there's a one-to-one mapping between input and output pixel types. When converting between formats which don't match this requirement, such as when converting from RGB8 to YUV420, please use a different routine.
| inputImage | This argument is the image to be converted. |
Definition at line 609 of file utilities.h.
| Array2D< typename ImageFormatTraits< FORMAT >::ComponentType > dlr::computerVision::dissociateColorComponents | ( | Image< FORMAT > & | inputImage | ) | [inline] |
WARNING: The returned array does no memory management. It is only valid until the original input image is destroyed.
| inputImage | This argument is the image from which to construct the return array. |
Definition at line 638 of file utilities.h.
References dissociateColorComponents().
| bool dlr::computerVision::dissociateColorComponents | ( | Image< FORMAT > & | inputImage, | |
| Array2D< typename ImageFormatTraits< FORMAT >::ComponentType > & | outputArray | |||
| ) | [inline] |
This function returns by reference an array which either shares or copies the data from the input image.
If possible, this function returns an Array2D which references the same memory as the input image, but in which each pixel has been "flattened" so that the returned array has a separate element for each color component of each pixel. For example, if this function is called with an NxM Image<RGB8> as its argument, the returned value will be an Nx(3*M) array of 8-bit unsigned ints which references the same memorty. Imagine that the upper-left RGB value of the image is {12, 14, 72}. In this case, the first three elements of first row of the returned image will be 12, 14, and 72. This memory sharing only works if the compiler does not "pad" the pixel struct to byte align its members.
If memory sharing is not possible, then this function tests the size of argument outputArray, reinitializes it only if the size does not match the size of the input image, and then copies the data from inputImage to outputArray.
WARNING: If data sharing is possible, the returned array does no memory management. It is only valid until the original input data is destroyed.
If you use this function in conjunction with associateColorComponents(), you can simply ignore the question of whether the data sharing works or not. For example, you might use associateColorComponents to get an Image to operate on, do all of your image processing, and then use dissocateColorComponents to get back to a flat array. If data sharing is possible, all of your operations will have taken place in the original array. If data sharing isn't possible, then the two functions will take care of copying back and forth between the image and the flat array.
| inputImage | This argument is the image from which to construct the return array. |
Definition at line 624 of file utilities.h.
Referenced by dissociateColorComponents(), and toArray().
| dlr::numeric::Array2D< double > dlr::computerVision::eightPointAlgorithm | ( | Iterator | sequence0Begin, | |
| Iterator | sequence0End, | |||
| Iterator | sequence1Begin, | |||
| dlr::numeric::Array1D< double > & | eigenvalues | |||
| ) | [inline] |
WARNING: This function may go away at some point, or be replaced with a slightly different interface.
This function is just like the other version of eightPointAlgorithm(), except that it returns by reference
| sequence0Begin | This argument matches the corresponding argument of the other version of eightPointAlgorithm(). | |
| sequence0End | This argument matches the corresponding argument of the other version of eightPointAlgorithm(). | |
| sequence1Begin | This argument matches the corresponding argument of the other version of eightPointAlgorithm(). | |
| eigenvalues | This argument returns by reference a vector of eigenvalues used in computing the result of the function call. Only the last one should be close to zero. |
Definition at line 160 of file eightPointAlgorithm.h.
References normalizePointSequence().
| dlr::numeric::Array2D< double > dlr::computerVision::eightPointAlgorithm | ( | Iterator | sequence0Begin, | |
| Iterator | sequence0End, | |||
| Iterator | sequence1Begin | |||
| ) | [inline] |
This function implements the "eight point algorithm"[1] for recovering the fundamental matrix of a pair of cameras from a sequence of at least eight pairs of corresponding image points.
That is, it recovers the matrix F, such that
transpose(u') * F * u = 0
where u is a homogeneous 2D point in the first image, u' is a homogeneous 2D point in the second image, and the symbol "*" indicates matrix multiplication.
This implementation implements the input transformation described in [2] to improve the numerical stability of the result.
[1] Longuet-Higgins, H.C., "A Computer Algorithm for Reconstructing a Scene From Two Projections," Nature, vol. 293, pp. 133Â135, Sept 1981.
[2] Hartley, R. I., "In Defense of the Eight Point Algorithm." IEEE Transactions on Pattern Analysis and Machine Intelligence, vol. 19, No. 6, pp. 580-593, June 1997.
| sequence0Begin | This argument is the beginning (in the STL sense) of a sequence of feature points, represented as dlr::numeric::Vector2D instances, from the first image (the u points in the equation above). | |
| sequence0End | This argument is the end (in the STL sense) of a sequence of feature points, represented as dlr::numeric::Vector2D instances, from the first image (the u points in the equation above). | |
| sequence1Begin | This argument is the beginning (in the STL sense) of a sequence of feature points, represented as dlr::numeric::Vector2D instances, from the second image (the u' points in the equation above). |
Definition at line 149 of file eightPointAlgorithm.h.
| CameraIntrinsicsPinhole dlr::computerVision::estimateCameraIntrinsicsPinhole | ( | size_t | numPixelsX, | |
| size_t | numPixelsY, | |||
| Iter3D | points3DBegin, | |||
| Iter3D | points3DEnd, | |||
| Iter2D | points2DBegin | |||
| ) | [inline] |
This function estimates pinhole camera intrinsic parameters based on corresponding points in 2D image coordinates and 3D camera coordinates.
If it is not possible to compute a valid CameraIntrinsicsPinhole instance from the input points, this function will throw ValueException.
| numPixelsX | This argument specifies the number of columns in images corresponding to this pinhole camera. It is copied directly in to the return value, and does not otherwise affect the operation of this funtion. | |
| numPixelsY | This argument specifies the number of columns in images corresponding to this pinhole camera. It is copied directly in to the return value, and does not otherwise affect the operation of this funtion. | |
| points3DBegin | This argument is an iterator pointing to the beginning of a sequence of 3D points in camera coordinates. The sequence must contain at least 3 elements. | |
| points2DEnd | This argument is an iterator pointing one element past the end of the sequence of 3D points in camera coordinates (following the standard library iterator convention). | |
| points2DBegin | This argument is an iterator pointing to the beginning of a sequence of 2D points in camera coordinates, corresponding to the the sequence defined by points3DBegin and points3DEnd. Each element of this sequence must be the projection of the corresponding element of the sequence of 3D image points. |
Definition at line 88 of file calibrationTools.h.
| void dlr::computerVision::filter2D | ( | Image< OutputFormat > & | outputImage, | |
| const Kernel< KernelType > & | kernel, | |||
| const Image< ImageFormat > & | image, | |||
| const typename ImageFormatTraits< OutputFormat >::PixelType | fillValue, | |||
| ConvolutionStrategy | convolutionStrategy = DLR_CONVOLVE_PAD_RESULT | |||
| ) | [inline] |
This function filters an image with the given kernel, placing the result into a pre-constructed Image instance.
Argument "convolutionStrategy" indicates what to do with the edges of the filtered image (where the filter kernel only partially overlaps the input image). Currently filter() only supports DLR_CONVOLVE_PAD_RESULT.
| outputImage | This argument is used to return the result. The associated memory is not reallocated unless outputImage has a different number of rows and/or columns than image. | |
| kernel | This argument is the Kernel instance with which to filter. | |
| image | This argument is the Image to be filtered. | |
| fillValue | This argument specifies the value with which image edges should be padded. | |
| convolutionStrategy | This argument specifies how to handle the edges of the image. Please see the dlrNumeric documentation for more information. |
Definition at line 498 of file filter.h.
References dlr::computerVision::Kernel< ELEMENT_TYPE >::getArray2D(), dlr::computerVision::Kernel< ELEMENT_TYPE >::getColumnComponent(), dlr::computerVision::Kernel< ELEMENT_TYPE >::getRowComponent(), and dlr::computerVision::Kernel< ELEMENT_TYPE >::isSeparable().
| Image< OutputFormat > dlr::computerVision::filter2D | ( | const Kernel< KernelType > & | kernel, | |
| const Image< ImageFormat > & | image, | |||
| const typename ImageFormatTraits< OutputFormat >::PixelType | fillValue, | |||
| ConvolutionStrategy | convolutionStrategy = DLR_CONVOLVE_PAD_RESULT | |||
| ) | [inline] |
This function filters an image with the given kernel.
Argument "convolutionStrategy" indicates what to do with the edges of the filtered image (where the filter kernel only partially overlaps the input image). Currently filter() only supports DLR_CONVOLVE_PAD_RESULT.
| kernel | This argument is the Kernel instance with which to filter. | |
| image | This argument is the Image to be filtered. | |
| fillValue | This argument specifies the value with which image edges should be padded. | |
| convolutionStrategy | This argument specifies how to handle the edges of the image. Please see the dlrNumeric documentation for more information. |
| std::vector< dlr::numeric::Array2D< double > > dlr::computerVision::fivePointAlgorithm | ( | Iterator | sequence0Begin, | |
| Iterator | sequence0End, | |||
| Iterator | sequence1Begin | |||
| ) | [inline] |
WARNING(xxx): The essential matrix returned by this funtion is currently not normalized to reasonable magnitude.
You can easily get back a matrix in which the average element magnitude is on the order of 1.0E12.
This function implements the "five point algorithm"[1] for recovering the essential matrix of a pair of cameras from a sequence of at least five pairs of corresponding image points. That is, it recovers the matrix E, such that
transpose(q') * E * q = 0
where q is a homogeneous 2D point in the "calibrated coordinate system" of the first image (see below), q' is a homogeneous 2D point in calibrated coordinate system of the second image, and the symbol "*" indicates matrix multiplication.
This algorithm differs from the eight point algorithm in that the intrinsic parameters of both cameras must be known. For pinhole cameras, points in the calibrated cooridinate system of the camera are related to points in the pixel coordinate system by the equations
q = inverse(K) * u q' = inverse(K') * u'
where K and K' are 3x3 matrices encoding the camera intrinsic parameters. Typically, a K matrix will look something like this:
|f/k_u, 0, C_u|
K = | 0, f/k_v, C_v|
| 0, 0, 1|
where f is the focal length of the camera, k_u & k_v describe the physical size of camera pixels in the horizontal and vertical directions, respectively, and C_u & C_v are the image coordinates of the camera projection center.
[1] Henrik Stewénius, Christopher Engels, and David Nistér, "Recent Developments on Direct Relative Orientation." ISPRS Journal of Photogrammetry and Remote Sensing, vol. 60, no. 4, pp. 284-294, January 2006.
| sequence0Begin | This argument is the beginning (in the STL sense) of a sequence of calibrated feature points, represented as dlr::numeric::Vector2D instances, from the first image (the q points in the equation above). You might generate this sequence of points by taking raw image coordinates and then left-multiplying them by inverse(K). | |
| sequence0End | This argument is the end (in the STL sense) of a sequence begun by sequence0Begin. | |
| sequence1Begin | This argument is the beginning (in the STL sense) of a sequence of calibrated feature points, represented as dlr::numeric::Vector2D instances, from the second image (the q' points in the equation above). You might generate this sequence of points by taking raw image coordinates and then left-multiplying them by inverse(K'). |
Definition at line 340 of file fivePointAlgorithm.h.
References generateFivePointConstraintMatrix().
Referenced by fivePointAlgorithmRobust().
| void dlr::computerVision::fivePointAlgorithmRobust | ( | Iterator | sequence0Begin, | |
| Iterator | sequence0End, | |||
| Iterator | sequence1Begin, | |||
| Iterator | sequence2Begin, | |||
| size_t | iterations, | |||
| double | inlierProportion, | |||
| dlr::numeric::Array2D< double > & | cam2Ecam0, | |||
| dlr::numeric::Transform3D & | cam0Tcam2, | |||
| dlr::numeric::Transform3D & | cam1Tcam2, | |||
| double & | score, | |||
| dlr::random::PseudoRandom | pRandom = dlr::random::PseudoRandom() | |||
| ) | [inline] |
Warning: this interface may change.
This function implements the three-view robust five-point algorithm described in section 5 of [2].
| sequence0Begin | This argument is the beginning (in the STL sense) of a sequence of calibrated feature points, represented as dlr::numeric::Vector2D instances, from the first image (the q points in the equation above). You might generate this sequence of points by taking raw image coordinates and then left-multiplying them by inverse(K). | |
| sequence0End | This argument is the end (in the STL sense) of a sequence begun by sequence0Begin. | |
| sequence1Begin | This argument is the beginning (in the STL sense) of a sequence of calibrated feature points, represented as dlr::numeric::Vector2D instances, from the second image (the q' points in the equation above). You might generate this sequence of points by taking raw image coordinates and then left-multiplying them by inverse(K'). | |
| sequence2Begin | This argument is the beginning (in the STL sense) of a sequence of calibrated feature points, represented as dlr::numeric::Vector2D instances, from the third image. | |
| iterations | This argument specifies how many random samples of fiv points each should be used to generate hypothetical essential matrices. Setting this number high increases the chances that you'll find the right answer, however runtime is directly proportional to the number of iterations. | |
| inlierProportion | This argument specifies what proportion of the input point pairs you expect to be correctly matched. Set this a little low, so that you're confident there are at least inlierProportion * (sequence0End - sequence0Begin) correct feature matches in the input data. | |
| cam2Ecam0 | This argument returns by reference the recovered Essential matrix between the third image and the first image, so that transpose(q'') * cam2Ecam0 * q = 0. | |
| cam0Tcam2 | This argument returns by reference a recovered coordinate transformation taking 3D points from the coordinate frame of third camera and converting them to the coordinate frame of first camera. | |
| cam1Tcam2 | This argument returns by reference a recovered coordinate transformation taking 3D points from the coordinate frame of third camera and converting them to the coordinate frame of second camera. | |
| score | This argument returns a value indicating how good the returned parameters are. 0.0 is perfect. 1.0 is terrible. | |
| pRandom | This argument is a pseudorandom number generator used by the algorithm to select sets of three input points. |
Definition at line 640 of file fivePointAlgorithm.h.
References fivePointAlgorithm(), and threePointAlgorithmRobust().
| dlr::numeric::Array2D< double > dlr::computerVision::fivePointAlgorithmRobust | ( | Iterator | sequence0Begin, | |
| Iterator | sequence0End, | |||
| Iterator | sequence1Begin, | |||
| size_t | iterations, | |||
| double | inlierProportion, | |||
| double & | score, | |||
| dlr::random::PseudoRandom | pRandom = dlr::random::PseudoRandom() | |||
| ) | [inline] |
WARNING(xxx): The essential matrix returned by this funtion is currently not normalized to reasonable magnitude.
You can easily get back a matrix in which the average element magnitude is on the order of 1.0E12.
Warning: this interface may change.
This function implements the two-view robust five-point algorithm described in section 5 of [2]. Note that our method of computing the goodness of a potential solution for the essential matrix involves testing feature point pairs against the (image-space) epipolar constraint. We do not project features into 3D space and compute errors there.
[2] David Nister, "An Efficient Solution to the Five-Point Relative Pose Problem." IEEE Transactions on Pattern Analysis and Machine Intelligence (PAMI), vol. 26, no. 6, pp. 756-770, June 2004.
| sequence0Begin | This argument is the beginning (in the STL sense) of a sequence of calibrated feature points, represented as dlr::numeric::Vector2D instances, from the first image (the q points in the equation above). You might generate this sequence of points by taking raw image coordinates and then left-multiplying them by inverse(K). | |
| sequence0End | This argument is the end (in the STL sense) of a sequence begun by sequence0Begin. | |
| sequence1Begin | This argument is the beginning (in the STL sense) of a sequence of calibrated feature points, represented as dlr::numeric::Vector2D instances, from the second image (the q' points in the equation above). You might generate this sequence of points by taking raw image coordinates and then left-multiplying them by inverse(K'). | |
| iterations | This argument specifies how many random samples of five points each should be used to generate hypothetical essential matrices. Setting this number high increases the chances that you'll find the right answer, however runtime is directly proportional to the number of iterations. | |
| inlierProportion | This argument specifies what proportion of the input point pairs you expect to be correctly matched. Set this a little low, so that you're confident there are at least inlierProportion * (sequence0End - sequence0Begin) correct feature matches in the input data. | |
| score | This argument returns a value indicating how good the returned essential matrix is. 0.0 is perfect. 1.0 is terrible. |
Definition at line 570 of file fivePointAlgorithm.h.
References fivePointAlgorithm().
| dlr::numeric::Array2D< double > dlr::computerVision::generateFivePointConstraintMatrix | ( | dlr::numeric::Array2D< double > const & | E0Array, | |
| dlr::numeric::Array2D< double > const & | E1Array, | |||
| dlr::numeric::Array2D< double > const & | E2Array, | |||
| dlr::numeric::Array2D< double > const & | E3Array | |||
| ) |
This function is used internally by fivePointAlgorithm() to generate a 10x20 matrix of coefficients of polynomial constraints.
It will normally not be useful unless you happen to be implementing a similar five point algorithm solver (such as the one described in [2], which is faster, but slightly less accurate.
| E0Array | This argument is the first basis element of the null space of the system of linear constraints on the essential matrix. | |
| E1Array | This argument is the first basis element of the null space of the system of linear constraints on the essential matrix. | |
| E2Array | This argument is the first basis element of the null space of the system of linear constraints on the essential matrix. | |
| E3Array | This argument is the first basis element of the null space of the system of linear constraints on the essential matrix. |
Definition at line 231 of file fivePointAlgorithm.cpp.
Referenced by fivePointAlgorithm().
| Kernel< KERNEL_TYPE > dlr::computerVision::getGaussianKernel | ( | size_t | rows, | |
| size_t | columns, | |||
| double | rowSigma = -1.0, |
|||
| double | columnSigma = -1.0 | |||
| ) | [inline] |
This function generates and returns a separable Gaussian kernel with the same variance along each axis.
The kernel will be normalized prior to return, so that the sum of its elements is equal to one.
Use this function like this:
Kernel<double> kernel = getGaussianKernel<double>(5, 5);
| rows | This argument specifies how many rows the kernel should have. | |
| columns | This argument specifies how many columns the kernel should have. | |
| rowSigma | This argument specifies the standard deviation of the kernel in the Y direction. If sigma is less than 0.0, then it will be automatically reset to rows / 6.0. | |
| columnSigma | This argument specifies the standard deviation of the kernel in the X direction. If sigma is less than 0.0, then it will be automatically reset columns / 6.0. |
| Kernel< KERNEL_TYPE > dlr::computerVision::getGaussianKernel | ( | double | rowSigma, | |
| double | columnSigma | |||
| ) | [inline] |
This function generates and returns a separable Gaussian kernel of user-specified standard deviation.
The kernel will be sized so that the number of rows is equal to the smallest odd number greater than 6.0 * rowSigma, and the number of columns is equal to the smallest odd number greater than 6.0 * columnSigma. The kernel will be normalized prior to return, so that the sum of its elements is equal to one.
Use this function like this:
Kernel<double> kernel = getGaussianKernel<double>(1.0, 1.0);
| rowSigma | This argument specifies the standard deviation of the kernel in the Y direction. | |
| columnSigma | This argument specifies the standard deviation of the kernel in the X direction. |
| Array1D< unsigned int > dlr::computerVision::getHistogram | ( | const Image< GRAY8 > & | inputImage | ) |
This function computes the histogram of an image.
That is, it counts the number of pixels with each possible value and returns a 1D array of counts.
| inputImage | This argument is the image to be histogrammed. |
Definition at line 26 of file histogramEqualize.cpp.
Referenced by histogramEqualize().
| Image< GRAY8 > dlr::computerVision::histogramEqualize | ( | const Image< GRAY8 > & | inputImage | ) |
This function remaps the pixel values of the input image in such a way that output pixel value increases monotonically with input pixel value, and the histogram of the output image is nearly flat.
| inputImage | This argument is the image to be equalized. |
Definition at line 50 of file histogramEqualize.cpp.
References getHistogram().
| Image< FORMAT > dlr::computerVision::nonMaximumSuppress | ( | const Image< FORMAT > & | inputImage, | |
| const Array2D< Float64 > & | gradX, | |||
| const Array2D< Float64 > & | gradY | |||
| ) | [inline] |
This function zeros any pixels of the input image which are not plausible edges.
Definition at line 53 of file nonMaximumSuppress.h.
Referenced by applyCanny().
| void dlr::computerVision::normalizePointSequence | ( | dlr::numeric::Array2D< double > const & | inputPoints, | |
| dlr::numeric::Array2D< double > & | outputPoints, | |||
| dlr::numeric::Array2D< double > & | transform | |||
| ) |
This function is used internally by eightPointAlgorithm() to translate and scale input points so that their mean lies at the origin and they have isotropic unit variance.
It is exposed here to facilitate testing, and in case it's useful.
| inputPoints | This argument is an Nx3 Array2D<double> instance in which each row` represents one 2D point of the input set using homogeneous coordinates. The last column of this array will normally contain only ones (although this is not required to be true).` | |
| outputPoints | This argument is an Nx3 Array2D<double> instance used to return the transformed points to the calling context. The elements of the third column of this array will almost certainly not be equal to 1.0. | |
| transform | this argument is return the affine transform that takes points from inputPoints to outputPoints via left multiplication. |
Definition at line 30 of file eightPointAlgorithm.cpp.
Referenced by eightPointAlgorithm().
| PixelRGB< typename dlr::common::TypePromoter< Type0, Type1 >::ResultType > dlr::computerVision::operator* | ( | const PixelRGB< Type0 > & | pixel0, | |
| const PixelRGB< Type1 > & | pixel1 | |||
| ) | [inline] |
This operator multiplies the values of the individual color components of its arguments.
| pixel0 | The color component values of this pixel will be multiplied by the color component values of pixel1. | |
| pixel1 | The color component values of pixel0 will be multiplied by the color component values of this pixel. |
Definition at line 462 of file pixelRGB.h.
| PixelRGB< typename dlr::common::TypePromoter< Scalar, Type >::ResultType > dlr::computerVision::operator* | ( | Scalar | scalar, | |
| const PixelRGB< Type > & | pixel1 | |||
| ) | [inline] |
This operator multiplies the color component values of a pixel by a scalar.
| scalar | Each color component will be multiplied by this value. | |
| pixel1 | The color component values of this pixel will be multiplied by the scalar. |
Definition at line 417 of file pixelRGB.h.
| PixelRGB< typename dlr::common::TypePromoter< Type0, Type1 >::ResultType > dlr::computerVision::operator+ | ( | const PixelRGB< Type0 > & | pixel0, | |
| const PixelRGB< Type1 > & | pixel1 | |||
| ) | [inline] |
This operator adds the values of the individual color components of its arguments.
| pixel0 | The color component values of pixel1 will be added to the color component values of this pixel. | |
| pixel1 | The color component values of this pixel will be added to the color component values of pixel0. |
Definition at line 432 of file pixelRGB.h.
| PixelYIQ< TYPE > dlr::computerVision::operator- | ( | const PixelYIQ< TYPE > & | pixel0, | |
| const PixelYIQ< TYPE > & | pixel1 | |||
| ) | [inline] |
This operator subtracts the values of the individual color components of its arguments.
| pixel0 | The color component values of pixel1 will be subtracted from the color component values of this pixel. | |
| pixel1 | The color component values of this pixel will be subtracted from the color component values of pixel1. |
Definition at line 222 of file pixelYIQ.h.
| PixelRGBA< TYPE > dlr::computerVision::operator- | ( | const PixelRGBA< TYPE > & | pixel0, | |
| const PixelRGBA< TYPE > & | pixel1 | |||
| ) | [inline] |
This operator subtracts the values of the individual color components of its arguments.
| pixel0 | The color component values of pixel1 will be subtracted from the color component values of this pixel. | |
| pixel1 | The color component values of this pixel will be subtracted from the color component values of pixel1. |
Definition at line 226 of file pixelRGBA.h.
| PixelRGB< typename dlr::common::TypePromoter< Type0, Type1 >::ResultType > dlr::computerVision::operator- | ( | const PixelRGB< Type0 > & | pixel0, | |
| const PixelRGB< Type1 > & | pixel1 | |||
| ) | [inline] |
This operator subtracts the values of the individual color components of its arguments.
| pixel0 | The color component values of pixel1 will be subtracted from the color component values of this pixel. | |
| pixel1 | The color component values of this pixel will be subtracted from the color component values of pixel0. |
Definition at line 447 of file pixelRGB.h.
| PixelHSV< TYPE > dlr::computerVision::operator- | ( | const PixelHSV< TYPE > & | pixel0, | |
| const PixelHSV< TYPE > & | pixel1 | |||
| ) | [inline] |
This operator subtracts the values of the individual color components of its arguments.
| pixel0 | The color component values of pixel1 will be subtracted from the color component values of this pixel. | |
| pixel1 | The color component values of this pixel will be subtracted from the color component values of pixel1. |
Definition at line 219 of file pixelHSV.h.
| PixelBGRA< TYPE > dlr::computerVision::operator- | ( | const PixelBGRA< TYPE > & | pixel0, | |
| const PixelBGRA< TYPE > & | pixel1 | |||
| ) | [inline] |
This operator subtracts the values of the individual color components of its arguments.
| pixel0 | The color component values of pixel1 will be subtracted from the color component values of this pixel. | |
| pixel1 | The color component values of this pixel will be subtracted from the color component values of pixel1. |
Definition at line 226 of file pixelBGRA.h.
| PixelRGB< typename dlr::common::TypePromoter< Type0, Type1 >::ResultType > dlr::computerVision::operator/ | ( | const PixelRGB< Type0 > & | pixel0, | |
| const PixelRGB< Type1 > & | pixel1 | |||
| ) | [inline] |
This operator divides the values of the individual color components of its arguments.
| pixel0 | The color component values this pixel will be divided by the color component values of pixel1. | |
| pixel1 | The color component values of pixel0 will be divided by the color component values of this pixel. |
Definition at line 477 of file pixelRGB.h.
| std::ostream& dlr::computerVision::operator<< | ( | std::ostream & | stream, | |
| const CameraIntrinsicsPlumbBob & | intrinsics | |||
| ) | [inline] |
This function outputs a text representation of a CameraIntrinsicsPlumbBob instance to a std::ostream.
The output format looks like this:
CameraIntrinsicsPlumbBob {240.0, 320.0, 2000.0, 3000.0, 640, 480, ...}
| stream | This argument is a reference to the the output stream. | |
| intrinsics | This argument is a const reference to the CameraIntrinsicsPlumbBob instance to be output. |
Definition at line 412 of file cameraIntrinsicsPlumbBob.h.
References dlr::computerVision::CameraIntrinsicsPlumbBob::writeToStream().
| std::ostream& dlr::computerVision::operator<< | ( | std::ostream & | stream, | |
| const CameraIntrinsicsPinhole & | intrinsics | |||
| ) | [inline] |
This function outputs a text representation of a CameraIntrinsicsPinhole instance to a std::ostream.
The output format looks like this:
CameraIntrinsicsPinhole {240.0, 320.0, 2000.0, 3000.0, 640, 480}
| stream | This argument is a reference to the the output stream. | |
| intrinsics | This argument is a const reference to the CameraIntrinsicsPinhole instance to be output. |
Definition at line 335 of file cameraIntrinsicsPinhole.h.
References dlr::computerVision::CameraIntrinsicsPinhole::writeToStream().
| bool dlr::computerVision::operator== | ( | const PixelYIQ< TYPE > & | pixel0, | |
| const PixelYIQ< TYPE > & | pixel1 | |||
| ) | [inline] |
This operator returns true if the contents of the two argments are identical, false otherwise.
| pixel0 | This argument is the first pixel value to be compared. | |
| pixel1 | This argument is the second pixel value to be compared. |
Definition at line 235 of file pixelYIQ.h.
| bool dlr::computerVision::operator== | ( | const PixelRGBA< TYPE > & | pixel0, | |
| const PixelRGBA< TYPE > & | pixel1 | |||
| ) | [inline] |
This operator returns true if the contents of the two argments are identical, false otherwise.
| pixel0 | This argument is the first pixel value to be compared. | |
| pixel1 | This argument is the second pixel value to be compared. |
Definition at line 240 of file pixelRGBA.h.
| bool dlr::computerVision::operator== | ( | const PixelRGB< Type > & | pixel0, | |
| const PixelRGB< Type > & | pixel1 | |||
| ) | [inline] |
This operator returns true if the contents of the two argments are identical, false otherwise.
| pixel0 | This argument is the first pixel value to be compared. | |
| pixel1 | This argument is the second pixel value to be compared. |
Definition at line 491 of file pixelRGB.h.
| bool dlr::computerVision::operator== | ( | const PixelHSV< TYPE > & | pixel0, | |
| const PixelHSV< TYPE > & | pixel1 | |||
| ) | [inline] |
This operator returns true if the contents of the two argments are identical, false otherwise.
| pixel0 | This argument is the first pixel value to be compared. | |
| pixel1 | This argument is the second pixel value to be compared. |
Definition at line 232 of file pixelHSV.h.
| bool dlr::computerVision::operator== | ( | const PixelBGRA< TYPE > & | pixel0, | |
| const PixelBGRA< TYPE > & | pixel1 | |||
| ) | [inline] |
This operator returns true if the contents of the two argments are identical, false otherwise.
| pixel0 | This argument is the first pixel value to be compablue. | |
| pixel1 | This argument is the second pixel value to be compablue. |
Definition at line 240 of file pixelBGRA.h.
| std::istream& dlr::computerVision::operator>> | ( | std::istream & | stream, | |
| CameraIntrinsicsPlumbBob & | intrinsics | |||
| ) | [inline] |
This function sets the value of a CameraIntrinsicsPlumbBob instance from a std::istream.
The input format is as described for operator<<(std::ostream&, const CameraIntrinsicsPlumbBob&) above.
| stream | This argument is a reference to the the input stream from which to read. | |
| intrinsics | This argument is a reference to the CameraIntrinsicsPlumbBob which will take the input. |
Definition at line 435 of file cameraIntrinsicsPlumbBob.h.
References dlr::computerVision::CameraIntrinsicsPlumbBob::readFromStream().
| std::istream& dlr::computerVision::operator>> | ( | std::istream & | stream, | |
| CameraIntrinsicsPinhole & | intrinsics | |||
| ) | [inline] |
This function sets the value of a CameraIntrinsicsPinhole instance from a std::istream.
The input format is as described for operator<<(std::ostream&, const CameraIntrinsicsPinhole&) above.
| stream | This argument is a reference to the the input stream from which to read. | |
| intrinsics | This argument is a reference to the CameraIntrinsicsPinhole which will take the input. |
Definition at line 357 of file cameraIntrinsicsPinhole.h.
References dlr::computerVision::CameraIntrinsicsPinhole::readFromStream().
| Image<GRAY8> dlr::computerVision::readPNG8 | ( | const std::string & | fileName, | |
| std::string & | commentString | |||
| ) |
WARNING: This routine may not stick around for long.
| fileName | This argument ... | |
| commentString | This argument ... |
| Transform3D dlr::computerVision::registerPoints3D | ( | InIter0 | fromPointsBegin, | |
| InIter0 | fromPointsEnd, | |||
| InIter1 | toPointsBegin, | |||
| OutIter0 | selectedFlagsBegin, | |||
| double | inclusion, | |||
| double | maximumResidual = -1.0, |
|||
| size_t | maximumIterations = 5 | |||
| ) | [inline] |
This function calls the four-argument form of registerPoints3D() repeatedly while trying to identify and ignore outliers.
Iteration terminates when a call to the four-argument form of registerPoints3D() does not change the selected outlier list. Calling this function with argument inclusion set to 1.0 and argument maximumResidual less than zero is just the same as calling the four-argument form of of registerPoints3D with flagsBegin pointing to a sequence of all true.
| fromPointsBegin | This iterator, along with fromPointsEnd, defines one of the two sets of points to be registered. The returned Transform3D instance will take points in the range specified by this iterator pair and transform them so that they match the corresponding elements of the "to" range as closely as possible in the least-squares sense. | |
| fromPointsEnd | See the documentation for argument fromPointsBegin. | |
| toPointsBegin | This argument defines the beginning of one of the two sets of points to be registered. The returned Transform3D instance will take points in the range specified by arguments fromPointsBegin and fromPointsEnd, and transform them so that they match as closely as possible (in the least squares sense) the corresponding elements of the range starting from toPointsBegin and extending (fromPointsEnd - fromPointsBegin) elements. possible in the least-squares sense. | |
| flagsBegin | This output iterator will be used to return a sequence of bools indicating which points were used in the registration. For points which were included in the registration, the corresponding bool will be true. | |
| inclusion | This argument specifies the proportion of the dataset which is expected to be inliers. Setting this value to 1.0 or greater indicates that all of the points should be included in the registration, unless their inclusion is countermanded by argument maximumResidual. Setting this value less than 0.0 has the same effect as settint it to 1.0. To clarify(?): at each call to the three-argument form of registerPoints3D(), only floor(inclusion * (int)(fromPointsEnd - fromPointsBegin)) pairs of points will be used, and the points used will be those with the smallest residual prior to the call to the three-argument form of registerPoints3D(). | |
| maximumResidual | This argument specifies the largest expected residual between corresponding points after the registration. Pairs of points which differ by more than this amount will be assumed to be outliers and ignored during the next registration. Setting this argument less than zero indicates that all pairs of points should be included in the registration, unless some points are countermanded by argument inclusion. | |
| maximumIterations | This argument how many iterations are permissible. The loop (register -> compute outliers -> repeat) will terminate after this many iterations even if the set of points chosen as outliers is still changing. |
Definition at line 351 of file registerPoints3D.h.
References registerPoints3D().
| Transform3D dlr::computerVision::registerPoints3D | ( | InIter0 | fromPointsBegin, | |
| InIter0 | fromPointsEnd, | |||
| InIter1 | toPointsBegin, | |||
| InIter2 | selectedFlagsBegin | |||
| ) | [inline] |
This function works just like the three-argument form of registerPoints3D(), except that only selected points are considered in the registration.
| fromPointsBegin | This iterator, along with fromPointsEnd, defines one of the two sets of points to be registered. The returned Transform3D instance will take points in the range specified by this iterator pair and transform them so that they match the corresponding elements of the "to" range as closely as possible in the least-squares sense. | |
| fromPointsEnd | See the documentation for argument fromPointsBegin. | |
| toPointsBegin | This argument defines the beginning of one of the two sets of points to be registered. The returned Transform3D instance will take points in the range specified by arguments fromPointsBegin and fromPointsEnd, and transform them so that they match as closely as possible (in the least squares sense) the corresponding elements of the range starting from toPointsBegin and extending (fromPointsEnd - fromPointsBegin) elements. | |
| flagsBegin | This argument defines the beginning of a sequence of boolean values indicating which points should be included in the registration. That is, flagsBegin is an iterator which must dereference to a bool, and the sequence from flagsBegin to flagsBegin + (fromPointsEnd - fromPointsBegin) must be valid. Points will be included in the registration iff the corresponding bool is true. |
Definition at line 238 of file registerPoints3D.h.
| Transform3D dlr::computerVision::registerPoints3D | ( | InIter0 | fromPointsBegin, | |
| InIter0 | fromPointsEnd, | |||
| InIter1 | toPointsBegin | |||
| ) | [inline] |
Using Horn's method, from "Closed-form solution of absolute orientation using unit quaternions", J.
Opt. Soc. Am., Vol. 4(4), April, 1987. Find the Rigid body tranform which takes one set of points and most nearly registers them with a second set.
| fromPointsBegin | This iterator, along with fromPointsEnd, defines one of the two sets of points to be registered. The returned Transform3D instance will take points in the range specified by this iterator pair and transform them so that they match the corresponding elements of the "to" range as closely as possible in the least-squares sense. | |
| fromPointsEnd | See the documentation for argument fromPointsBegin. | |
| toPointsBegin | This argument defines the beginning of one of the two sets of points to be registered. The returned Transform3D instance will take points in the range specified by arguments fromPointsBegin and fromPointsEnd, and transform them so that they match as closely as possible (in the least squares sense) the corresponding elements of the range starting from toPointsBegin and extending (fromPointsEnd - fromPointsBegin) elements. possible in the least-squares sense. |
Definition at line 227 of file registerPoints3D.h.
Referenced by registerPoints3D(), and threePointAlgorithmRobust().
| void dlr::computerVision::stereoRectify | ( | CameraIntrinsicsPinhole const & | intrinsics0, | |
| CameraIntrinsicsPinhole const & | intrinsics1, | |||
| numeric::Transform3D const & | camera0Tworld, | |||
| numeric::Transform3D const & | camera1Tworld, | |||
| CameraIntrinsicsPinhole & | rectifiedIntrinsics0, | |||
| CameraIntrinsicsPinhole & | rectifiedIntrinsics1, | |||
| numeric::Transform3D & | rcamera0Tworld, | |||
| numeric::Transform3D & | rcamera1Tworld, | |||
| numeric::Transform2D & | image0Trimage0, | |||
| numeric::Transform2D & | image1Trimage1 | |||
| ) |
A.
Fusiello, E. Trucco, and A. Verri. A compact algorithm for rectification of stereo pairs. Machine Vision and Applications, 2000.
... Our convention is that, from the perspective of rectified camera0, rectified camera1 is located to the right (in the positive X direction).
Warning: this routine assumes, but does not check, that the camera?Tworld arguments are euclidean rigid body transformations. That is, the routine assumes that the 3x3 upper left block of each camera?Tworld argument is orthonormal, and the last row is [0, 0, 0, 1].
| intrinsics0 | This argument | |
| intrinsics1 | This argument | |
| camera0Tworld | This argument | |
| camera1Tworld | This argument | |
| rectifiedIntrinsics0 | This argument | |
| rectifiedIntrinsics1 | This argument | |
| image0Trimage0 | This argument | |
| image1Trimage1 | This argument | |
| rcamera0Tworld | This argument | |
| rcamera1Tworld | This argument |
Definition at line 82 of file stereoRectify.cpp.
References dlr::computerVision::CameraIntrinsicsPinhole::getCenterU(), dlr::computerVision::CameraIntrinsicsPinhole::getCenterV(), dlr::computerVision::CameraIntrinsicsPinhole::getFocalLength(), dlr::computerVision::CameraIntrinsicsPinhole::getNumPixelsX(), dlr::computerVision::CameraIntrinsicsPinhole::getNumPixelsY(), dlr::computerVision::CameraIntrinsicsPinhole::getPixelSizeX(), and dlr::computerVision::CameraIntrinsicsPinhole::getPixelSizeY().
| Image< Format > dlr::computerVision::subsample | ( | const Image< Format > & | inputImage, | |
| size_t | rowStep = 2, |
|||
| size_t | columnStep = 2 | |||
| ) | [inline] |
This function subsamples its input to create a new, smaller image.
The number of rows in the resulting image is the largest integer, r, such that (rowStep * (r - 1) + 1) <= inputImage.rows(). The number of columns in the resulting image is the largest integer, c, such that (columnStep * (c - 1) + 1) <= inputImage.columns(). The pixel values in the resulting image are the values at the intersection of every rowStep-th row and columnStep-th column of inputImage, starting with the value at (row, column) = (0, 0), which is always copied directly in to pixel (0, 0) of the result image. In other words, element (0, 0) of the resulting image is equal to element (0, 0) of inputImage, element (0, 1) of the resulting image is equal to element (0, columnStep) of inputImage, element (0, 2) of the resulting image is equal to element (0, 2 * columnStep) of inputImage, element (2, 4) of the resulting image is equal to element (2 * rowStep, 4 * columnStep) in inputImage.
| inputImage | This argument is the image to be subsampled. | |
| rowStep | This argument controls which rows of inputImage contribute to the result. | |
| columnStep | This argument controls which columns of inputImage contribute to the result. |
Definition at line 657 of file utilities.h.
| Image< OutputFormat > dlr::computerVision::supersample | ( | const Image< InputFormat > & | inputImage | ) | [inline] |
This function interpolates its input to create a new, larger image.
The number of rows in the resulting image is one fewer than twice the number of rows in the input image. The number of columns in the resulting image is one fewer than twice the number of columns in the input image. Where output pixels overlap input pixels, they are copied directly from the input image. Where output pixels fall in between input pixels, they are constructed by bilinear interpolation. The pixel at (0, 0) in the output image falls directly on top of pixel (0, 0) in the input image. (2, 2) in the output image falls on top of (1, 1) in the input image, and so forth.
Template argument IntermediateFormat specifies the type of pixel that should be used during calculation of the interpolated values. It should have sufficient precision to contain the sum of four input pixels.
| inputImage | This argument is the image to be interpolated. |
Definition at line 700 of file utilities.h.
| unsigned int dlr::computerVision::threePointAlgorithm | ( | dlr::numeric::Vector3D const & | w0, | |
| dlr::numeric::Vector3D const & | w1, | |||
| dlr::numeric::Vector3D const & | w2, | |||
| dlr::numeric::Vector2D const & | u0, | |||
| dlr::numeric::Vector2D const & | u1, | |||
| dlr::numeric::Vector2D const & | u2, | |||
| CameraIntrinsicsPinhole const & | intrinsics, | |||
| IterType | p0OutputIter, | |||
| IterType | p1OutputIter, | |||
| IterType | p2OutputIter, | |||
| double | epsilon = 1.0E-8 | |||
| ) | [inline] |
This function implements the "three point perspective pose estimation algorithm" of Grunert[1][2] for recovering the camera-frame coordinates of the corners of a triangle of known size, given the projections of those corners in the camera image.
We follow the derivation in [2]. That is, given w_0, w_1, and w_2, all 3D positions in world coordinates, u_0, u_1, u_2, the projections of those coordinates in the image, and pinhole camera parameters, the algorithm recovers p_0, p_1, and p_2, the positions of those points in camera coordinates.
[1] J. A. Grunert, "Das Pothenotische Problem in Erweiterter Gestalt Nebst Uber Seine Anwendungen in der Geodisie," Grunerts Archiv fur Mathematik und Physik, Band 1, 1841, pp. 238-248.
[2] R. M. Haralick, C. Lee, K. Ottenberg, and M. Nolle, "Review and Analysis of Solutions of the Three Point Perspective Pose Estimation Problem," International Journal of Computer Vision, 13, 3, 331-356 (1994).
| w0 | This argument is the first of the three 3D points in world coordinates. | |
| w1 | This argument is the second of the three 3D points in world coordinates. | |
| w2 | This argument is the third of the three 3D points in world coordinates. | |
| u0 | This argument is the image location of the projection of world point w0. | |
| u1 | This argument is the image location of the projection of world point w1. | |
| u2 | This argument is the image location of the projection of world point w2. | |
| intrinsics | This argument describes the intrinsic calibration of the camera that generated the image from which u0, u1, u2 were drawn. | |
| p0OutputIter | This argument is used to return estimates of the point in camera coordinates corresponding to w0. It is an iterator pointing to the beginning of an output sequence, and must be able to accept at least four values. | |
| p1OutputIter | This argument is used to return estimates of the point in camera coordinates corresponding to w1. It is an iterator pointing to the beginning of an output sequence, and must be able to accept at least four values. | |
| p2OutputIter | This argument is used to return estimates of the point in camera coordinates corresponding to w2. It is an iterator pointing to the beginning of an output sequence, and must be able to accept at least four values. | |
| epsilon | This argument sets some internal tolerances of the algorithm, and should be left at its default value for now. |
Definition at line 199 of file threePointAlgorithm.h.
References dlr::computerVision::CameraIntrinsicsPinhole::reverseProject().
Referenced by threePointAlgorithmRobust().
| dlr::numeric::Transform3D dlr::computerVision::threePointAlgorithmRobust | ( | InIter3D | worldPointsBegin, | |
| InIter3D | worldPointsEnd, | |||
| InIter2D | imagePointsBegin, | |||
| CameraIntrinsicsPinhole const & | intrinsics, | |||
| size_t | iterations, | |||
| double | inlierProportion, | |||
| double & | score, | |||
| dlr::random::PseudoRandom & | pRandom = dlr::random::PseudoRandom() | |||
| ) | [inline] |
This function implements the "robust" version of threePointAlgorithm().
Multiple solutions for camera pose are computed using randomly selected sets of three input points, an error value is computed (based on all of the input points) for each of the potential solutions, and the solution having the best error value is retained.
| worldPointsBegin | This argument is the beginning (in the STL sense) of a sequence of 3D points expressed in world coordinates, and represented as dlr::numeric::Vector3D instances. | |
| worldPointsEnd | This argument is the end (in the STL sense) of the sequence begun by worldPointsBegin. | |
| imagePointsBegin | This argument is the beginning (in the STL sense) of a sequence of 2D points corresponding to the elements of [worlPointsBegin, worldPointsEnd], and expressed in image coordinates. | |
| intrinsics | This argument describes the intrinsic calibration of the camera that generated the input points. | |
| iterations | This argument specifies how many random samples of three input points should be processed to generate solution hypotheses. | |
| inlierProportion | This argument specifies what proportion of the input points are expected to be "inliers" and conform to the correct solution (once we find it). It is used to tune the error value computation. | |
| score | This argument is a projection residual indicating the goodness of the final solution. | |
| pRandom | This argument is a pseudorandom number generator used by the algorithm to select sets of three input points. |
Definition at line 327 of file threePointAlgorithm.h.
References dlr::computerVision::CameraIntrinsicsPinhole::project(), registerPoints3D(), and threePointAlgorithm().
Referenced by fivePointAlgorithmRobust().
| Array2D< Type > dlr::computerVision::toArray | ( | const Image< FORMAT > & | inputImage | ) | [inline] |
This function creates a new array and copies into it the pixel data from the input image.
If the image format is one which has multiple interleaved color components, such as RGB8, then the returned array will have individual elements for each component of each pixel. For example, if the first row of an HSV8 image is [{h0, s0, v0}, {h1, s1, v1}, {h2, s2, v2}, ... ], then the first row of the array returned by toArray will be [h0, s0, v0, h1, s1, v1, h2, s2, v2, ...].
| inputImage | This argument is the image to be copied. |
Definition at line 787 of file utilities.h.
References dissociateColorComponents().
| void dlr::computerVision::writePNG8 | ( | const std::string & | fileName, | |
| const Image< GRAY8 > & | outputImage, | |||
| const std::string & | comment = "" | |||
| ) |
WARNING: This routine may not stick around for long.
| fileName | This argument ... | |
| outputImage | This argument ... | |
| comment | This argument ... |
1.5.8