Continuous Time ICP Factor Bellenbach et al., "CT-ICP: Real-time Elastic LiDAR Odometry with Loop Closure", 2021.
More...
#include <integrated_ct_icp_factor.hpp>
|
| | 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 void | print (const std::string &s="", const gtsam::KeyFormatter &keyFormatter=gtsam::DefaultKeyFormatter) const override |
| | Print the factor information.
|
| |
|
virtual size_t | memory_usage () const |
| |
|
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 |
| |
|
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 |
| |
|
|
virtual void | update_correspondences () const |
| |
|
|
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 |
| |
template<typename TargetFrame = gtsam_points::PointCloud, typename SourceFrame = gtsam_points::PointCloud>
class gtsam_points::IntegratedCT_ICPFactor_< TargetFrame, SourceFrame >
Continuous Time ICP Factor Bellenbach et al., "CT-ICP: Real-time Elastic LiDAR Odometry with Loop Closure", 2021.
◆ IntegratedCT_ICPFactor_() [1/2]
template<typename TargetFrame , typename SourceFrame >
| 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.
- Parameters
-
| 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 |
◆ IntegratedCT_ICPFactor_() [2/2]
template<typename TargetFrame , typename SourceFrame >
| 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 |
|
) |
| |
Constructor.
- Parameters
-
| 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 |
◆ print()
template<typename TargetFrame , typename SourceFrame >
| void gtsam_points::IntegratedCT_ICPFactor_< TargetFrame, SourceFrame >::print |
( |
const std::string & |
s = "", |
|
|
const gtsam::KeyFormatter & |
keyFormatter = gtsam::DefaultKeyFormatter |
|
) |
| const |
|
overridevirtual |
The documentation for this class was generated from the following files: