6 #include <Eigen/Geometry> 
   19   template <
typename TargetPo
intCloud, 
typename SourcePo
intCloud, 
typename TargetTree, 
typename CorrespondenceRejector>
 
   21     const TargetPointCloud& target,
 
   22     const SourcePointCloud& source,
 
   23     const TargetTree& target_tree,
 
   24     const Eigen::Isometry3d& T,
 
   26     const CorrespondenceRejector& rejector,
 
   27     Eigen::Matrix<double, 6, 6>* H,
 
   28     Eigen::Matrix<double, 6, 1>* b,
 
   45     Eigen::Matrix<double, 4, 6> J = Eigen::Matrix<double, 4, 6>::Zero();
 
   47     J.block<3, 3>(0, 3) = -T.linear();
 
   49     *H = J.transpose() * J;
 
   50     *b = J.transpose() * residual;
 
   51     *e = 0.5 * residual.squaredNorm();
 
   56   template <
typename TargetPo
intCloud, 
typename SourcePo
intCloud>
 
   57   double error(
const TargetPointCloud& target, 
const SourcePointCloud& source, 
const Eigen::Isometry3d& T)
 const {
 
   58     if (
target_index == std::numeric_limits<size_t>::max()) {
 
   63     return 0.5 * residual.squaredNorm();
 
size_t nearest_neighbor_search(const T &tree, const Eigen::Vector4d &point, size_t *k_index, double *k_sq_dist)
Find the nearest neighbor. If Traits<T>::nearest_neighbor_search is not defined, fallback to knn_sear...
Definition: traits.hpp:44
 
auto point(const T &points, size_t i)
Get i-th point. 4D vector is used to take advantage of SIMD intrinsics. The last element must be fill...
Definition: traits.hpp:40
 
Definition: flat_container.hpp:12
 
Eigen::Matrix3d skew(const Eigen::Vector3d &x)
Create skew symmetric matrix.
Definition: lie.hpp:13
 
Definition: icp_factor.hpp:15
 
Point-to-point per-point error factor.
Definition: icp_factor.hpp:14
 
bool linearize(const TargetPointCloud &target, const SourcePointCloud &source, const TargetTree &target_tree, const Eigen::Isometry3d &T, size_t source_index, const CorrespondenceRejector &rejector, Eigen::Matrix< double, 6, 6 > *H, Eigen::Matrix< double, 6, 1 > *b, double *e)
Definition: icp_factor.hpp:20
 
bool inlier() const
Definition: icp_factor.hpp:66
 
size_t source_index
Definition: icp_factor.hpp:69
 
double error(const TargetPointCloud &target, const SourcePointCloud &source, const Eigen::Isometry3d &T) const
Definition: icp_factor.hpp:57
 
ICPFactor(const Setting &setting=Setting())
Definition: icp_factor.hpp:17
 
size_t target_index
Definition: icp_factor.hpp:68