|
gtsam_points
|
Continuous Time ICP with GICP's D2D cost Bellenbach et al., "CT-ICP: Real-time Elastic LiDAR Odometry with Loop Closure", 2021 Segal et al., "Generalized-ICP", RSS2005. More...
#include <integrated_ct_gicp_factor.hpp>


Public Types | |
| using | shared_ptr = gtsam_points::shared_ptr< IntegratedCT_GICPFactor_< TargetFrame, SourceFrame > > |
Public Types inherited from gtsam_points::IntegratedCT_ICPFactor_< TargetFrame, SourceFrame > | |
| using | shared_ptr = gtsam_points::shared_ptr< IntegratedCT_ICPFactor_< TargetFrame, SourceFrame > > |
Public Member Functions | |
| IntegratedCT_GICPFactor_ (gtsam::Key source_t0_key, gtsam::Key source_t1_key, const std::shared_ptr< const TargetFrame > &target, const std::shared_ptr< const SourceFrame > &source, const std::shared_ptr< const NearestNeighborSearch > &target_tree) | |
| Constructor. | |
| IntegratedCT_GICPFactor_ (gtsam::Key source_t0_key, gtsam::Key source_t1_key, const std::shared_ptr< const TargetFrame > &target, const std::shared_ptr< const SourceFrame > &source) | |
| Constructor. | |
| 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 |
| virtual double | error (const gtsam::Values &values) const override |
| virtual gtsam::GaussianFactor::shared_ptr | linearize (const gtsam::Values &values) const override |
Public Member Functions inherited from gtsam_points::IntegratedCT_ICPFactor_< TargetFrame, SourceFrame > | |
| IntegratedCT_ICPFactor_ (gtsam::Key source_t0_key, gtsam::Key source_t1_key, const std::shared_ptr< const TargetFrame > &target, const std::shared_ptr< const SourceFrame > &source, const std::shared_ptr< const NearestNeighborSearch > &target_tree) | |
| Constructor. | |
| IntegratedCT_ICPFactor_ (gtsam::Key source_t0_key, gtsam::Key source_t1_key, const std::shared_ptr< const TargetFrame > &target, const std::shared_ptr< const SourceFrame > &source) | |
| Constructor. | |
| virtual size_t | dim () const override |
| void | set_num_threads (int n) |
| void | set_max_correspondence_distance (double dist) |
| const std::vector< double > & | get_time_table () const |
| const std::vector< int > & | get_time_indices () const |
| const std::vector< gtsam::Pose3 > & | get_source_poses () const |
| std::vector< Eigen::Vector4d > | deskewed_source_points (const gtsam::Values &values, bool local=false) |
| virtual void | update_poses (const gtsam::Values &values) const |
Protected Member Functions | |
| virtual void | update_correspondences () const override |
Protected Attributes | |
| std::vector< Eigen::Matrix4d > | mahalanobis |
Protected Attributes inherited from gtsam_points::IntegratedCT_ICPFactor_< TargetFrame, SourceFrame > | |
| int | num_threads |
| double | max_correspondence_distance_sq |
| std::shared_ptr< const NearestNeighborSearch > | target_tree |
| std::vector< double > | time_table |
| std::vector< gtsam::Pose3 > | source_poses |
| std::vector< gtsam::Matrix6 > | pose_derivatives_t0 |
| std::vector< gtsam::Matrix6 > | pose_derivatives_t1 |
| std::vector< int > | time_indices |
| std::vector< long > | correspondences |
| std::shared_ptr< const TargetFrame > | target |
| std::shared_ptr< const SourceFrame > | source |
Continuous Time ICP with GICP's D2D cost Bellenbach et al., "CT-ICP: Real-time Elastic LiDAR Odometry with Loop Closure", 2021 Segal et al., "Generalized-ICP", RSS2005.
| gtsam_points::IntegratedCT_GICPFactor_< TargetFrame, SourceFrame >::IntegratedCT_GICPFactor_ | ( | gtsam::Key | source_t0_key, |
| gtsam::Key | source_t1_key, | ||
| const std::shared_ptr< const TargetFrame > & | target, | ||
| const std::shared_ptr< const SourceFrame > & | source, | ||
| const std::shared_ptr< const NearestNeighborSearch > & | target_tree | ||
| ) |
Constructor.
| source_t0_key | Key of the source pose at the beginning of the scan |
| source_t1_key | Key of the source pose at the end of the scan |
| target | Target point cloud |
| source | Source point cloud |
| target_tree | NN search for the target point cloud |
| gtsam_points::IntegratedCT_GICPFactor_< TargetFrame, SourceFrame >::IntegratedCT_GICPFactor_ | ( | gtsam::Key | source_t0_key, |
| gtsam::Key | source_t1_key, | ||
| const std::shared_ptr< const TargetFrame > & | target, | ||
| const std::shared_ptr< const SourceFrame > & | source | ||
| ) |
Constructor.
| source_t0_key | Key of the source pose at the beginning of the scan |
| source_t1_key | Key of the source pose at the end of the scan |
| target | Target point cloud |
| source | Source point cloud |
|
overridevirtual |
Reimplemented from gtsam_points::IntegratedCT_ICPFactor_< TargetFrame, SourceFrame >.
|
overridevirtual |
Reimplemented from gtsam_points::IntegratedCT_ICPFactor_< TargetFrame, SourceFrame >.
|
overridevirtual |
Reimplemented from gtsam_points::IntegratedCT_ICPFactor_< TargetFrame, SourceFrame >.
|
overridevirtual |
Print the factor information.
Reimplemented from gtsam_points::IntegratedCT_ICPFactor_< TargetFrame, SourceFrame >.
|
overrideprotectedvirtual |
Reimplemented from gtsam_points::IntegratedCT_ICPFactor_< TargetFrame, SourceFrame >.