Motion estimation based on aligning sparse features against a persistent, dynamic model. More...
#include <motion_estimation_icp_prob_model.h>
Public Member Functions | |
Matrix3fVector * | getCovariances () |
Matrix3fVector * | getCovariances () |
Vector3fVector * | getMeans () |
Vector3fVector * | getMeans () |
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. |
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 from ROS noehandles.
nh | the public nodehandle |
nh_private | the 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.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW rgbdtools::MotionEstimationICPProbModel::MotionEstimationICPProbModel | ( | ) |
Constructor from ROS noehandles.
nh | the public nodehandle |
nh_private | the private notehandle |
virtual rgbdtools::MotionEstimationICPProbModel::~MotionEstimationICPProbModel | ( | ) | [virtual] |
Default destructor.
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
data_mean | 3x1 data point means |
data_cov | 3x3 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
data_mean | 3x1 data point means |
data_cov | 3x3 data point covariances |
bool rgbdtools::MotionEstimationICPProbModel::alignICPEuclidean | ( | const Vector3fVector & | data_means, |
AffineTransform & | correction | ||
) | [private] |
Performs ICP alignment using the Euclidean distance for corresopndences.
data_means | a vector of 3x1 matrices, repesenting the 3D positions of the features |
correction | reference to the resulting transformation |
true | the motion estimation was successful |
false | the motion estimation failed |
bool rgbdtools::MotionEstimationICPProbModel::alignICPEuclidean | ( | const Vector3fVector & | data_means, |
AffineTransform & | correction | ||
) | [private] |
Performs ICP alignment using the Euclidean distance for corresopndences.
data_means | a vector of 3x1 matrices, repesenting the 3D positions of the features |
correction | reference to the resulting transformation |
true | the motion estimation was successful |
false | the 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.
data_cloud | a pointcloud of the 3D positions of the features |
data_indices | reference to a vector containting the resulting data indices |
model_indices | reference 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.
data_cloud | a pointcloud of the 3D positions of the features |
data_indices | reference to a vector containting the resulting data indices |
model_indices | reference to a vector containting the resulting model indices |
Definition at line 219 of file motion_estimation_icp_prob_model.cpp.
Definition at line 77 of file include/rgbdtools/registration/motion_estimation_icp_prob_model.h.
Definition at line 77 of file rgbdtools_git/include/rgbdtools/registration/motion_estimation_icp_prob_model.h.
Definition at line 76 of file include/rgbdtools/registration/motion_estimation_icp_prob_model.h.
Definition at line 76 of file rgbdtools_git/include/rgbdtools/registration/motion_estimation_icp_prob_model.h.
PointCloudFeature::Ptr rgbdtools::MotionEstimationICPProbModel::getModel | ( | ) | [inline] |
Definition at line 75 of file include/rgbdtools/registration/motion_estimation_icp_prob_model.h.
PointCloudFeature::Ptr rgbdtools::MotionEstimationICPProbModel::getModel | ( | ) | [inline] |
Definition at line 75 of file rgbdtools_git/include/rgbdtools/registration/motion_estimation_icp_prob_model.h.
int rgbdtools::MotionEstimationICPProbModel::getModelSize | ( | ) | const [inline, virtual] |
Returns the number of points in the model built from the feature buffer.
Reimplemented from rgbdtools::MotionEstimation.
Definition at line 73 of file rgbdtools_git/include/rgbdtools/registration/motion_estimation_icp_prob_model.h.
int rgbdtools::MotionEstimationICPProbModel::getModelSize | ( | ) | const [inline, virtual] |
Returns the number of points in the model built from the feature buffer.
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.
frame | the current RGBD frame |
prediction | the predicted motion (currently ignored) |
motion | the (output) incremental motion, wrt the fixed frame |
true | the motion estimation was successful |
false | the motion estimation failed |
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.
frame | the current RGBD frame |
prediction | the predicted motion (currently ignored) |
motion | the (output) incremental motion, wrt the fixed frame |
true | the motion estimation was successful |
false | the 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.
data_point | the query 3D data point |
eucl_nn_idx | reference to the resulting nearest neigbor index in the model |
eucl_dist_sq | reference to the resulting squared distance |
true | a neighbor was found |
false | a 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.
data_point | the query 3D data point |
eucl_nn_idx | reference to the resulting nearest neigbor index in the model |
eucl_dist_sq | reference to the resulting squared distance |
true | a neighbor was found |
false | a 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.
data_mean | 3x1 matrix of the query 3D data point mean |
data_cov | 3x3 matrix of the query 3D data point covariance |
mah_nn_idx | reference to the resulting nearest neigbor index in the model |
mah_dist_sq | reference to the resulting squared Mahalanobis distance |
indices | cache vector, pre-allocated with n_nearest_neighbors_ size |
dists_sq | cache vector, pre-allocated with n_nearest_neighbors_ size |
true | a neighbor was found |
false | a 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.
data_mean | 3x1 matrix of the query 3D data point mean |
data_cov | 3x3 matrix of the query 3D data point covariance |
mah_nn_idx | reference to the resulting nearest neigbor index in the model |
mah_dist_sq | reference to the resulting squared Mahalanobis distance |
indices | cache vector, pre-allocated with n_nearest_neighbors_ size |
dists_sq | cache vector, pre-allocated with n_nearest_neighbors_ size |
true | a neighbor was found |
false | a 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.
data_means | vector of 3x1 data point means |
data_covariances | vector 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.
data_means | vector of 3x1 data point means |
data_covariances | vector 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] |
Definition at line 382 of file motion_estimation_icp_prob_model.cpp.
void rgbdtools::MotionEstimationICPProbModel::setMaxAssociationDistMahalanobis | ( | double | max_assoc_dist_mah | ) |
void rgbdtools::MotionEstimationICPProbModel::setMaxAssociationDistMahalanobis | ( | double | max_assoc_dist_mah | ) |
Definition at line 434 of file motion_estimation_icp_prob_model.cpp.
void rgbdtools::MotionEstimationICPProbModel::setMaxCorrespondenceDistEuclidean | ( | double | max_corresp_dist_eucl | ) |
void rgbdtools::MotionEstimationICPProbModel::setMaxCorrespondenceDistEuclidean | ( | double | max_corresp_dist_eucl | ) |
Definition at line 441 of file motion_estimation_icp_prob_model.cpp.
void rgbdtools::MotionEstimationICPProbModel::setMaxIterations | ( | int | max_iterations | ) |
Definition at line 404 of file motion_estimation_icp_prob_model.cpp.
void rgbdtools::MotionEstimationICPProbModel::setMaxIterations | ( | int | max_iterations | ) |
void rgbdtools::MotionEstimationICPProbModel::setMaxModelSize | ( | int | max_model_size | ) |
Definition at line 419 of file motion_estimation_icp_prob_model.cpp.
void rgbdtools::MotionEstimationICPProbModel::setMaxModelSize | ( | int | max_model_size | ) |
void rgbdtools::MotionEstimationICPProbModel::setMinCorrespondences | ( | int | min_correspondences | ) |
void rgbdtools::MotionEstimationICPProbModel::setMinCorrespondences | ( | int | min_correspondences | ) |
Definition at line 409 of file motion_estimation_icp_prob_model.cpp.
void rgbdtools::MotionEstimationICPProbModel::setNNearestNeighbors | ( | int | n_nearest_neighbors | ) |
Definition at line 414 of file motion_estimation_icp_prob_model.cpp.
void rgbdtools::MotionEstimationICPProbModel::setNNearestNeighbors | ( | int | n_nearest_neighbors | ) |
void rgbdtools::MotionEstimationICPProbModel::setTfEpsilonAngular | ( | double | tf_epsilon_angular | ) |
Definition at line 429 of file motion_estimation_icp_prob_model.cpp.
void rgbdtools::MotionEstimationICPProbModel::setTfEpsilonAngular | ( | double | tf_epsilon_angular | ) |
void rgbdtools::MotionEstimationICPProbModel::setTfEpsilonLinear | ( | double | tf_epsilon_linear | ) |
void rgbdtools::MotionEstimationICPProbModel::setTfEpsilonLinear | ( | double | tf_epsilon_linear | ) |
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.
data_means | vector of 3x1 data point means |
data_covariances | vector 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.
data_means | vector of 3x1 data point means |
data_covariances | vector of 3x3 data point covariances |
Definition at line 324 of file motion_estimation_icp_prob_model.cpp.
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.
double rgbdtools::MotionEstimationICPProbModel::max_assoc_dist_mah_ [private] |
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.
double rgbdtools::MotionEstimationICPProbModel::max_assoc_dist_mah_sq_ [private] |
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.
double rgbdtools::MotionEstimationICPProbModel::max_corresp_dist_eucl_ [private] |
Maximum Euclidean correspondce distance for ICP.
Definition at line 116 of file include/rgbdtools/registration/motion_estimation_icp_prob_model.h.
double rgbdtools::MotionEstimationICPProbModel::max_corresp_dist_eucl_sq_ [private] |
Maximum Euclidean correspondce distance for ICP, derived.
Definition at line 126 of file include/rgbdtools/registration/motion_estimation_icp_prob_model.h.
int rgbdtools::MotionEstimationICPProbModel::max_iterations_ [private] |
Maximum number of ICP iterations.
Definition at line 92 of file include/rgbdtools/registration/motion_estimation_icp_prob_model.h.
int rgbdtools::MotionEstimationICPProbModel::max_model_size_ [private] |
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.
int rgbdtools::MotionEstimationICPProbModel::model_idx_ [private] |
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.
int rgbdtools::MotionEstimationICPProbModel::model_size_ [private] |
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.
double rgbdtools::MotionEstimationICPProbModel::tf_epsilon_angular_ [private] |
Angular convergence criteria for ICP.
Definition at line 107 of file include/rgbdtools/registration/motion_estimation_icp_prob_model.h.
double rgbdtools::MotionEstimationICPProbModel::tf_epsilon_linear_ [private] |
Linear convergence criteria for ICP.
Definition at line 106 of file include/rgbdtools/registration/motion_estimation_icp_prob_model.h.