|
gtsam_points
|
Base class of range-based bundle adjustment factors. More...
#include <bundle_adjustment_factor.hpp>


Public Types | |
| using | shared_ptr = gtsam_points::shared_ptr< BundleAdjustmentFactorBase > |
Public Member Functions | |
| virtual void | add (const gtsam::Point3 &pt, const gtsam::Key &key)=0 |
| Assign a point to the factor. | |
| virtual int | num_points () const =0 |
| Number of points assigned to the factor. | |
| virtual void | set_scale (double scale) |
| Set a constant error scale to boost the weight of the constraint. | |
Base class of range-based bundle adjustment factors.
|
pure virtual |
Assign a point to the factor.
| pt | Point |
| key | Key of the frame corresponding to the point |
Implemented in gtsam_points::EVMBundleAdjustmentFactorBase, and gtsam_points::LsqBundleAdjustmentFactor.
|
pure virtual |
Number of points assigned to the factor.
Implemented in gtsam_points::EVMBundleAdjustmentFactorBase, and gtsam_points::LsqBundleAdjustmentFactor.
|
inlinevirtual |
Set a constant error scale to boost the weight of the constraint.
Reimplemented in gtsam_points::EVMBundleAdjustmentFactorBase.