Public Member Functions | Static Public Member Functions | Public Attributes | Private Member Functions
but_plane_detector::Normals Class Reference

#include <normals.h>

List of all members.

Public Member Functions

cv::Vec4f getNormal (int i, int j, int step, float depthThreshold)
cv::Vec4f getNormalLSQ (int i, int j, int step, float depthThreshold)
cv::Vec4f getNormalLSQAround (int i, int j, int step, float depthThreshold)
cv::Vec4f getNormalLTS (int i, int j, int step, float depthThreshold, float outlierThreshold, int maxIter)
cv::Vec4f getNormalLTSAround (int i, int j, int step, float depthThreshold, float outlierThreshold, int maxIter)
 Normals (cv::Mat &points, const sensor_msgs::CameraInfoConstPtr &cam_info, int normalType=NormalType::PCL, int neighborhood=4, float threshold=0.2, float outlierThreshold=0.02, int iter=3)
 Normals (pcl::PointCloud< pcl::PointXYZ > &pointcloud, int normalType=NormalType::PCL, int neighborhood=4, float threshold=0.2, float outlierThreshold=0.02, int iter=3)

Static Public Member Functions

static Plane< float > LeastSquaresPlane (std::vector< cv::Vec3f > &points)

Public Attributes

sensor_msgs::CameraInfoConstPtr m_cam_info
cv::Mat m_planes
cv::Mat m_points
int m_quantbins
std::vector< cv::Vec3f > m_quantVectors

Private Member Functions

unsigned int getQuantVector (std::vector< cv::Vec3f > &vec, cv::Vec3f &vector)
void initQuantVectors (int n_bins, std::vector< cv::Vec3f > &vec)
void nextStep (int step, int &x, int &y, int &plusX, int &plusY)

Detailed Description

Class encapsulating normal computation from depth image

Definition at line 300 of file normals.h.


Constructor & Destructor Documentation

but_plane_detector::Normals::Normals ( cv::Mat &  points,
const sensor_msgs::CameraInfoConstPtr &  cam_info,
int  normalType = NormalType::PCL,
int  neighborhood = 4,
float  threshold = 0.2,
float  outlierThreshold = 0.02,
int  iter = 3 
)

Constructor - computes real point positions (in scene coordinates) and normals and initiates all variables

Parameters:
pointsInput CV_16UC depth matrix (raw input from kinect)
cam_infoCamera info message (ROS)
normalTypeType of normal computation method (NormalType enum)
See also:
NormalType()
Parameters:
neighborhoodNeighborhood from which normals are computed
thresholdThreshold for depth difference outlier marking (if depth of neighbor is greater than this threshold, point is skipped)
outlierThresholdOutlier threshold for least trimmed squares regression (max error between point depth and proposed plane)
iterMaximum RANSAC iterations
but_plane_detector::Normals::Normals ( pcl::PointCloud< pcl::PointXYZ > &  pointcloud,
int  normalType = NormalType::PCL,
int  neighborhood = 4,
float  threshold = 0.2,
float  outlierThreshold = 0.02,
int  iter = 3 
)

Constructor - computes real point positions (in scene coordinates) and normals and initiates all variables

Parameters:
pointcloudPoint cloud
thresholdThreshold for depth difference outlier marking (if depth of neighbor is greater than this threshold, point is skipped)
neighborhoodNeighborhood from which normals are computed

Definition at line 282 of file normals.cpp.


Member Function Documentation

cv::Vec4f but_plane_detector::Normals::getNormal ( int  i,
int  j,
int  step,
float  depthThreshold 
)

Function computes normal for point (i, j) using direct computation (mean of surrounding triangles)

Parameters:
irow index
jcolumn index
stepNeighborhood to compute with
depthThresholdThreshold for depth difference outlier marking (if depth of neighbor is greater than this threshold, point is skipped)

Definition at line 444 of file normals.cpp.

cv::Vec4f but_plane_detector::Normals::getNormalLSQ ( int  i,
int  j,
int  step,
float  depthThreshold 
)

Function computes normal for point (i, j) using least squares regression

Parameters:
irow index
jcolumn index
stepNeighborhood to compute with
depthThresholdThreshold for depth difference outlier marking (if depth of neighbor is greater than this threshold, point is skipped)

Definition at line 535 of file normals.cpp.

cv::Vec4f but_plane_detector::Normals::getNormalLSQAround ( int  i,
int  j,
int  step,
float  depthThreshold 
)

Function computes normal for point (i, j) using least squares regression with using only outer neighborhood ring

Parameters:
irow index
jcolumn index
stepNeighborhood to compute with
depthThresholdThreshold for depth difference outlier marking (if depth of neighbor is greater than this threshold, point is skipped)

Definition at line 578 of file normals.cpp.

cv::Vec4f but_plane_detector::Normals::getNormalLTS ( int  i,
int  j,
int  step,
float  depthThreshold,
float  outlierThreshold,
int  maxIter 
)

Function computes normal for point (i, j) using least trimmed squares regression

Parameters:
irow index
jcolumn index
stepNeighborhood to compute with
depthThresholdThreshold for depth difference outlier marking (if depth of neighbor is greater than this threshold, point is skipped)
outlierThresholdThreshold for marking outliers in RANSAC (maximum difference from proposed plane)
maxIterMaximum RANSAC iterations

Definition at line 629 of file normals.cpp.

cv::Vec4f but_plane_detector::Normals::getNormalLTSAround ( int  i,
int  j,
int  step,
float  depthThreshold,
float  outlierThreshold,
int  maxIter 
)

Function computes normal for point (i, j) using least trimmed squares regression with using only outer neighborhood ring

Parameters:
irow index
jcolumn index
stepNeighborhood to compute with
depthThresholdThreshold for depth difference outlier marking (if depth of neighbor is greater than this threshold, point is skipped)
outlierThresholdThreshold for marking outliers in RANSAC (maximum difference from proposed plane)
maxIterMaximum RANSAC iterations

Definition at line 699 of file normals.cpp.

unsigned int but_plane_detector::Normals::getQuantVector ( std::vector< cv::Vec3f > &  vec,
cv::Vec3f &  vector 
) [private]

Helper function which returns bin index for given vector (not used, TODO)

Parameters:
vecVector of computed quantization vectors
vectorVector whos bin we are computing

Definition at line 905 of file normals.cpp.

void but_plane_detector::Normals::initQuantVectors ( int  n_bins,
std::vector< cv::Vec3f > &  vec 
) [private]

Helper function which initializes quantization vectors (not used, TODO)

Parameters:
n_binsNumber of quantization bins
vecVector of computed quantization vectors

Definition at line 885 of file normals.cpp.

Plane< float > but_plane_detector::Normals::LeastSquaresPlane ( std::vector< cv::Vec3f > &  points) [static]

Function computes plane using least squares regression from given point set

Parameters:
pointsVector of Vec3f points
Returns:
Plane object
See also:
Plane()

Definition at line 777 of file normals.cpp.

void but_plane_detector::Normals::nextStep ( int  step,
int &  x,
int &  y,
int &  plusX,
int &  plusY 
) [private]

Helper function for "Around" functions - sets next point on outer ring

Parameters:
stepMaximum distance from center (neighborhood)
xCurrent x offset
yCurrent y offset
plusXNext x shift
plusYNext y shift

Definition at line 854 of file normals.cpp.


Member Data Documentation

sensor_msgs::CameraInfoConstPtr but_plane_detector::Normals::m_cam_info

Saved camera info (ROS)

Definition at line 397 of file normals.h.

Computed plane equation approximations (so the normals also) for each point

Definition at line 392 of file normals.h.

Computed real points - scene coordinates (in meters)

Definition at line 387 of file normals.h.

Helper if vector quantization is on - not used in this version (TODO)

Definition at line 407 of file normals.h.

Helper if vector quantization is on - not used in this version (TODO)

Definition at line 402 of file normals.h.


The documentation for this class was generated from the following files:


srs_env_model_percp
Author(s): Rostislav Hulik (ihulik@fit.vutbr.cz), Tomas Hodan, Michal Spanel (spanel@fit.vutbr.cz)
autogenerated on Mon Oct 6 2014 08:07:23