Go to the documentation of this file.
39 size_t expectedNumberCameras = 10)
Base class to create smart factors on poses or cameras.
Pose3 body_P_sensor() const
double error(const Values &values) const override
SmartFactorBase< PinholeCamera< Cal3Bundler > > Base
std::shared_ptr< GaussianFactor > linearize(const Values &values) const override
Base class for all pinhole cameras.
noiseModel::Base::shared_ptr SharedNoiseModel
Base class for smart factors. This base class has no internal point, but it has a measurement,...
Calibration used by Bundler.
PinholeFactor(const SharedNoiseModel &sharedNoiseModel, std::optional< Pose3 > body_P_sensor={}, size_t expectedNumberCameras=10)
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:03:34