All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends
Public Member Functions | Private Member Functions | Private Attributes
rgbdtools::MotionEstimationICPProbModel Class Reference

Motion estimation based on aligning sparse features against a persistent, dynamic model. More...

#include <motion_estimation_icp_prob_model.h>

Inheritance diagram for rgbdtools::MotionEstimationICPProbModel:
Inheritance graph
[legend]

List of all members.

Public Member Functions

Matrix3fVectorgetCovariances ()
Matrix3fVectorgetCovariances ()
Vector3fVectorgetMeans ()
Vector3fVectorgetMeans ()
PointCloudFeature::Ptr getModel ()
PointCloudFeature::Ptr getModel ()
int getModelSize () const
 Returns the number of points in the model built from the feature buffer.
int getModelSize () const
 Returns the number of points in the model built from the feature buffer.
bool getMotionEstimationImpl (RGBDFrame &frame, const AffineTransform &prediction, AffineTransform &motion)
 Main method for estimating the motion given an RGBD frame.
bool getMotionEstimationImpl (RGBDFrame &frame, const AffineTransform &prediction, AffineTransform &motion)
 Main method for estimating the motion given an RGBD frame.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW MotionEstimationICPProbModel ()
 Constructor from ROS noehandles.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW MotionEstimationICPProbModel ()
 Constructor from ROS noehandles.
void resetModel ()
void resetModel ()
void setMaxAssociationDistMahalanobis (double max_assoc_dist_mah)
void setMaxAssociationDistMahalanobis (double max_assoc_dist_mah)
void setMaxCorrespondenceDistEuclidean (double max_corresp_dist_eucl)
void setMaxCorrespondenceDistEuclidean (double max_corresp_dist_eucl)
void setMaxIterations (int max_iterations)
void setMaxIterations (int max_iterations)
void setMaxModelSize (int max_model_size)
void setMaxModelSize (int max_model_size)
void setMinCorrespondences (int min_correspondences)
void setMinCorrespondences (int min_correspondences)
void setNNearestNeighbors (int n_nearest_neighbors)
void setNNearestNeighbors (int n_nearest_neighbors)
void setTfEpsilonAngular (double tf_epsilon_angular)
void setTfEpsilonAngular (double tf_epsilon_angular)
void setTfEpsilonLinear (double tf_epsilon_linear)
void setTfEpsilonLinear (double tf_epsilon_linear)
virtual ~MotionEstimationICPProbModel ()
 Default destructor.
virtual ~MotionEstimationICPProbModel ()
 Default destructor.

Private Member Functions

void addToModel (const Vector3f &data_mean, const Matrix3f &data_cov)
 Adds a new point to the model.
void addToModel (const Vector3f &data_mean, const Matrix3f &data_cov)
 Adds a new point to the model.
bool alignICPEuclidean (const Vector3fVector &data_means, AffineTransform &correction)
 Performs ICP alignment using the Euclidean distance for corresopndences.
bool alignICPEuclidean (const Vector3fVector &data_means, AffineTransform &correction)
 Performs ICP alignment using the Euclidean distance for corresopndences.
void getCorrespEuclidean (const PointCloudFeature &data_cloud, IntVector &data_indices, IntVector &model_indices)
 Performs ICP alignment using the Euclidean distance for corresopndences.
void getCorrespEuclidean (const PointCloudFeature &data_cloud, IntVector &data_indices, IntVector &model_indices)
 Performs ICP alignment using the Euclidean distance for corresopndences.
bool getNNEuclidean (const PointFeature &data_point, int &eucl_nn_idx, double &eucl_dist_sq)
 Finds the nearest Euclidean neighbor.
bool getNNEuclidean (const PointFeature &data_point, int &eucl_nn_idx, double &eucl_dist_sq)
 Finds the nearest Euclidean neighbor.
bool getNNMahalanobis (const Vector3f &data_mean, const Matrix3f &data_cov, int &mah_nn_idx, double &mah_dist_sq, IntVector &indices, FloatVector &dists_sq)
 Finds the nearest Mahalanobis neighbor.
bool getNNMahalanobis (const Vector3f &data_mean, const Matrix3f &data_cov, int &mah_nn_idx, double &mah_dist_sq, IntVector &indices, FloatVector &dists_sq)
 Finds the nearest Mahalanobis neighbor.
void initializeModelFromData (const Vector3fVector &data_means, const Matrix3fVector &data_covariances)
 Initializes the (empty) model from a set of data means and covariances.
void initializeModelFromData (const Vector3fVector &data_means, const Matrix3fVector &data_covariances)
 Initializes the (empty) model from a set of data means and covariances.
bool saveModel (const std::string &filename)
bool saveModel (const std::string &filename)
void updateModelFromData (const Vector3fVector &data_means, const Matrix3fVector &data_covariances)
 Updates the (non-empty) model from a set of data means and covariances.
void updateModelFromData (const Vector3fVector &data_means, const Matrix3fVector &data_covariances)
 Updates the (non-empty) model from a set of data means and covariances.

Private Attributes

Matrix3fVector covariances_
 Vector of model feature covariances.
AffineTransform f2b_
 Transform from fixed to moving frame.
Matrix3f I_
 3x3 Identity matrix
double max_assoc_dist_mah_
 Maximum Mahalanobis distance for associating points between the data and the model.
double max_assoc_dist_mah_sq_
 Maximum squared Mahalanobis distance for associating points between the data and the model, derived.
double max_corresp_dist_eucl_
 Maximum Euclidean correspondce distance for ICP.
double max_corresp_dist_eucl_sq_
 Maximum Euclidean correspondce distance for ICP, derived.
int max_iterations_
 Maximum number of ICP iterations.
int max_model_size_
 Upper bound for how many features to store in the model.
Vector3fVector means_
 Vector of model feature mean.
int min_correspondences_
 Minimum number of correspondences for ICP to contuinue.
int model_idx_
 Current intex in the ring buffer.
PointCloudFeature::Ptr model_ptr_
 The model point cloud.
int model_size_
 Current model size.
KdTree model_tree_
 Kdtree of model_ptr_.
int n_nearest_neighbors_
 How many euclidean neighbors to go through, in a brute force search of the closest Mahalanobis neighbor.
double tf_epsilon_angular_
 Angular convergence criteria for ICP.
double tf_epsilon_linear_
 Linear convergence criteria for ICP.

Detailed Description

Motion estimation based on aligning sparse features against a persistent, dynamic model.

The model is build from incoming features through a Kalman Filter update step.

Definition at line 42 of file include/rgbdtools/registration/motion_estimation_icp_prob_model.h.


Constructor & Destructor Documentation

Constructor from ROS noehandles.

Parameters:
nhthe public nodehandle
nh_privatethe private notehandle

Definition at line 28 of file motion_estimation_icp_prob_model.cpp.

Default destructor.

Definition at line 54 of file motion_estimation_icp_prob_model.cpp.

Constructor from ROS noehandles.

Parameters:
nhthe public nodehandle
nh_privatethe private notehandle

Default destructor.


Member Function Documentation

void rgbdtools::MotionEstimationICPProbModel::addToModel ( const Vector3f data_mean,
const Matrix3f data_cov 
) [private]

Adds a new point to the model.

The model is implemented using a rign buffer. If the number of points in the model has reached the maximum, the new point will overwrite the oldest model point

Parameters:
data_mean3x1 data point means
data_cov3x3 data point covariances

Definition at line 59 of file motion_estimation_icp_prob_model.cpp.

void rgbdtools::MotionEstimationICPProbModel::addToModel ( const Vector3f data_mean,
const Matrix3f data_cov 
) [private]

Adds a new point to the model.

The model is implemented using a rign buffer. If the number of points in the model has reached the maximum, the new point will overwrite the oldest model point

Parameters:
data_mean3x1 data point means
data_cov3x3 data point covariances
bool rgbdtools::MotionEstimationICPProbModel::alignICPEuclidean ( const Vector3fVector data_means,
AffineTransform correction 
) [private]

Performs ICP alignment using the Euclidean distance for corresopndences.

Parameters:
data_meansa vector of 3x1 matrices, repesenting the 3D positions of the features
correctionreference to the resulting transformation
Return values:
truethe motion estimation was successful
falsethe motion estimation failed
bool rgbdtools::MotionEstimationICPProbModel::alignICPEuclidean ( const Vector3fVector data_means,
AffineTransform correction 
) [private]

Performs ICP alignment using the Euclidean distance for corresopndences.

Parameters:
data_meansa vector of 3x1 matrices, repesenting the 3D positions of the features
correctionreference to the resulting transformation
Return values:
truethe motion estimation was successful
falsethe motion estimation failed

Definition at line 159 of file motion_estimation_icp_prob_model.cpp.

void rgbdtools::MotionEstimationICPProbModel::getCorrespEuclidean ( const PointCloudFeature data_cloud,
IntVector data_indices,
IntVector model_indices 
) [private]

Performs ICP alignment using the Euclidean distance for corresopndences.

Parameters:
data_clouda pointcloud of the 3D positions of the features
data_indicesreference to a vector containting the resulting data indices
model_indicesreference to a vector containting the resulting model indices
void rgbdtools::MotionEstimationICPProbModel::getCorrespEuclidean ( const PointCloudFeature data_cloud,
IntVector data_indices,
IntVector model_indices 
) [private]

Performs ICP alignment using the Euclidean distance for corresopndences.

Parameters:
data_clouda pointcloud of the 3D positions of the features
data_indicesreference to a vector containting the resulting data indices
model_indicesreference to a vector containting the resulting model indices

Definition at line 219 of file motion_estimation_icp_prob_model.cpp.

PointCloudFeature::Ptr rgbdtools::MotionEstimationICPProbModel::getModel ( ) [inline]
PointCloudFeature::Ptr rgbdtools::MotionEstimationICPProbModel::getModel ( ) [inline]

Returns the number of points in the model built from the feature buffer.

Returns:
number of points in model

Reimplemented from rgbdtools::MotionEstimation.

Definition at line 73 of file rgbdtools_git/include/rgbdtools/registration/motion_estimation_icp_prob_model.h.

Returns the number of points in the model built from the feature buffer.

Returns:
number of points in model

Reimplemented from rgbdtools::MotionEstimation.

Definition at line 73 of file include/rgbdtools/registration/motion_estimation_icp_prob_model.h.

bool rgbdtools::MotionEstimationICPProbModel::getMotionEstimationImpl ( RGBDFrame frame,
const AffineTransform prediction,
AffineTransform motion 
) [virtual]

Main method for estimating the motion given an RGBD frame.

Parameters:
framethe current RGBD frame
predictionthe predicted motion (currently ignored)
motionthe (output) incremental motion, wrt the fixed frame
Return values:
truethe motion estimation was successful
falsethe motion estimation failed
Todo:
: currently ignores prediction

Implements rgbdtools::MotionEstimation.

Definition at line 95 of file motion_estimation_icp_prob_model.cpp.

bool rgbdtools::MotionEstimationICPProbModel::getMotionEstimationImpl ( RGBDFrame frame,
const AffineTransform prediction,
AffineTransform motion 
) [virtual]

Main method for estimating the motion given an RGBD frame.

Parameters:
framethe current RGBD frame
predictionthe predicted motion (currently ignored)
motionthe (output) incremental motion, wrt the fixed frame
Return values:
truethe motion estimation was successful
falsethe motion estimation failed

Implements rgbdtools::MotionEstimation.

bool rgbdtools::MotionEstimationICPProbModel::getNNEuclidean ( const PointFeature data_point,
int &  eucl_nn_idx,
double &  eucl_dist_sq 
) [private]

Finds the nearest Euclidean neighbor.

Parameters:
data_pointthe query 3D data point
eucl_nn_idxreference to the resulting nearest neigbor index in the model
eucl_dist_sqreference to the resulting squared distance
Return values:
truea neighbor was found
falsea neighbor was not found

Definition at line 241 of file motion_estimation_icp_prob_model.cpp.

bool rgbdtools::MotionEstimationICPProbModel::getNNEuclidean ( const PointFeature data_point,
int &  eucl_nn_idx,
double &  eucl_dist_sq 
) [private]

Finds the nearest Euclidean neighbor.

Parameters:
data_pointthe query 3D data point
eucl_nn_idxreference to the resulting nearest neigbor index in the model
eucl_dist_sqreference to the resulting squared distance
Return values:
truea neighbor was found
falsea neighbor was not found
bool rgbdtools::MotionEstimationICPProbModel::getNNMahalanobis ( const Vector3f data_mean,
const Matrix3f data_cov,
int &  mah_nn_idx,
double &  mah_dist_sq,
IntVector indices,
FloatVector dists_sq 
) [private]

Finds the nearest Mahalanobis neighbor.

Requests the K nearest Euclidean neighbors (K = n_nearest_neighbors_) using a kdtree, and performs a brute force search for the closest Mahalanobis nighbor. Reasonable values for K are 4 or 8.

Parameters:
data_mean3x1 matrix of the query 3D data point mean
data_cov3x3 matrix of the query 3D data point covariance
mah_nn_idxreference to the resulting nearest neigbor index in the model
mah_dist_sqreference to the resulting squared Mahalanobis distance
indicescache vector, pre-allocated with n_nearest_neighbors_ size
dists_sqcache vector, pre-allocated with n_nearest_neighbors_ size
Return values:
truea neighbor was found
falsea neighbor was not found

Definition at line 263 of file motion_estimation_icp_prob_model.cpp.

bool rgbdtools::MotionEstimationICPProbModel::getNNMahalanobis ( const Vector3f data_mean,
const Matrix3f data_cov,
int &  mah_nn_idx,
double &  mah_dist_sq,
IntVector indices,
FloatVector dists_sq 
) [private]

Finds the nearest Mahalanobis neighbor.

Requests the K nearest Euclidean neighbors (K = n_nearest_neighbors_) using a kdtree, and performs a brute force search for the closest Mahalanobis nighbor. Reasonable values for K are 4 or 8.

Parameters:
data_mean3x1 matrix of the query 3D data point mean
data_cov3x3 matrix of the query 3D data point covariance
mah_nn_idxreference to the resulting nearest neigbor index in the model
mah_dist_sqreference to the resulting squared Mahalanobis distance
indicescache vector, pre-allocated with n_nearest_neighbors_ size
dists_sqcache vector, pre-allocated with n_nearest_neighbors_ size
Return values:
truea neighbor was found
falsea neighbor was not found
void rgbdtools::MotionEstimationICPProbModel::initializeModelFromData ( const Vector3fVector data_means,
const Matrix3fVector data_covariances 
) [private]

Initializes the (empty) model from a set of data means and covariances.

Parameters:
data_meansvector of 3x1 data point means
data_covariancesvector of 3x3 data point covariances

Definition at line 312 of file motion_estimation_icp_prob_model.cpp.

void rgbdtools::MotionEstimationICPProbModel::initializeModelFromData ( const Vector3fVector data_means,
const Matrix3fVector data_covariances 
) [private]

Initializes the (empty) model from a set of data means and covariances.

Parameters:
data_meansvector of 3x1 data point means
data_covariancesvector of 3x3 data point covariances

Definition at line 90 of file motion_estimation_icp_prob_model.cpp.

bool rgbdtools::MotionEstimationICPProbModel::saveModel ( const std::string &  filename) [private]
bool rgbdtools::MotionEstimationICPProbModel::saveModel ( const std::string &  filename) [private]
Todo:
also save Eigen means and covariances

Definition at line 382 of file motion_estimation_icp_prob_model.cpp.

Definition at line 434 of file motion_estimation_icp_prob_model.cpp.

Definition at line 441 of file motion_estimation_icp_prob_model.cpp.

Definition at line 404 of file motion_estimation_icp_prob_model.cpp.

Definition at line 419 of file motion_estimation_icp_prob_model.cpp.

Definition at line 409 of file motion_estimation_icp_prob_model.cpp.

Definition at line 414 of file motion_estimation_icp_prob_model.cpp.

Definition at line 429 of file motion_estimation_icp_prob_model.cpp.

Definition at line 424 of file motion_estimation_icp_prob_model.cpp.

void rgbdtools::MotionEstimationICPProbModel::updateModelFromData ( const Vector3fVector data_means,
const Matrix3fVector data_covariances 
) [private]

Updates the (non-empty) model from a set of data means and covariances.

Any data points which have a Mahalanobis neighbor in the model under a certain threshold distance get updated using a Kalman filter.

Any data points without a Mahalanobis neighbor get insterted as new model points.

Parameters:
data_meansvector of 3x1 data point means
data_covariancesvector of 3x3 data point covariances
void rgbdtools::MotionEstimationICPProbModel::updateModelFromData ( const Vector3fVector data_means,
const Matrix3fVector data_covariances 
) [private]

Updates the (non-empty) model from a set of data means and covariances.

Any data points which have a Mahalanobis neighbor in the model under a certain threshold distance get updated using a Kalman filter.

Any data points without a Mahalanobis neighbor get insterted as new model points.

Parameters:
data_meansvector of 3x1 data point means
data_covariancesvector of 3x3 data point covariances

Definition at line 324 of file motion_estimation_icp_prob_model.cpp.


Member Data Documentation

Vector of model feature covariances.

Definition at line 134 of file include/rgbdtools/registration/motion_estimation_icp_prob_model.h.

Transform from fixed to moving frame.

Definition at line 140 of file include/rgbdtools/registration/motion_estimation_icp_prob_model.h.

3x3 Identity matrix

Definition at line 138 of file include/rgbdtools/registration/motion_estimation_icp_prob_model.h.

Maximum Mahalanobis distance for associating points between the data and the model.

Definition at line 112 of file include/rgbdtools/registration/motion_estimation_icp_prob_model.h.

Maximum squared Mahalanobis distance for associating points between the data and the model, derived.

Definition at line 122 of file include/rgbdtools/registration/motion_estimation_icp_prob_model.h.

Maximum Euclidean correspondce distance for ICP.

Definition at line 116 of file include/rgbdtools/registration/motion_estimation_icp_prob_model.h.

Maximum Euclidean correspondce distance for ICP, derived.

Definition at line 126 of file include/rgbdtools/registration/motion_estimation_icp_prob_model.h.

Maximum number of ICP iterations.

Definition at line 92 of file include/rgbdtools/registration/motion_estimation_icp_prob_model.h.

Upper bound for how many features to store in the model.

New features added beyond thi spoint will overwrite old features

Definition at line 104 of file include/rgbdtools/registration/motion_estimation_icp_prob_model.h.

Vector of model feature mean.

Definition at line 133 of file include/rgbdtools/registration/motion_estimation_icp_prob_model.h.

Minimum number of correspondences for ICP to contuinue.

Definition at line 93 of file include/rgbdtools/registration/motion_estimation_icp_prob_model.h.

Current intex in the ring buffer.

Definition at line 131 of file include/rgbdtools/registration/motion_estimation_icp_prob_model.h.

PointCloudFeature::Ptr rgbdtools::MotionEstimationICPProbModel::model_ptr_ [private]

The model point cloud.

Definition at line 130 of file include/rgbdtools/registration/motion_estimation_icp_prob_model.h.

Current model size.

Definition at line 132 of file include/rgbdtools/registration/motion_estimation_icp_prob_model.h.

Kdtree of model_ptr_.

Definition at line 136 of file include/rgbdtools/registration/motion_estimation_icp_prob_model.h.

How many euclidean neighbors to go through, in a brute force search of the closest Mahalanobis neighbor.

Definition at line 98 of file include/rgbdtools/registration/motion_estimation_icp_prob_model.h.

Angular convergence criteria for ICP.

Definition at line 107 of file include/rgbdtools/registration/motion_estimation_icp_prob_model.h.

Linear convergence criteria for ICP.

Definition at line 106 of file include/rgbdtools/registration/motion_estimation_icp_prob_model.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends


lib_rgbdtools
Author(s): Ivan Dryanovski
autogenerated on Tue Aug 27 2013 10:33:55