Public Types | Public Member Functions | List of all members
gtsam::PinholeFactor Class Reference

#include <PinholeFactor.h>

Inheritance diagram for gtsam::PinholeFactor:
Inheritance graph
[legend]

Public Types

typedef SmartFactorBase< PinholeCamera< Cal3Bundler > > Base
 
- Public Types inherited from gtsam::SmartFactorBase< PinholeCamera< Cal3Bundler > >
typedef CameraSet< PinholeCamera< Cal3Bundler > > Cameras
 The CameraSet data structure is used to refer to a set of cameras. More...
 
typedef std::vector< MatrixZD, Eigen::aligned_allocator< MatrixZD > > FBlocks
 
typedef Eigen::Matrix< double, ZDim, DimMatrixZD
 
- Public Types inherited from gtsam::NonlinearFactor
typedef std::shared_ptr< Thisshared_ptr
 
- Public Types inherited from gtsam::Factor
typedef KeyVector::const_iterator const_iterator
 Const iterator over keys. More...
 
typedef KeyVector::iterator iterator
 Iterator over keys. More...
 

Public Member Functions

double error (const Values &values) const override
 
std::shared_ptr< GaussianFactorlinearize (const Values &values) const override
 
 PinholeFactor ()
 
 PinholeFactor (const SharedNoiseModel &sharedNoiseModel, std::optional< Pose3 > body_P_sensor={}, size_t expectedNumberCameras=10)
 
- Public Member Functions inherited from gtsam::SmartFactorBase< PinholeCamera< Cal3Bundler > >
void add (const Z &measured, const Key &key)
 
void add (const ZVector &measurements, const KeyVector &cameraKeys)
 Add a bunch of measurements, together with the camera keys. More...
 
void add (const SFM_TRACK &trackToAdd)
 
Pose3 body_P_sensor () const
 
virtual Cameras cameras (const Values &values) const
 Collect all cameras: important that in key order. More...
 
void computeJacobians (FBlocks &Fs, Matrix &E, Vector &b, const Cameras &cameras, const POINT &point) const
 
void computeJacobiansSVD (FBlocks &Fs, Matrix &Enull, Vector &b, const Cameras &cameras, const POINT &point) const
 
virtual void correctForMissingMeasurements (const Cameras &cameras, Vector &ue, typename Cameras::FBlocks *Fs=nullptr, Matrix *E=nullptr) const
 
void correctForMissingMeasurements (const Cameras &cameras, Vector &ue, OptArgs &&... optArgs) const
 
std::shared_ptr< RegularHessianFactor< Dim > > createHessianFactor (const Cameras &cameras, const Point3 &point, const double lambda=0.0, bool diagonalDamping=false) const
 Linearize to a Hessianfactor. More...
 
std::shared_ptr< JacobianFactorQ< Dim, ZDim > > createJacobianQFactor (const Cameras &cameras, const Point3 &point, double lambda=0.0, bool diagonalDamping=false) const
 Return Jacobians as JacobianFactorQ. More...
 
std::shared_ptr< JacobianFactorcreateJacobianSVDFactor (const Cameras &cameras, const Point3 &point, double lambda=0.0) const
 
std::shared_ptr< RegularImplicitSchurFactor< PinholeCamera< Cal3Bundler > > > createRegularImplicitSchurFactor (const Cameras &cameras, const Point3 &point, double lambda=0.0, bool diagonalDamping=false) const
 Return Jacobians as RegularImplicitSchurFactor with raw access. More...
 
size_t dim () const override
 Return the dimension (number of rows!) of the factor. More...
 
bool equals (const NonlinearFactor &p, double tol=1e-9) const override
 equals More...
 
const ZVectormeasured () const
 Return the 2D measurements (ZDim, in general). More...
 
void print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
 
 SmartFactorBase ()
 Default Constructor, for serialization. More...
 
 SmartFactorBase (const SharedNoiseModel &sharedNoiseModel, std::optional< Pose3 > body_P_sensor={}, size_t expectedNumberCameras=10)
 Construct with given noise model and optional arguments. More...
 
double totalReprojectionError (const Cameras &cameras, const POINT &point) const
 
Vector unwhitenedError (const Cameras &cameras, const POINT &point, typename Cameras::FBlocks *Fs=nullptr, Matrix *E=nullptr) const
 
Vector unwhitenedError (const Cameras &cameras, const POINT &point, OptArgs &&... optArgs) const
 
void updateAugmentedHessian (const Cameras &cameras, const Point3 &point, const double lambda, bool diagonalDamping, SymmetricBlockMatrix &augmentedHessian, const KeyVector allKeys) const
 
Vector whitenedError (const Cameras &cameras, const POINT &point) const
 
void whitenJacobians (FBlocks &F, Matrix &E, Vector &b) const
 Whiten the Jacobians computed by computeJacobians using noiseModel_. More...
 
 ~SmartFactorBase () override
 Virtual destructor, subclasses from NonlinearFactor. More...
 
- Public Member Functions inherited from gtsam::NonlinearFactor
 NonlinearFactor ()
 
template<typename CONTAINER >
 NonlinearFactor (const CONTAINER &keys)
 
double error (const HybridValues &c) const override
 
virtual bool active (const Values &) const
 
virtual shared_ptr clone () const
 
virtual shared_ptr rekey (const std::map< Key, Key > &rekey_mapping) const
 
virtual shared_ptr rekey (const KeyVector &new_keys) const
 
virtual bool sendable () const
 
- Public Member Functions inherited from gtsam::Factor
virtual ~Factor ()=default
 Default destructor. More...
 
bool empty () const
 Whether the factor is empty (involves zero variables). More...
 
Key front () const
 First key. More...
 
Key back () const
 Last key. More...
 
const_iterator find (Key key) const
 find More...
 
const KeyVectorkeys () const
 Access the factor's involved variable keys. More...
 
const_iterator begin () const
 
const_iterator end () const
 
size_t size () const
 
virtual void printKeys (const std::string &s="Factor", const KeyFormatter &formatter=DefaultKeyFormatter) const
 print only keys More...
 
bool equals (const This &other, double tol=1e-9) const
 check equality More...
 
KeyVectorkeys ()
 
iterator begin ()
 
iterator end ()
 

Additional Inherited Members

- Static Public Member Functions inherited from gtsam::SmartFactorBase< PinholeCamera< Cal3Bundler > >
static void FillDiagonalF (const FBlocks &Fs, Matrix &F)
 Create BIG block-diagonal matrix F from Fblocks. More...
 
static Matrix PointCov (const Matrix &E)
 Computes Point Covariance P from the "point Jacobian" E. More...
 
- Public Attributes inherited from gtsam::SmartFactorBase< PinholeCamera< Cal3Bundler > >
GTSAM_MAKE_ALIGNED_OPERATOR_NEW typedef std::shared_ptr< Thisshared_ptr
 shorthand for a smart pointer to a factor. More...
 
- Static Public Attributes inherited from gtsam::SmartFactorBase< PinholeCamera< Cal3Bundler > >
static const int Dim
 Camera dimension. More...
 
static const int ZDim
 Measurement dimension. More...
 
- Protected Types inherited from gtsam::NonlinearFactor
typedef Factor Base
 
typedef NonlinearFactor This
 
- Protected Member Functions inherited from gtsam::Factor
 Factor ()
 
template<typename CONTAINER >
 Factor (const CONTAINER &keys)
 
template<typename ITERATOR >
 Factor (ITERATOR first, ITERATOR last)
 
- Static Protected Member Functions inherited from gtsam::Factor
template<typename CONTAINER >
static Factor FromKeys (const CONTAINER &keys)
 
template<typename ITERATOR >
static Factor FromIterators (ITERATOR first, ITERATOR last)
 
- Protected Attributes inherited from gtsam::SmartFactorBase< PinholeCamera< Cal3Bundler > >
std::optional< Pose3body_P_sensor_
 Pose of the camera in the body frame. More...
 
FBlocks Fs
 
ZVector measured_
 
SharedIsotropic noiseModel_
 
- Protected Attributes inherited from gtsam::Factor
KeyVector keys_
 The keys involved in this factor. More...
 

Detailed Description

Definition at line 33 of file PinholeFactor.h.

Member Typedef Documentation

◆ Base

Definition at line 35 of file PinholeFactor.h.

Constructor & Destructor Documentation

◆ PinholeFactor() [1/2]

gtsam::PinholeFactor::PinholeFactor ( )
inline

Definition at line 36 of file PinholeFactor.h.

◆ PinholeFactor() [2/2]

gtsam::PinholeFactor::PinholeFactor ( const SharedNoiseModel sharedNoiseModel,
std::optional< Pose3 body_P_sensor = {},
size_t  expectedNumberCameras = 10 
)
inline

Definition at line 37 of file PinholeFactor.h.

Member Function Documentation

◆ error()

double gtsam::PinholeFactor::error ( const Values values) const
inlineoverridevirtual

Reimplemented from gtsam::NonlinearFactor.

Definition at line 41 of file PinholeFactor.h.

◆ linearize()

std::shared_ptr<GaussianFactor> gtsam::PinholeFactor::linearize ( const Values c) const
inlineoverridevirtual

linearize to a GaussianFactor

Implements gtsam::NonlinearFactor.

Definition at line 42 of file PinholeFactor.h.


The documentation for this class was generated from the following file:


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:47:06