|
gtsam_points
|
Bundle adjustment factor based on EVM and EF optimal condition satisfaction. More...
#include <bundle_adjustment_factor_lsq.hpp>


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. | |
Bundle adjustment factor based on EVM and EF optimal condition satisfaction.
Huang et al, "On Bundle Adjustment for Multiview Point Cloud Registration", IEEE RA-L, 2021
|
overridevirtual |
Assign a point to the factor.
| pt | Point |
| key | Key of the frame corresponding to the point |
Implements gtsam_points::BundleAdjustmentFactorBase.
|
inlineoverridevirtual |
Number of points assigned to the factor.
Implements gtsam_points::BundleAdjustmentFactorBase.