Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes
pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT > Class Template Reference

HarrisKeypoint2D detects Harris corners family points. More...

#include <harris_2d.h>

Inheritance diagram for pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef boost::shared_ptr
< const HarrisKeypoint2D
< PointInT, PointOutT,
IntensityT > > 
ConstPtr
typedef Keypoint< PointInT,
PointOutT >::KdTree 
KdTree
typedef Keypoint< PointInT,
PointOutT >::PointCloudIn 
PointCloudIn
typedef PointCloudIn::ConstPtr PointCloudInConstPtr
typedef Keypoint< PointInT,
PointOutT >::PointCloudOut 
PointCloudOut
typedef boost::shared_ptr
< HarrisKeypoint2D< PointInT,
PointOutT, IntensityT > > 
Ptr
enum  ResponseMethod { HARRIS = 1, NOBLE, LOWE, TOMASI }

Public Member Functions

 HarrisKeypoint2D (ResponseMethod method=HARRIS, int window_width=3, int window_height=3, int min_distance=5, float threshold=0.0)
 Constructor.
void setMethod (ResponseMethod type)
 set the method of the response to be calculated.
void setMinimalDistance (int min_distance)
 Set minimal distance between candidate keypoints.
void setNonMaxSupression (bool=false)
 whether non maxima suppression should be applied or the response for each point should be returned
void setNumberOfThreads (unsigned int nr_threads=0)
 Initialize the scheduler and set the number of threads to use.
void setRefine (bool do_refine)
 whether the detected key points should be refined or not. If turned of, the key points are a subset of the original point cloud. Otherwise the key points may be arbitrary.
void setSkippedPixels (int skipped_pixels)
 Set number of pixels to skip.
void setThreshold (float threshold)
 set the threshold value for detecting corners. This is only evaluated if non maxima suppression is turned on.
void setWindowHeight (int window_height)
 Set window height.
void setWindowWidth (int window_width)
 Set window width.

Protected Member Functions

void computeSecondMomentMatrix (std::size_t pos, float *coefficients) const
 calculates the upper triangular part of unnormalized covariance matrix over intensities given by the 2D coordinates and window_width_ and window_height_
void detectKeypoints (PointCloudOut &output)
 Abstract key point detection method.
bool initCompute ()
 This method should get called before starting the actual computation.
void responseHarris (PointCloudOut &output, float &highest_response) const
 gets the corner response for valid input points
void responseLowe (PointCloudOut &output, float &highest_response) const
void responseNoble (PointCloudOut &output, float &highest_response) const
void responseTomasi (PointCloudOut &output, float &highest_response) const

Protected Attributes

ResponseMethod method_
 cornerness computation methode
bool nonmax_
 non maximas suppression
bool refine_
 corner refinement
unsigned int threads_
 number of threads to be used
float threshold_
 threshold for non maxima suppression

Private Member Functions

bool greaterIntensityAtIndices (int a, int b) const
 comparator for responses intensity

Private Attributes

Eigen::MatrixXf derivatives_cols_
Eigen::MatrixXf derivatives_rows_
int half_window_height_
 half window height
int half_window_width_
 half window width
IntensityT intensity_
 intensity field accessor
int min_distance_
 minimum distance between two keypoints
boost::shared_ptr
< pcl::PointCloud< PointOutT > > 
response_
 intermediate holder for computed responses
int skipped_pixels_
 number of pixels to skip within search window
int window_height_
 Window height.
int window_width_
 Window width.

Detailed Description

template<typename PointInT, typename PointOutT, typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
class pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >

HarrisKeypoint2D detects Harris corners family points.

Author:
Nizar Sallem

Definition at line 54 of file harris_2d.h.


Member Typedef Documentation

template<typename PointInT , typename PointOutT , typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
typedef boost::shared_ptr<const HarrisKeypoint2D<PointInT, PointOutT, IntensityT> > pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::ConstPtr

Reimplemented from pcl::Keypoint< PointInT, PointOutT >.

Definition at line 58 of file harris_2d.h.

template<typename PointInT , typename PointOutT , typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
typedef Keypoint<PointInT, PointOutT>::KdTree pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::KdTree

Reimplemented from pcl::Keypoint< PointInT, PointOutT >.

Definition at line 62 of file harris_2d.h.

template<typename PointInT , typename PointOutT , typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
typedef Keypoint<PointInT, PointOutT>::PointCloudIn pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::PointCloudIn

Reimplemented from pcl::Keypoint< PointInT, PointOutT >.

Definition at line 60 of file harris_2d.h.

template<typename PointInT , typename PointOutT , typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
typedef PointCloudIn::ConstPtr pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::PointCloudInConstPtr

Reimplemented from pcl::Keypoint< PointInT, PointOutT >.

Definition at line 63 of file harris_2d.h.

template<typename PointInT , typename PointOutT , typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
typedef Keypoint<PointInT, PointOutT>::PointCloudOut pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::PointCloudOut

Reimplemented from pcl::Keypoint< PointInT, PointOutT >.

Definition at line 61 of file harris_2d.h.

template<typename PointInT , typename PointOutT , typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
typedef boost::shared_ptr<HarrisKeypoint2D<PointInT, PointOutT, IntensityT> > pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::Ptr

Reimplemented from pcl::Keypoint< PointInT, PointOutT >.

Definition at line 57 of file harris_2d.h.


Member Enumeration Documentation

template<typename PointInT , typename PointOutT , typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
enum pcl::HarrisKeypoint2D::ResponseMethod
Enumerator:
HARRIS 
NOBLE 
LOWE 
TOMASI 

Definition at line 69 of file harris_2d.h.


Constructor & Destructor Documentation

template<typename PointInT , typename PointOutT , typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::HarrisKeypoint2D ( ResponseMethod  method = HARRIS,
int  window_width = 3,
int  window_height = 3,
int  min_distance = 5,
float  threshold = 0.0 
) [inline]

Constructor.

Parameters:
[in]methodthe method to be used to determine the corner responses
[in]thresholdthe threshold to filter out weak corners

Definition at line 75 of file harris_2d.h.


Member Function Documentation

template<typename PointInT , typename PointOutT , typename IntensityT >
void pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::computeSecondMomentMatrix ( std::size_t  pos,
float *  coefficients 
) const [protected]

calculates the upper triangular part of unnormalized covariance matrix over intensities given by the 2D coordinates and window_width_ and window_height_

Definition at line 101 of file harris_2d.hpp.

template<typename PointInT , typename PointOutT , typename IntensityT >
void pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::detectKeypoints ( PointCloudOut output) [protected, virtual]

Abstract key point detection method.

!! nsallem 20120220 : we don't test here for density so if one term in nan the result is nan

Implements pcl::Keypoint< PointInT, PointOutT >.

Definition at line 174 of file harris_2d.hpp.

template<typename PointInT , typename PointOutT , typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
bool pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::greaterIntensityAtIndices ( int  a,
int  b 
) const [inline, private]

comparator for responses intensity

Definition at line 171 of file harris_2d.h.

template<typename PointInT , typename PointOutT , typename IntensityT >
bool pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::initCompute ( ) [protected, virtual]

This method should get called before starting the actual computation.

Internally, initCompute() does the following:

  • checks if an input dataset is given, and returns false otherwise
  • checks whether a set of input indices has been given. Returns true if yes.
  • if no input indices have been given, a fake set is created, which will be used until:
    • either a new set is given via setIndices(), or
    • a new cloud is given that has a different set of points. This will trigger an update on the set of fake indices

Reimplemented from pcl::Keypoint< PointInT, PointOutT >.

Definition at line 128 of file harris_2d.hpp.

template<typename PointInT , typename PointOutT , typename IntensityT >
void pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::responseHarris ( PointCloudOut output,
float &  highest_response 
) const [protected]

gets the corner response for valid input points

Definition at line 301 of file harris_2d.hpp.

template<typename PointInT , typename PointOutT , typename IntensityT >
void pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::responseLowe ( PointCloudOut output,
float &  highest_response 
) const [protected]

Definition at line 385 of file harris_2d.hpp.

template<typename PointInT , typename PointOutT , typename IntensityT >
void pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::responseNoble ( PointCloudOut output,
float &  highest_response 
) const [protected]

Definition at line 343 of file harris_2d.hpp.

template<typename PointInT , typename PointOutT , typename IntensityT >
void pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::responseTomasi ( PointCloudOut output,
float &  highest_response 
) const [protected]

Definition at line 427 of file harris_2d.hpp.

template<typename PointInT , typename PointOutT , typename IntensityT >
void pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::setMethod ( ResponseMethod  type)

set the method of the response to be calculated.

Parameters:
[in]type

Definition at line 45 of file harris_2d.hpp.

template<typename PointInT , typename PointOutT , typename IntensityT >
void pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::setMinimalDistance ( int  min_distance)

Set minimal distance between candidate keypoints.

Definition at line 94 of file harris_2d.hpp.

template<typename PointInT , typename PointOutT , typename IntensityT >
void pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::setNonMaxSupression ( bool  nonmax = false)

whether non maxima suppression should be applied or the response for each point should be returned

Note:
this value needs to be turned on in order to apply thresholding and refinement
Parameters:
[in]nonmaxdefault is false

Definition at line 66 of file harris_2d.hpp.

template<typename PointInT , typename PointOutT , typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
void pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::setNumberOfThreads ( unsigned int  nr_threads = 0) [inline]

Initialize the scheduler and set the number of threads to use.

Parameters:
nr_threadsthe number of hardware threads to use (0 sets the value back to automatic)

Definition at line 130 of file harris_2d.h.

template<typename PointInT , typename PointOutT , typename IntensityT >
void pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::setRefine ( bool  do_refine)

whether the detected key points should be refined or not. If turned of, the key points are a subset of the original point cloud. Otherwise the key points may be arbitrary.

note non maxima supression needs to be on in order to use this feature.

Parameters:
[in]do_refine

Definition at line 59 of file harris_2d.hpp.

template<typename PointInT , typename PointOutT , typename IntensityT >
void pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::setSkippedPixels ( int  skipped_pixels)

Set number of pixels to skip.

Definition at line 87 of file harris_2d.hpp.

template<typename PointInT , typename PointOutT , typename IntensityT >
void pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::setThreshold ( float  threshold)

set the threshold value for detecting corners. This is only evaluated if non maxima suppression is turned on.

note non maxima suppression needs to be activated in order to use this feature.

Parameters:
[in]threshold

Definition at line 52 of file harris_2d.hpp.

template<typename PointInT , typename PointOutT , typename IntensityT >
void pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::setWindowHeight ( int  window_height)

Set window height.

Definition at line 80 of file harris_2d.hpp.

template<typename PointInT , typename PointOutT , typename IntensityT >
void pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::setWindowWidth ( int  window_width)

Set window width.

Definition at line 73 of file harris_2d.hpp.


Member Data Documentation

template<typename PointInT , typename PointOutT , typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
Eigen::MatrixXf pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::derivatives_cols_ [private]

Definition at line 166 of file harris_2d.h.

template<typename PointInT , typename PointOutT , typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
Eigen::MatrixXf pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::derivatives_rows_ [private]

Definition at line 165 of file harris_2d.h.

template<typename PointInT , typename PointOutT , typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
int pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::half_window_height_ [private]

half window height

Definition at line 182 of file harris_2d.h.

template<typename PointInT , typename PointOutT , typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
int pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::half_window_width_ [private]

half window width

Definition at line 180 of file harris_2d.h.

template<typename PointInT , typename PointOutT , typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
IntensityT pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::intensity_ [private]

intensity field accessor

Definition at line 188 of file harris_2d.h.

template<typename PointInT , typename PointOutT , typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
ResponseMethod pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::method_ [protected]

cornerness computation methode

Definition at line 160 of file harris_2d.h.

template<typename PointInT , typename PointOutT , typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
int pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::min_distance_ [private]

minimum distance between two keypoints

Definition at line 186 of file harris_2d.h.

template<typename PointInT , typename PointOutT , typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
bool pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::nonmax_ [protected]

non maximas suppression

Definition at line 158 of file harris_2d.h.

template<typename PointInT , typename PointOutT , typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
bool pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::refine_ [protected]

corner refinement

Definition at line 156 of file harris_2d.h.

template<typename PointInT , typename PointOutT , typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
boost::shared_ptr<pcl::PointCloud<PointOutT> > pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::response_ [private]

intermediate holder for computed responses

Definition at line 168 of file harris_2d.h.

template<typename PointInT , typename PointOutT , typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
int pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::skipped_pixels_ [private]

number of pixels to skip within search window

Definition at line 184 of file harris_2d.h.

template<typename PointInT , typename PointOutT , typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
unsigned int pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::threads_ [protected]

number of threads to be used

Definition at line 162 of file harris_2d.h.

template<typename PointInT , typename PointOutT , typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
float pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::threshold_ [protected]

threshold for non maxima suppression

Definition at line 154 of file harris_2d.h.

template<typename PointInT , typename PointOutT , typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
int pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::window_height_ [private]

Window height.

Definition at line 178 of file harris_2d.h.

template<typename PointInT , typename PointOutT , typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
int pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::window_width_ [private]

Window width.

Definition at line 176 of file harris_2d.h.


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


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:41:38