6#include <gtsam/geometry/Point3.h>
7#include <gtsam/nonlinear/NonlinearFactor.h>
8#include <gtsam_points/util/gtsam_migration.hpp>
10namespace gtsam_points {
17 using shared_ptr = gtsam_points::shared_ptr<BundleAdjustmentFactorBase>;
26 virtual void add(
const gtsam::Point3& pt,
const gtsam::Key& key) = 0;
Base class of range-based bundle adjustment factors.
Definition bundle_adjustment_factor.hpp:15
virtual void add(const gtsam::Point3 &pt, const gtsam::Key &key)=0
Assign a point to the factor.
virtual void set_scale(double scale)
Set a constant error scale to boost the weight of the constraint.
Definition bundle_adjustment_factor.hpp:37
virtual int num_points() const =0
Number of points assigned to the factor.