OpenCV  5.0.0-pre
Open Source Computer Vision
Loading...
Searching...
No Matches
Classes | Enumerations | Functions
RGB-Depth Processing

Detailed Description

ICP point-to-plane odometry algorithm

Classes

class  cv::linemod::ColorGradient
 Modality that computes quantized gradient orientations from a color image. More...
 
class  cv::linemod::DepthNormal
 Modality that computes quantized surface normals from a dense depth map. More...
 
class  cv::linemod::Detector
 Object detector using the LINE template matching algorithm with any set of modalities. More...
 
struct  cv::linemod::Feature
 Discriminant feature described by its location and label. More...
 
struct  cv::linemod::Match
 Represents a successful template match. More...
 
class  cv::linemod::Modality
 Interface for modalities that plug into the LINE template matching representation. More...
 
class  cv::linemod::QuantizedPyramid
 Represents a modality operating over an image pyramid. More...
 
class  cv::RgbdNormals
 
struct  cv::linemod::Template
 

Enumerations

enum  cv::RgbdPlaneMethod { cv::RGBD_PLANE_METHOD_DEFAULT }
 

Functions

 cv::linemod::QuantizedPyramid::Candidate::Candidate (int x, int y, int label, float score)
 
 cv::linemod::Feature::Feature (int x, int y, int label)
 
 cv::linemod::Match::Match (int x, int y, float similarity, const String &class_id, int template_id)
 
void cv::linemod::colormap (const Mat &quantized, Mat &dst)
 Debug function to colormap a quantized image for viewing.
 
void cv::depthTo3d (InputArray depth, InputArray K, OutputArray points3d, InputArray mask=noArray())
 
void cv::depthTo3dSparse (InputArray depth, InputArray in_K, InputArray in_points, OutputArray points3d)
 
void cv::linemod::drawFeatures (InputOutputArray img, const std::vector< Template > &templates, const Point2i &tl, int size=10)
 Debug function to draw linemod features.
 
void cv::findPlanes (InputArray points3d, InputArray normals, OutputArray mask, OutputArray plane_coefficients, int block_size=40, int min_size=40 *40, double threshold=0.01, double sensor_error_a=0, double sensor_error_b=0, double sensor_error_c=0, RgbdPlaneMethod method=RGBD_PLANE_METHOD_DEFAULT)
 
Ptr< linemod::Detectorcv::linemod::getDefaultLINE ()
 Factory function for detector using LINE algorithm with color gradients.
 
Ptr< linemod::Detectorcv::linemod::getDefaultLINEMOD ()
 Factory function for detector using LINE-MOD algorithm with color gradients and depth normals.
 
void cv::registerDepth (InputArray unregisteredCameraMatrix, InputArray registeredCameraMatrix, InputArray registeredDistCoeffs, InputArray Rt, InputArray unregisteredDepth, const Size &outputImagePlaneSize, OutputArray registeredDepth, bool depthDilation=false)
 
void cv::rescaleDepth (InputArray in, int type, OutputArray out, double depth_factor=1000.0)
 
void cv::warpFrame (InputArray depth, InputArray image, InputArray mask, InputArray Rt, InputArray cameraMatrix, OutputArray warpedDepth=noArray(), OutputArray warpedImage=noArray(), OutputArray warpedMask=noArray())
 

Enumeration Type Documentation

◆ RgbdPlaneMethod

#include <opencv2/3d/depth.hpp>

Enumerator
RGBD_PLANE_METHOD_DEFAULT 
Python: cv.RGBD_PLANE_METHOD_DEFAULT

Function Documentation

◆ Candidate()

cv::linemod::QuantizedPyramid::Candidate::Candidate ( int  x,
int  y,
int  label,
float  score 
)
inline

◆ Feature()

cv::linemod::Feature::Feature ( int  x,
int  y,
int  label 
)
inline

◆ Match()

cv::linemod::Match::Match ( int  x,
int  y,
float  similarity,
const String class_id,
int  template_id 
)
inline

◆ colormap()

void cv::linemod::colormap ( const Mat quantized,
Mat dst 
)
Python:
cv.linemod.colormap(quantized[, dst]) -> dst

#include <opencv2/rgbd/linemod.hpp>

Debug function to colormap a quantized image for viewing.

◆ depthTo3d()

void cv::depthTo3d ( InputArray  depth,
InputArray  K,
OutputArray  points3d,
InputArray  mask = noArray() 
)
Python:
cv.depthTo3d(depth, K[, points3d[, mask]]) -> points3d

#include <opencv2/3d/depth.hpp>

Converts a depth image to 3d points. If the mask is empty then the resulting array has the same dimensions as depth, otherwise it is 1d vector containing mask-enabled values only. The coordinate system is x pointing left, y down and z away from the camera

Parameters
depththe depth image (if given as short int CV_U, it is assumed to be the depth in millimeters (as done with the Microsoft Kinect), otherwise, if given as CV_32F or CV_64F, it is assumed in meters)
KThe calibration matrix
points3dthe resulting 3d points (point is represented by 4 channels value [x, y, z, 0]). They are of the same depth as depth if it is CV_32F or CV_64F, and the depth of K if depth is of depth CV_16U or CV_16S
maskthe mask of the points to consider (can be empty)

◆ depthTo3dSparse()

void cv::depthTo3dSparse ( InputArray  depth,
InputArray  in_K,
InputArray  in_points,
OutputArray  points3d 
)
Python:
cv.depthTo3dSparse(depth, in_K, in_points[, points3d]) -> points3d

#include <opencv2/3d/depth.hpp>

Parameters
depththe depth image
in_K
in_pointsthe list of xy coordinates
points3dthe resulting 3d points (point is represented by 4 chanels value [x, y, z, 0])

◆ drawFeatures()

void cv::linemod::drawFeatures ( InputOutputArray  img,
const std::vector< Template > &  templates,
const Point2i tl,
int  size = 10 
)
Python:
cv.linemod.drawFeatures(img, templates, tl[, size]) -> img

#include <opencv2/rgbd/linemod.hpp>

Debug function to draw linemod features.

Parameters
img
templatessee Detector::addTemplate
tltemplate bbox top-left offset see Detector::addTemplate
sizemarker size see cv::drawMarker

◆ findPlanes()

void cv::findPlanes ( InputArray  points3d,
InputArray  normals,
OutputArray  mask,
OutputArray  plane_coefficients,
int  block_size = 40,
int  min_size = 40 *40,
double  threshold = 0.01,
double  sensor_error_a = 0,
double  sensor_error_b = 0,
double  sensor_error_c = 0,
RgbdPlaneMethod  method = RGBD_PLANE_METHOD_DEFAULT 
)
Python:
cv.findPlanes(points3d, normals[, mask[, plane_coefficients[, block_size[, min_size[, threshold[, sensor_error_a[, sensor_error_b[, sensor_error_c[, method]]]]]]]]]) -> mask, plane_coefficients

#include <opencv2/3d/depth.hpp>

Find the planes in a depth image

Parameters
points3dthe 3d points organized like the depth image: rows x cols with 3 channels
normalsthe normals for every point in the depth image; optional, can be empty
maskAn image where each pixel is labeled with the plane it belongs to and 255 if it does not belong to any plane
plane_coefficientsthe coefficients of the corresponding planes (a,b,c,d) such that ax+by+cz+d=0, norm(a,b,c)=1 and c < 0 (so that the normal points towards the camera)
block_sizeThe size of the blocks to look at for a stable MSE
min_sizeThe minimum size of a cluster to be considered a plane
thresholdThe maximum distance of a point from a plane to belong to it (in meters)
sensor_error_acoefficient of the sensor error. 0 by default, use 0.0075 for a Kinect
sensor_error_bcoefficient of the sensor error. 0 by default
sensor_error_ccoefficient of the sensor error. 0 by default
methodThe method to use to compute the planes.

◆ getDefaultLINE()

Ptr< linemod::Detector > cv::linemod::getDefaultLINE ( )
Python:
cv.linemod.getDefaultLINE() -> retval

#include <opencv2/rgbd/linemod.hpp>

Factory function for detector using LINE algorithm with color gradients.

Default parameter settings suitable for VGA images.

◆ getDefaultLINEMOD()

Ptr< linemod::Detector > cv::linemod::getDefaultLINEMOD ( )
Python:
cv.linemod.getDefaultLINEMOD() -> retval

#include <opencv2/rgbd/linemod.hpp>

Factory function for detector using LINE-MOD algorithm with color gradients and depth normals.

Default parameter settings suitable for VGA images.

◆ registerDepth()

void cv::registerDepth ( InputArray  unregisteredCameraMatrix,
InputArray  registeredCameraMatrix,
InputArray  registeredDistCoeffs,
InputArray  Rt,
InputArray  unregisteredDepth,
const Size outputImagePlaneSize,
OutputArray  registeredDepth,
bool  depthDilation = false 
)
Python:
cv.registerDepth(unregisteredCameraMatrix, registeredCameraMatrix, registeredDistCoeffs, Rt, unregisteredDepth, outputImagePlaneSize[, registeredDepth[, depthDilation]]) -> registeredDepth

#include <opencv2/3d/depth.hpp>

Registers depth data to an external camera Registration is performed by creating a depth cloud, transforming the cloud by the rigid body transformation between the cameras, and then projecting the transformed points into the RGB camera.

uv_rgb = K_rgb * [R | t] * z * inv(K_ir) * uv_ir

Currently does not check for negative depth values.

Parameters
unregisteredCameraMatrixthe camera matrix of the depth camera
registeredCameraMatrixthe camera matrix of the external camera
registeredDistCoeffsthe distortion coefficients of the external camera
Rtthe rigid body transform between the cameras. Transforms points from depth camera frame to external camera frame.
unregisteredDepththe input depth data
outputImagePlaneSizethe image plane dimensions of the external camera (width, height)
registeredDepththe result of transforming the depth into the external camera
depthDilationwhether or not the depth is dilated to avoid holes and occlusion errors (optional)

◆ rescaleDepth()

void cv::rescaleDepth ( InputArray  in,
int  type,
OutputArray  out,
double  depth_factor = 1000.0 
)
Python:
cv.rescaleDepth(in_, type[, out[, depth_factor]]) -> out

#include <opencv2/3d/depth.hpp>

If the input image is of type CV_16UC1 (like the Kinect one), the image is converted to floats, divided by depth_factor to get a depth in meters, and the values 0 are converted to std::numeric_limits<float>::quiet_NaN() Otherwise, the image is simply converted to floats

Parameters
inthe depth image (if given as short int CV_U, it is assumed to be the depth in millimeters (as done with the Microsoft Kinect), it is assumed in meters)
typethe desired output depth (CV_32F or CV_64F)
outThe rescaled float depth image
depth_factor(optional) factor by which depth is converted to distance (by default = 1000.0 for Kinect sensor)

◆ warpFrame()

void cv::warpFrame ( InputArray  depth,
InputArray  image,
InputArray  mask,
InputArray  Rt,
InputArray  cameraMatrix,
OutputArray  warpedDepth = noArray(),
OutputArray  warpedImage = noArray(),
OutputArray  warpedMask = noArray() 
)
Python:
cv.warpFrame(depth, image, mask, Rt, cameraMatrix[, warpedDepth[, warpedImage[, warpedMask]]]) -> warpedDepth, warpedImage, warpedMask

#include <opencv2/3d/depth.hpp>

Warps depth or RGB-D image by reprojecting it in 3d, applying Rt transformation and then projecting it back onto the image plane. This function can be used to visualize the results of the Odometry algorithm.

Parameters
depthDepth data, should be 1-channel CV_16U, CV_16S, CV_32F or CV_64F
imageRGB image (optional), should be 1-, 3- or 4-channel CV_8U
maskMask of used pixels (optional), should be CV_8UC1
RtRotation+translation matrix (3x4 or 4x4) to be applied to depth points
cameraMatrixCamera intrinsics matrix (3x3)
warpedDepthThe warped depth data (optional)
warpedImageThe warped RGB image (optional)
warpedMaskThe mask of valid pixels in warped image (optional)