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

Bundle adjustment factor based on EVM and EF optimal condition satisfaction. More...

#include <bundle_adjustment_factor_lsq.hpp>

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

Public Types

using shared_ptr = gtsam_points::shared_ptr< LsqBundleAdjustmentFactor >
 
- Public Types inherited from gtsam_points::BundleAdjustmentFactorBase
using shared_ptr = gtsam_points::shared_ptr< BundleAdjustmentFactorBase >
 

Public Member Functions

virtual void print (const std::string &s="", const gtsam::KeyFormatter &keyFormatter=gtsam::DefaultKeyFormatter) const override
 Print the factor information.
 
virtual size_t dim () const override
 
virtual double error (const gtsam::Values &c) const override
 
virtual gtsam::GaussianFactor::shared_ptr linearize (const gtsam::Values &c) const override
 
virtual void add (const gtsam::Point3 &pt, const gtsam::Key &key) override
 Assign a point to the factor.
 
virtual int num_points () const override
 Number of points assigned to the factor.
 
- Public Member Functions inherited from gtsam_points::BundleAdjustmentFactorBase
virtual void set_scale (double scale)
 Set a constant error scale to boost the weight of the constraint.
 

Protected Attributes

std::unordered_map< gtsam::Key, std::shared_ptr< FrameDistribution > > frame_dists
 
int global_num_points
 
Eigen::Vector3d global_mean
 
Eigen::Matrix3d global_cov
 
Eigen::Vector3d global_normal
 

Detailed Description

Bundle adjustment factor based on EVM and EF optimal condition satisfaction.

Note
The evaluation cost of this factor depends on the number of frames and is independent of the number of points
This factor requires a better initial guess compared to EVM-based one because the global normal not included in the optimization

Huang et al, "On Bundle Adjustment for Multiview Point Cloud Registration", IEEE RA-L, 2021

Member Function Documentation

◆ add()

virtual void gtsam_points::LsqBundleAdjustmentFactor::add ( const gtsam::Point3 &  pt,
const gtsam::Key &  key 
)
overridevirtual

Assign a point to the factor.

Parameters
ptPoint
keyKey of the frame corresponding to the point

Implements gtsam_points::BundleAdjustmentFactorBase.

◆ num_points()

virtual int gtsam_points::LsqBundleAdjustmentFactor::num_points ( ) const
inlineoverridevirtual

Number of points assigned to the factor.

Returns
Number of points

Implements gtsam_points::BundleAdjustmentFactorBase.


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