gtsam_points
Loading...
Searching...
No Matches
Public Types | Public Member Functions | Protected Attributes | List of all members
gtsam_points::IntegratedMatchingCostFactor Class Referenceabstract

Abstraction of LSQ-based scan matching constraints between point clouds. More...

#include <integrated_matching_cost_factor.hpp>

Inheritance diagram for gtsam_points::IntegratedMatchingCostFactor:
Inheritance graph
[legend]
Collaboration diagram for gtsam_points::IntegratedMatchingCostFactor:
Collaboration graph
[legend]

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
 

Detailed Description

Abstraction of LSQ-based scan matching constraints between point clouds.

Constructor & Destructor Documentation

◆ IntegratedMatchingCostFactor() [1/2]

gtsam_points::IntegratedMatchingCostFactor::IntegratedMatchingCostFactor ( gtsam::Key  target_key,
gtsam::Key  source_key 
)

Create a binary matching cost factor between target and source poses.

Parameters
target_keyTarget key
source_keySource key

◆ IntegratedMatchingCostFactor() [2/2]

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.

Parameters
fixed_target_poseFixed target pose
source_keySource key

Member Function Documentation

◆ error()

virtual double gtsam_points::IntegratedMatchingCostFactor::error ( const gtsam::Values &  values) const
overridevirtual
Note
The following error and linearize methods are not thread-safe, because we need to update correspondences (that may be mutable members) for every linearization

◆ evaluate()

virtual double gtsam_points::IntegratedMatchingCostFactor::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
pure virtual

Evaluate the matching cost.

Parameters
deltaTransformation between target and source (i.e., T_target_source)
H_targetHessian (target x target)
H_sourceHessian (source x source)
H_target_sourceHessian (target x source)
b_targetError vector (target)
b_sourceError vector (source)

◆ memory_usage()

virtual size_t gtsam_points::IntegratedMatchingCostFactor::memory_usage ( ) const
virtual

◆ print()

virtual void gtsam_points::IntegratedMatchingCostFactor::print ( const std::string &  s = "",
const gtsam::KeyFormatter &  keyFormatter = gtsam::DefaultKeyFormatter 
) const
overridevirtual

◆ update_correspondences()

virtual void gtsam_points::IntegratedMatchingCostFactor::update_correspondences ( const Eigen::Isometry3d &  delta) const
pure virtual

Update point correspondences.

Parameters
deltaTransformation between target and source (i.e., T_target_source)

The documentation for this class was generated from the following file: