|
gtsam_points
|
Bundle adjustment factor based on Eigenvalue minimization One EVMFactor represents one feature (plane / edge) More...
#include <bundle_adjustment_factor_evm.hpp>


Public Types | |
| using | shared_ptr = gtsam_points::shared_ptr< EVMBundleAdjustmentFactorBase > |
Public Types inherited from gtsam_points::BundleAdjustmentFactorBase | |
| using | shared_ptr = gtsam_points::shared_ptr< BundleAdjustmentFactorBase > |
Public Member Functions | |
| 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 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 this factor. | |
| virtual void | set_scale (double scale) override |
| Set a constant error scaling factor to boost the weight of the factor. | |
Protected Attributes | |
| double | error_scale |
| std::vector< gtsam::Key > | keys |
| std::vector< gtsam::Point3 > | points |
| std::unordered_map< gtsam::Key, int > | key_index |
Bundle adjustment factor based on Eigenvalue minimization One EVMFactor represents one feature (plane / edge)
Liu and Zhang, "BALM: Bundle Adjustment for Lidar Mapping", IEEE RA-L, 2021
|
overridevirtual |
Assign a point to the factor.
| pt | Point to be added |
| key | Key of the pose corresponding to the point |
Implements gtsam_points::BundleAdjustmentFactorBase.
|
inlineoverridevirtual |
Number of points assigned to this factor.
Implements gtsam_points::BundleAdjustmentFactorBase.
|
overridevirtual |
Print the factor information.
Reimplemented in gtsam_points::PlaneEVMFactor, and gtsam_points::EdgeEVMFactor.
|
overridevirtual |
Set a constant error scaling factor to boost the weight of the factor.
| scale | Error scale |
Reimplemented from gtsam_points::BundleAdjustmentFactorBase.