gtsam::NoiseModelFactor gtsam::NonlinearFactor gtsam::NoiseModelFactor1< VALUE > gtsam::NoiseModelFactor2< VALUE1, VALUE2 > gtsam::NoiseModelFactor3< VALUE1, VALUE2, VALUE3 > gtsam::NoiseModelFactor4< VALUE1, VALUE2, VALUE3, VALUE4 > gtsam::NoiseModelFactor5< VALUE1, VALUE2, VALUE3, VALUE4, VALUE5 > gtsam::NoiseModelFactor6< VALUE1, VALUE2, VALUE3, VALUE4, VALUE5, VALUE6 > NonlinearFactor.h NonlinearFactor typedef NonlinearFactor gtsam::NoiseModelFactor::Base Base NoiseModelFactor typedef NoiseModelFactor gtsam::NoiseModelFactor::This This std::shared_ptr< This > typedef std::shared_ptr<This> gtsam::NoiseModelFactor::shared_ptr shared_ptr Noise model SharedNoiseModel SharedNoiseModel gtsam::NoiseModelFactor::noiseModel_ noiseModel_ friend class friend class boost::serialization::access boost::serialization::access Serialization function gtsam::NoiseModelFactor::NoiseModelFactor () NoiseModelFactor Default constructor for I/O only virtual gtsam::NoiseModelFactor::~NoiseModelFactor () ~NoiseModelFactor Destructor typename CONTAINER gtsam::NoiseModelFactor::NoiseModelFactor (const SharedNoiseModel &noiseModel, const CONTAINER &keys) NoiseModelFactor const SharedNoiseModel & noiseModel const CONTAINER & keys Constructor void virtual void gtsam::NoiseModelFactor::print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const print print const std::string & s "" const KeyFormatter & keyFormatter DefaultKeyFormatter Print bool virtual bool gtsam::NoiseModelFactor::equals (const NonlinearFactor &f, double tol=1e-9) const equals equals const NonlinearFactor & f double tol 1e-9 Check if two factors are equal size_t virtual size_t gtsam::NoiseModelFactor::dim () const dim dim get the dimension of the factor (number of rows on linearization) const SharedNoiseModel & const SharedNoiseModel& gtsam::NoiseModelFactor::noiseModel () const noiseModel access to the noise model SharedNoiseModel SharedNoiseModel gtsam::NoiseModelFactor::get_noiseModel () const get_noiseModel Deprecatedaccess to the noise model Vector virtual Vector gtsam::NoiseModelFactor::unwhitenedError (const Values &x, boost::optional< std::vector< Matrix > & > H=boost::none) const =0 unwhitenedError unwhitenedError unwhitenedError unwhitenedError unwhitenedError unwhitenedError unwhitenedError const Values & x boost::optional< std::vector< Matrix > & > H boost::none Error function without the NoiseModel, $ z-h(x) $. Override this method to finish implementing an N-way factor. If the optional arguments is specified, it should compute both the function evaluation and its derivative(s) in H. Vector Vector gtsam::NoiseModelFactor::whitenedError (const Values &c) const whitenedError const Values & c Vector of errors, whitened This is the raw error, i.e., i.e. $ (h(x)-z)/\sigma $ in case of a Gaussian double virtual double gtsam::NoiseModelFactor::error (const Values &c) const error error const Values & c Calculate the error of the factor. This is the log-likelihood, e.g. $ 0.5(h(x)-z)^2/\sigma^2 $ in case of Gaussian. In this class, we take the raw prediction error $ h(x)-z $, ask the noise model to transform it to $ (h(x)-z)^2/\sigma^2 $, and then multiply by 0.5. std::shared_ptr< GaussianFactor > std::shared_ptr<GaussianFactor> gtsam::NoiseModelFactor::linearize (const Values &x) const linearize linearize const Values & x Linearize a non-linearFactorN to get a GaussianFactor, $ Ax-b \approx h(x+\delta x)-z = h(x) + A \delta x - z $ Hence $ b = z - h(x) = - \mathtt{error\_vector}(x) $ gtsam::NoiseModelFactor::NoiseModelFactor (const SharedNoiseModel &noiseModel) NoiseModelFactor const SharedNoiseModel & noiseModel Constructor - only for subclasses, as this does not set keys. class ARCHIVE void void gtsam::NoiseModelFactor::serialize (ARCHIVE &ar, const unsigned int) serialize ARCHIVE & ar const unsigned int A nonlinear sum-of-squares factor with a zero-mean noise model implementing the density $ P(z|x) \propto exp -0.5*|z-h(x)|^2_C $ Templated on the parameter type X and the values structure Values There is no return type specified for h(x). Instead, we require the derived class implements $ \mathtt{error\_vector}(x) = h(x)-z \approx A \delta x - b $ This allows a graph to have factors with measurements of mixed type.The noise model is typically Gaussian, but robust and constrained error models are also supported. gtsam::NoiseModelFactoractive gtsam::NoiseModelFactorBase gtsam::NoiseModelFactorboost::serialization::access gtsam::NoiseModelFactorclone gtsam::NoiseModelFactordim gtsam::NoiseModelFactorequals gtsam::NoiseModelFactorerror gtsam::NoiseModelFactorget_noiseModel gtsam::NoiseModelFactorlinearize gtsam::NoiseModelFactornoiseModel gtsam::NoiseModelFactornoiseModel_ gtsam::NoiseModelFactorNoiseModelFactor gtsam::NoiseModelFactorNoiseModelFactor gtsam::NoiseModelFactorNoiseModelFactor gtsam::NoiseModelFactorNonlinearFactor gtsam::NoiseModelFactorNonlinearFactor gtsam::NoiseModelFactorprint gtsam::NoiseModelFactorrekey gtsam::NoiseModelFactorrekey gtsam::NoiseModelFactorserialize gtsam::NoiseModelFactorshared_ptr gtsam::NoiseModelFactorThis gtsam::NoiseModelFactorunwhitenedError gtsam::NoiseModelFactorwhitenedError gtsam::NoiseModelFactor~NoiseModelFactor gtsam::NoiseModelFactor~NonlinearFactor