gtsam 4.1.1
gtsam
gtsam::SmartProjectionFactor< CAMERA > Class Template Reference

Detailed Description

template<class CAMERA>
class gtsam::SmartProjectionFactor< CAMERA >

SmartProjectionFactor: triangulates point and keeps an estimate of it around.

This factor operates with monocular cameras, where a camera is expected to behave like PinholeCamera or PinholePose. This factor is intended to be used directly with PinholeCamera, which optimizes the camera pose and calibration. This also requires that values contains the involved cameras (instead of poses and calibrations separately). If the calibration is fixed use SmartProjectionPoseFactor instead!

+ Inheritance diagram for gtsam::SmartProjectionFactor< CAMERA >:

Public Member Functions

 SmartProjectionFactor ()
 Default constructor, only for serialization.
 
 SmartProjectionFactor (const SharedNoiseModel &sharedNoiseModel, const SmartProjectionParams &params=SmartProjectionParams())
 Constructor. More...
 
 ~SmartProjectionFactor () override
 Virtual destructor.
 
void print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
 print More...
 
bool equals (const NonlinearFactor &p, double tol=1e-9) const override
 equals More...
 
bool decideIfTriangulate (const Cameras &cameras) const
 Check if the new linearization point is the same as the one used for previous triangulation. More...
 
TriangulationResult triangulateSafe (const Cameras &cameras) const
 Call gtsam::triangulateSafe iff we need to re-triangulate. More...
 
bool triangulateForLinearize (const Cameras &cameras) const
 Possibly re-triangulate before calculating Jacobians. More...
 
boost::shared_ptr< RegularHessianFactor< Base::Dim > > createHessianFactor (const Cameras &cameras, const double lambda=0.0, bool diagonalDamping=false) const
 Create a Hessianfactor that is an approximation of error(p).
 
boost::shared_ptr< RegularImplicitSchurFactor< CAMERA > > createRegularImplicitSchurFactor (const Cameras &cameras, double lambda) const
 
boost::shared_ptr< JacobianFactorQ< Base::Dim, 2 > > createJacobianQFactor (const Cameras &cameras, double lambda) const
 Create JacobianFactorQ factor.
 
boost::shared_ptr< JacobianFactorQ< Base::Dim, 2 > > createJacobianQFactor (const Values &values, double lambda) const
 Create JacobianFactorQ factor, takes values.
 
boost::shared_ptr< JacobianFactorcreateJacobianSVDFactor (const Cameras &cameras, double lambda) const
 Different (faster) way to compute a JacobianFactorSVD factor.
 
virtual boost::shared_ptr< RegularHessianFactor< Base::Dim > > linearizeToHessian (const Values &values, double lambda=0.0) const
 Linearize to a Hessianfactor.
 
virtual boost::shared_ptr< RegularImplicitSchurFactor< CAMERA > > linearizeToImplicit (const Values &values, double lambda=0.0) const
 Linearize to an Implicit Schur factor.
 
virtual boost::shared_ptr< JacobianFactorQ< Base::Dim, 2 > > linearizeToJacobian (const Values &values, double lambda=0.0) const
 Linearize to a JacobianfactorQ.
 
boost::shared_ptr< GaussianFactorlinearizeDamped (const Cameras &cameras, const double lambda=0.0) const
 Linearize to Gaussian Factor. More...
 
boost::shared_ptr< GaussianFactorlinearizeDamped (const Values &values, const double lambda=0.0) const
 Linearize to Gaussian Factor. More...
 
boost::shared_ptr< GaussianFactorlinearize (const Values &values) const override
 linearize More...
 
bool triangulateAndComputeE (Matrix &E, const Cameras &cameras) const
 Triangulate and compute derivative of error with respect to point. More...
 
bool triangulateAndComputeE (Matrix &E, const Values &values) const
 Triangulate and compute derivative of error with respect to point. More...
 
void computeJacobiansWithTriangulatedPoint (typename Base::FBlocks &Fs, Matrix &E, Vector &b, const Cameras &cameras) const
 Compute F, E only (called below in both vanilla and SVD versions) Assumes the point has been computed Note E can be 2m*3 or 2m*2, in case point is degenerate.
 
bool triangulateAndComputeJacobians (typename Base::FBlocks &Fs, Matrix &E, Vector &b, const Values &values) const
 Version that takes values, and creates the point.
 
bool triangulateAndComputeJacobiansSVD (typename Base::FBlocks &Fs, Matrix &Enull, Vector &b, const Values &values) const
 takes values
 
Vector reprojectionErrorAfterTriangulation (const Values &values) const
 Calculate vector of re-projection errors, before applying noise model.
 
double totalReprojectionError (const Cameras &cameras, boost::optional< Point3 > externalPoint=boost::none) const
 Calculate the error of the factor. More...
 
double error (const Values &values) const override
 Calculate total reprojection error. More...
 
TriangulationResult point () const
 return the landmark
 
TriangulationResult point (const Values &values) const
 COMPUTE the landmark.
 
bool isValid () const
 Is result valid?
 
bool isDegenerate () const
 return the degenerate state
 
bool isPointBehindCamera () const
 return the cheirality status flag
 
bool isOutlier () const
 return the outlier state
 
bool isFarPoint () const
 return the farPoint state
 
- Public Member Functions inherited from gtsam::SmartFactorBase< CAMERA >
 SmartFactorBase ()
 Default Constructor, for serialization.
 
 SmartFactorBase (const SharedNoiseModel &sharedNoiseModel, boost::optional< Pose3 > body_P_sensor=boost::none, size_t expectedNumberCameras=10)
 Construct with given noise model and optional arguments.
 
 ~SmartFactorBase () override
 Virtual destructor, subclasses from NonlinearFactor.
 
void add (const Z &measured, const Key &key)
 Add a new measurement and pose/camera key. More...
 
void add (const ZVector &measurements, const KeyVector &cameraKeys)
 Add a bunch of measurements, together with the camera keys.
 
template<class SFM_TRACK >
void add (const SFM_TRACK &trackToAdd)
 Add an entire SfM_track (collection of cameras observing a single point). More...
 
size_t dim () const override
 Return the dimension (number of rows!) of the factor. More...
 
const ZVector & measured () const
 Return the 2D measurements (ZDim, in general).
 
virtual Cameras cameras (const Values &values) const
 Collect all cameras: important that in key order. More...
 
void print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
 print More...
 
bool equals (const NonlinearFactor &p, double tol=1e-9) const override
 equals More...
 
template<class POINT >
Vector unwhitenedError (const Cameras &cameras, const POINT &point, boost::optional< typename Cameras::FBlocks & > Fs=boost::none, boost::optional< Matrix & > E=boost::none) const
 Compute reprojection errors [h(x)-z] = [cameras.project(p)-z] and derivatives. More...
 
virtual void correctForMissingMeasurements (const Cameras &cameras, Vector &ue, boost::optional< typename Cameras::FBlocks & > Fs=boost::none, boost::optional< Matrix & > E=boost::none) const
 This corrects the Jacobians for the case in which some 2D measurement is missing (nan). More...
 
template<class POINT >
Vector whitenedError (const Cameras &cameras, const POINT &point) const
 Calculate vector of re-projection errors [h(x)-z] = [cameras.project(p) - z], with the noise model applied.
 
template<class POINT >
double totalReprojectionError (const Cameras &cameras, const POINT &point) const
 Calculate the error of the factor. More...
 
template<class POINT >
void computeJacobians (FBlocks &Fs, Matrix &E, Vector &b, const Cameras &cameras, const POINT &point) const
 Compute F, E, and b (called below in both vanilla and SVD versions), where F is a vector of derivatives wrpt the cameras, and E the stacked derivatives with respect to the point. More...
 
template<class POINT >
void computeJacobiansSVD (FBlocks &Fs, Matrix &Enull, Vector &b, const Cameras &cameras, const POINT &point) const
 SVD version that produces smaller Jacobian matrices by doing an SVD decomposition on E, and returning the left nulkl-space of E. More...
 
boost::shared_ptr< RegularHessianFactor< Dim > > createHessianFactor (const Cameras &cameras, const Point3 &point, const double lambda=0.0, bool diagonalDamping=false) const
 Linearize to a Hessianfactor.
 
void updateAugmentedHessian (const Cameras &cameras, const Point3 &point, const double lambda, bool diagonalDamping, SymmetricBlockMatrix &augmentedHessian, const KeyVector allKeys) const
 Add the contribution of the smart factor to a pre-allocated Hessian, using sparse linear algebra. More...
 
void whitenJacobians (FBlocks &F, Matrix &E, Vector &b) const
 Whiten the Jacobians computed by computeJacobians using noiseModel_.
 
boost::shared_ptr< RegularImplicitSchurFactor< CAMERA > > createRegularImplicitSchurFactor (const Cameras &cameras, const Point3 &point, double lambda=0.0, bool diagonalDamping=false) const
 Return Jacobians as RegularImplicitSchurFactor with raw access.
 
boost::shared_ptr< JacobianFactorQ< Dim, ZDim > > createJacobianQFactor (const Cameras &cameras, const Point3 &point, double lambda=0.0, bool diagonalDamping=false) const
 Return Jacobians as JacobianFactorQ.
 
boost::shared_ptr< JacobianFactorcreateJacobianSVDFactor (const Cameras &cameras, const Point3 &point, double lambda=0.0) const
 Return Jacobians as JacobianFactorSVD. More...
 
Pose3 body_P_sensor () const
 
- Public Member Functions inherited from gtsam::NonlinearFactor
 NonlinearFactor ()
 Default constructor for I/O only.
 
template<typename CONTAINER >
 NonlinearFactor (const CONTAINER &keys)
 Constructor from a collection of the keys involved in this factor.
 
virtual ~NonlinearFactor ()
 Destructor.
 
virtual bool active (const Values &) const
 Checks whether a factor should be used based on a set of values. More...
 
virtual shared_ptr clone () const
 Creates a shared_ptr clone of the factor - needs to be specialized to allow for subclasses. More...
 
virtual shared_ptr rekey (const std::map< Key, Key > &rekey_mapping) const
 Creates a shared_ptr clone of the factor with different keys using a map from old->new keys. More...
 
virtual shared_ptr rekey (const KeyVector &new_keys) const
 Clones a factor and fully replaces its keys. More...
 
virtual bool sendable () const
 Should the factor be evaluated in the same thread as the caller This is to enable factors that has shared states (like the Python GIL lock) More...
 
- Public Member Functions inherited from gtsam::Factor
virtual ~Factor ()=default
 Default destructor.
 
KeyVectorkeys ()
 
iterator begin ()
 Iterator at beginning of involved variable keys.
 
iterator end ()
 Iterator at end of involved variable keys.
 
virtual void printKeys (const std::string &s="Factor", const KeyFormatter &formatter=DefaultKeyFormatter) const
 print only keys More...
 
Key front () const
 First key.
 
Key back () const
 Last key.
 
const_iterator find (Key key) const
 find
 
const KeyVectorkeys () const
 Access the factor's involved variable keys.
 
const_iterator begin () const
 Iterator at beginning of involved variable keys.
 
const_iterator end () const
 Iterator at end of involved variable keys.
 
size_t size () const
 

Public Types

typedef boost::shared_ptr< Thisshared_ptr
 shorthand for a smart pointer to a factor
 
typedef CAMERA Camera
 shorthand for a set of cameras
 
typedef CameraSet< CAMERA > Cameras
 
- Public Types inherited from gtsam::SmartFactorBase< CAMERA >
typedef Eigen::Matrix< double, ZDim, DimMatrixZD
 
typedef std::vector< MatrixZD, Eigen::aligned_allocator< MatrixZD > > FBlocks
 
typedef CameraSet< CAMERA > Cameras
 The CameraSet data structure is used to refer to a set of cameras.
 
- Public Types inherited from gtsam::NonlinearFactor
typedef boost::shared_ptr< Thisshared_ptr
 
- Public Types inherited from gtsam::Factor
typedef KeyVector::iterator iterator
 Iterator over keys.
 
typedef KeyVector::const_iterator const_iterator
 Const iterator over keys.
 

Protected Attributes

Parameters
SmartProjectionParams params_
 
Caching triangulation
TriangulationResult result_
 result from triangulateSafe
 
std::vector< Pose3, Eigen::aligned_allocator< Pose3 > > cameraPosesTriangulation_
 current triangulation poses
 
- Protected Attributes inherited from gtsam::SmartFactorBase< CAMERA >
SharedIsotropic noiseModel_
 As of Feb 22, 2015, the noise model is the same for all measurements and is isotropic. More...
 
ZVector measured_
 Measurements for each of the m views. More...
 
boost::optional< Pose3body_P_sensor_
 Pose of the camera in the body frame.
 
FBlocks Fs
 
- Protected Attributes inherited from gtsam::Factor
KeyVector keys_
 The keys involved in this factor.
 

Friends

class boost::serialization::access
 Serialization function.
 

Additional Inherited Members

- Static Public Member Functions inherited from gtsam::SmartFactorBase< CAMERA >
static Matrix PointCov (const Matrix &E)
 Computes Point Covariance P from the "point Jacobian" E.
 
static void FillDiagonalF (const FBlocks &Fs, Matrix &F)
 Create BIG block-diagonal matrix F from Fblocks.
 
- Public Attributes inherited from gtsam::SmartFactorBase< CAMERA >
GTSAM_MAKE_ALIGNED_OPERATOR_NEW typedef boost::shared_ptr< Thisshared_ptr
 shorthand for a smart pointer to a factor.
 
- Static Public Attributes inherited from gtsam::SmartFactorBase< CAMERA >
static const int Dim = traits<CAMERA>::dimension
 Camera dimension.
 
static const int ZDim = traits<Z>::dimension
 Measurement dimension.
 
- Protected Types inherited from gtsam::NonlinearFactor
typedef Factor Base
 
typedef NonlinearFactor This
 
- Protected Member Functions inherited from gtsam::Factor
 Factor ()
 Default constructor for I/O.
 
template<typename CONTAINER >
 Factor (const CONTAINER &keys)
 Construct factor from container of keys. More...
 
template<typename ITERATOR >
 Factor (ITERATOR first, ITERATOR last)
 Construct factor from iterator keys. More...
 
bool equals (const This &other, double tol=1e-9) const
 check equality
 
- Static Protected Member Functions inherited from gtsam::Factor
template<typename CONTAINER >
static Factor FromKeys (const CONTAINER &keys)
 Construct factor from container of keys. More...
 
template<typename ITERATOR >
static Factor FromIterators (ITERATOR first, ITERATOR last)
 Construct factor from iterator keys. More...
 

Constructor & Destructor Documentation

◆ SmartProjectionFactor()

template<class CAMERA >
gtsam::SmartProjectionFactor< CAMERA >::SmartProjectionFactor ( const SharedNoiseModel sharedNoiseModel,
const SmartProjectionParams params = SmartProjectionParams() 
)
inline

Constructor.

Parameters
sharedNoiseModelisotropic noise model for the 2D feature measurements
paramsparameters for the smart projection factors

Member Function Documentation

◆ decideIfTriangulate()

template<class CAMERA >
bool gtsam::SmartProjectionFactor< CAMERA >::decideIfTriangulate ( const Cameras cameras) const
inline

Check if the new linearization point is the same as the one used for previous triangulation.

Parameters
cameras
Returns
true if we need to re-triangulate.

◆ equals()

template<class CAMERA >
bool gtsam::SmartProjectionFactor< CAMERA >::equals ( const NonlinearFactor p,
double  tol = 1e-9 
) const
inlineoverridevirtual

◆ error()

template<class CAMERA >
double gtsam::SmartProjectionFactor< CAMERA >::error ( const Values values) const
inlineoverridevirtual

◆ linearize()

template<class CAMERA >
boost::shared_ptr< GaussianFactor > gtsam::SmartProjectionFactor< CAMERA >::linearize ( const Values values) const
inlineoverridevirtual

◆ linearizeDamped() [1/2]

template<class CAMERA >
boost::shared_ptr< GaussianFactor > gtsam::SmartProjectionFactor< CAMERA >::linearizeDamped ( const Cameras cameras,
const double  lambda = 0.0 
) const
inline

Linearize to Gaussian Factor.

Parameters
valuesValues structure which must contain camera poses for this factor
Returns
a Gaussian factor

◆ linearizeDamped() [2/2]

template<class CAMERA >
boost::shared_ptr< GaussianFactor > gtsam::SmartProjectionFactor< CAMERA >::linearizeDamped ( const Values values,
const double  lambda = 0.0 
) const
inline

Linearize to Gaussian Factor.

Parameters
valuesValues structure which must contain camera poses for this factor
Returns
a Gaussian factor

◆ print()

template<class CAMERA >
void gtsam::SmartProjectionFactor< CAMERA >::print ( const std::string &  s = "",
const KeyFormatter keyFormatter = DefaultKeyFormatter 
) const
inlineoverridevirtual

print

Parameters
soptional string naming the factor
keyFormatteroptional formatter useful for printing Symbols

Reimplemented from gtsam::SmartFactorBase< CAMERA >.

Reimplemented in gtsam::SmartProjectionRigFactor< CAMERA >, and gtsam::SmartProjectionPoseFactorRollingShutter< CAMERA >.

◆ totalReprojectionError()

template<class CAMERA >
double gtsam::SmartProjectionFactor< CAMERA >::totalReprojectionError ( const Cameras cameras,
boost::optional< Point3 externalPoint = boost::none 
) const
inline

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.

◆ triangulateAndComputeE() [1/2]

template<class CAMERA >
bool gtsam::SmartProjectionFactor< CAMERA >::triangulateAndComputeE ( Matrix &  E,
const Cameras cameras 
) const
inline

Triangulate and compute derivative of error with respect to point.

Returns
whether triangulation worked

◆ triangulateAndComputeE() [2/2]

template<class CAMERA >
bool gtsam::SmartProjectionFactor< CAMERA >::triangulateAndComputeE ( Matrix &  E,
const Values values 
) const
inline

Triangulate and compute derivative of error with respect to point.

Returns
whether triangulation worked

◆ triangulateForLinearize()

template<class CAMERA >
bool gtsam::SmartProjectionFactor< CAMERA >::triangulateForLinearize ( const Cameras cameras) const
inline

Possibly re-triangulate before calculating Jacobians.

Parameters
cameras
Returns
true if we could safely triangulate

◆ triangulateSafe()

template<class CAMERA >
TriangulationResult gtsam::SmartProjectionFactor< CAMERA >::triangulateSafe ( const Cameras cameras) const
inline

Call gtsam::triangulateSafe iff we need to re-triangulate.

Parameters
cameras
Returns
TriangulationResult

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