Naive point-to-point ICP matching cost factor Zhang, "Iterative Point Matching for Registration of Free-Form Curve", IJCV1994.
More...
|
| | IntegratedICPFactor_ (gtsam::Key target_key, gtsam::Key source_key, const std::shared_ptr< const TargetFrame > &target, const std::shared_ptr< const SourceFrame > &source, const std::shared_ptr< const NearestNeighborSearch > &target_tree, bool use_point_to_plane=false) |
| | Create a binary ICP factor between two poses.
|
| |
|
| IntegratedICPFactor_ (gtsam::Key target_key, gtsam::Key source_key, const std::shared_ptr< const TargetFrame > &target, const std::shared_ptr< const SourceFrame > &source, bool use_point_to_plane=false) |
| | Create a binary ICP factor between two poses.
|
| |
| | IntegratedICPFactor_ (const gtsam::Pose3 &fixed_target_pose, gtsam::Key source_key, const std::shared_ptr< const TargetFrame > &target, const std::shared_ptr< const SourceFrame > &source, const std::shared_ptr< const NearestNeighborSearch > &target_tree, bool use_point_to_plane=false) |
| | Create a unary ICP factor between a fixed target pose and an active source pose.
|
| |
|
| IntegratedICPFactor_ (const gtsam::Pose3 &fixed_target_pose, gtsam::Key source_key, const std::shared_ptr< const TargetFrame > &target, const std::shared_ptr< const SourceFrame > &source, bool use_point_to_plane=false) |
| | Create a unary ICP factor between a fixed target pose and an active source pose.
|
| |
| virtual void | print (const std::string &s="", const gtsam::KeyFormatter &keyFormatter=gtsam::DefaultKeyFormatter) const override |
| | Print the factor information.
|
| |
| virtual size_t | memory_usage () const override |
| | Calculate the memory usage of this factor.
|
| |
| void | set_num_threads (int n) |
| | Set the number of thread used for linearization of this factor.
|
| |
|
void | set_max_correspondence_distance (double dist) |
| | Set the maximum distance between corresponding points. Correspondences with distances larger than this will be rejected (i.e., correspondence trimming).
|
| |
|
void | set_point_to_plane_distance (bool use) |
| | Enable or disable point-to-plane distance computation.
|
| |
| void | set_correspondence_update_tolerance (double angle, double trans) |
| | Correspondences are updated only when the displacement from the last update point is larger than these threshold values.
|
| |
| | IntegratedMatchingCostFactor (gtsam::Key target_key, gtsam::Key source_key) |
| | Create a binary matching cost factor between target and source poses.
|
| |
| | IntegratedMatchingCostFactor (const gtsam::Pose3 &fixed_target_pose, gtsam::Key source_key) |
| | Create a unary matching cost factor between a fixed target pose and an active source pose.
|
| |
|
virtual size_t | dim () const override |
| |
| virtual double | error (const gtsam::Values &values) const override |
| |
|
virtual gtsam::GaussianFactor::shared_ptr | linearize (const gtsam::Values &values) const override |
| |
|
const Eigen::Isometry3d & | get_fixed_target_pose () const |
| |
|
Eigen::Isometry3d | calc_delta (const gtsam::Values &values) const |
| |
template<typename TargetFrame = gtsam_points::PointCloud, typename SourceFrame = gtsam_points::PointCloud>
class gtsam_points::IntegratedICPFactor_< TargetFrame, SourceFrame >
Naive point-to-point ICP matching cost factor Zhang, "Iterative Point Matching for Registration of Free-Form Curve", IJCV1994.