|
gtsam_points
|
Abstraction of LSQ-based scan matching constraints between point clouds. More...
#include <integrated_matching_cost_factor.hpp>


Public Types | |
| using | shared_ptr = gtsam_points::shared_ptr< IntegratedMatchingCostFactor > |
Public Member Functions | |
| 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 void | print (const std::string &s="", const gtsam::KeyFormatter &keyFormatter=gtsam::DefaultKeyFormatter) const override |
| Print the factor information. | |
| 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 |
| virtual size_t | memory_usage () const |
| Calculate the memory usage of this factor. | |
| virtual void | update_correspondences (const Eigen::Isometry3d &delta) const =0 |
| Update point correspondences. | |
| virtual double | evaluate (const Eigen::Isometry3d &delta, Eigen::Matrix< double, 6, 6 > *H_target=nullptr, Eigen::Matrix< double, 6, 6 > *H_source=nullptr, Eigen::Matrix< double, 6, 6 > *H_target_source=nullptr, Eigen::Matrix< double, 6, 1 > *b_target=nullptr, Eigen::Matrix< double, 6, 1 > *b_source=nullptr) const =0 |
| Evaluate the matching cost. | |
Protected Attributes | |
| bool | is_binary |
| Eigen::Isometry3d | fixed_target_pose |
Abstraction of LSQ-based scan matching constraints between point clouds.
| gtsam_points::IntegratedMatchingCostFactor::IntegratedMatchingCostFactor | ( | gtsam::Key | target_key, |
| gtsam::Key | source_key | ||
| ) |
Create a binary matching cost factor between target and source poses.
| target_key | Target key |
| source_key | Source key |
| gtsam_points::IntegratedMatchingCostFactor::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.
| fixed_target_pose | Fixed target pose |
| source_key | Source key |
|
overridevirtual |
|
pure virtual |
Evaluate the matching cost.
| delta | Transformation between target and source (i.e., T_target_source) |
| H_target | Hessian (target x target) |
| H_source | Hessian (source x source) |
| H_target_source | Hessian (target x source) |
| b_target | Error vector (target) |
| b_source | Error vector (source) |
|
virtual |
Calculate the memory usage of this factor.
Reimplemented in gtsam_points::IntegratedColorConsistencyFactor_< TargetFrame, SourceFrame, IntensityGradients >, gtsam_points::IntegratedColoredGICPFactor_< TargetFrame, SourceFrame, IntensityGradients >, gtsam_points::IntegratedGICPFactor_< TargetFrame, SourceFrame >, gtsam_points::IntegratedICPFactor_< TargetFrame, SourceFrame >, gtsam_points::IntegratedICPFactor_< gtsam_points::PointCloud, gtsam_points::PointCloud >, gtsam_points::IntegratedLOAMFactor_< TargetFrame, SourceFrame >, gtsam_points::IntegratedPointToPlaneFactor_< TargetFrame, SourceFrame >, gtsam_points::IntegratedPointToEdgeFactor_< TargetFrame, SourceFrame >, and gtsam_points::IntegratedVGICPFactor_< SourceFrame >.
|
overridevirtual |
Print the factor information.
Reimplemented in gtsam_points::IntegratedColorConsistencyFactor_< TargetFrame, SourceFrame, IntensityGradients >, gtsam_points::IntegratedColoredGICPFactor_< TargetFrame, SourceFrame, IntensityGradients >, gtsam_points::IntegratedGICPFactor_< TargetFrame, SourceFrame >, gtsam_points::IntegratedICPFactor_< TargetFrame, SourceFrame >, gtsam_points::IntegratedICPFactor_< gtsam_points::PointCloud, gtsam_points::PointCloud >, gtsam_points::IntegratedLOAMFactor_< TargetFrame, SourceFrame >, gtsam_points::IntegratedPointToPlaneFactor_< TargetFrame, SourceFrame >, gtsam_points::IntegratedPointToEdgeFactor_< TargetFrame, SourceFrame >, and gtsam_points::IntegratedVGICPFactor_< SourceFrame >.
|
pure virtual |
Update point correspondences.
| delta | Transformation between target and source (i.e., T_target_source) |