Public Types | Public Member Functions | Public Attributes | Protected Attributes | Private Types | Static Private Attributes | List of all members
gtsam::SmartProjectionRigFactor< CAMERA > Class Template Reference

#include <SmartProjectionRigFactor.h>

Inheritance diagram for gtsam::SmartProjectionRigFactor< CAMERA >:
Inheritance graph
[legend]

Public Types

typedef CameraSet< CAMERA > Cameras
 
typedef std::shared_ptr< Thisshared_ptr
 shorthand for a smart pointer to a factor More...
 
- Public Types inherited from gtsam::SmartProjectionFactor< CAMERA >
typedef CAMERA Camera
 shorthand for a set of cameras More...
 
typedef CameraSet< CAMERA > Cameras
 
typedef std::shared_ptr< Thisshared_ptr
 shorthand for a smart pointer to a factor More...
 
- Public Types inherited from gtsam::SmartFactorBase< CAMERA >
typedef CameraSet< CAMERA > 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

void add (const MEASUREMENT &measured, const Key &poseKey, const size_t &cameraId=0)
 
void add (const MEASUREMENTS &measurements, const KeyVector &poseKeys, const FastVector< size_t > &cameraIds=FastVector< size_t >())
 
const FastVector< size_t > & cameraIds () const
 return the calibration object More...
 
const std::shared_ptr< Cameras > & cameraRig () const
 return the calibration object More...
 
Base::Cameras cameras (const Values &values) const override
 
void computeJacobiansWithTriangulatedPoint (typename Base::FBlocks &Fs, Matrix &E, Vector &b, const Cameras &cameras) const
 
std::shared_ptr< RegularHessianFactor< DimPose > > createHessianFactor (const Values &values, const double &lambda=0.0, bool diagonalDamping=false) const
 linearize and return a Hessianfactor that is an approximation of error(p) More...
 
bool equals (const NonlinearFactor &p, double tol=1e-9) const override
 equals More...
 
double error (const Values &values) const override
 
std::shared_ptr< GaussianFactorlinearize (const Values &values) const override
 linearize More...
 
std::shared_ptr< GaussianFactorlinearizeDamped (const Values &values, const double &lambda=0.0) const
 
const KeyVectornonUniqueKeys () const
 
void print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
 
 SmartProjectionRigFactor ()
 Default constructor, only for serialization. More...
 
 SmartProjectionRigFactor (const SharedNoiseModel &sharedNoiseModel, const std::shared_ptr< Cameras > &cameraRig, const SmartProjectionParams &params=SmartProjectionParams())
 
- Public Member Functions inherited from gtsam::SmartProjectionFactor< CAMERA >
void computeJacobiansWithTriangulatedPoint (typename Base::FBlocks &Fs, Matrix &E, Vector &b, const Cameras &cameras) const
 
std::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). More...
 
std::shared_ptr< JacobianFactorQ< Base::Dim, 2 > > createJacobianQFactor (const Cameras &cameras, double lambda) const
 Create JacobianFactorQ factor. More...
 
std::shared_ptr< JacobianFactorQ< Base::Dim, 2 > > createJacobianQFactor (const Values &values, double lambda) const
 Create JacobianFactorQ factor, takes values. More...
 
std::shared_ptr< JacobianFactorcreateJacobianSVDFactor (const Cameras &cameras, double lambda) const
 Different (faster) way to compute a JacobianFactorSVD factor. More...
 
std::shared_ptr< RegularImplicitSchurFactor< CAMERA > > createRegularImplicitSchurFactor (const Cameras &cameras, double lambda) const
 
bool decideIfTriangulate (const Cameras &cameras) const
 Check if the new linearization point is the same as the one used for previous triangulation. More...
 
bool isDegenerate () const
 
bool isFarPoint () const
 
bool isOutlier () const
 
bool isPointBehindCamera () const
 
bool isValid () const
 Is result valid? More...
 
std::shared_ptr< GaussianFactorlinearizeDamped (const Cameras &cameras, const double lambda=0.0) const
 
std::shared_ptr< GaussianFactorlinearizeDamped (const Values &values, const double lambda=0.0) const
 
virtual std::shared_ptr< RegularHessianFactor< Base::Dim > > linearizeToHessian (const Values &values, double lambda=0.0) const
 Linearize to a Hessianfactor. More...
 
virtual std::shared_ptr< RegularImplicitSchurFactor< CAMERA > > linearizeToImplicit (const Values &values, double lambda=0.0) const
 Linearize to an Implicit Schur factor. More...
 
virtual std::shared_ptr< JacobianFactorQ< Base::Dim, 2 > > linearizeToJacobian (const Values &values, double lambda=0.0) const
 Linearize to a JacobianfactorQ. More...
 
TriangulationResult point () const
 
TriangulationResult point (const Values &values) const
 
Vector reprojectionErrorAfterTriangulation (const Values &values) const
 Calculate vector of re-projection errors, before applying noise model. More...
 
 SmartProjectionFactor ()
 
 SmartProjectionFactor (const SharedNoiseModel &sharedNoiseModel, const SmartProjectionParams &params=SmartProjectionParams())
 
double totalReprojectionError (const Cameras &cameras, std::optional< Point3 > externalPoint={}) const
 
bool triangulateAndComputeE (Matrix &E, const Cameras &cameras) const
 
bool triangulateAndComputeE (Matrix &E, const Values &values) const
 
bool triangulateAndComputeJacobians (typename Base::FBlocks &Fs, Matrix &E, Vector &b, const Values &values) const
 Version that takes values, and creates the point. More...
 
bool triangulateAndComputeJacobiansSVD (typename Base::FBlocks &Fs, Matrix &Enull, Vector &b, const Values &values) const
 takes values More...
 
bool triangulateForLinearize (const Cameras &cameras) const
 Possibly re-triangulate before calculating Jacobians. More...
 
TriangulationResult triangulateSafe (const Cameras &cameras) const
 Call gtsam::triangulateSafe iff we need to re-triangulate. More...
 
 ~SmartProjectionFactor () override
 
- Public Member Functions inherited from gtsam::SmartFactorBase< CAMERA >
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...
 
template<class SFM_TRACK >
void add (const SFM_TRACK &trackToAdd)
 
Pose3 body_P_sensor () const
 
template<class POINT >
void computeJacobians (FBlocks &Fs, Matrix &E, Vector &b, const Cameras &cameras, const POINT &point) const
 
template<class POINT >
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
 
template<class ... OptArgs>
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< CAMERA > > 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...
 
const ZVectormeasured () const
 Return the 2D measurements (ZDim, in general). More...
 
 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...
 
template<class POINT >
double totalReprojectionError (const Cameras &cameras, const POINT &point) const
 
template<class POINT >
Vector unwhitenedError (const Cameras &cameras, const POINT &point, typename Cameras::FBlocks *Fs=nullptr, Matrix *E=nullptr) const
 
template<class POINT , class ... OptArgs, typename = std::enable_if_t<sizeof...(OptArgs)!=0>>
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
 
template<class POINT >
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 ()
 

Public Attributes

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef CAMERA Camera
 
- Public Attributes inherited from gtsam::SmartFactorBase< CAMERA >
GTSAM_MAKE_ALIGNED_OPERATOR_NEW typedef std::shared_ptr< Thisshared_ptr
 shorthand for a smart pointer to a factor. More...
 

Protected Attributes

FastVector< size_tcameraIds_
 
std::shared_ptr< typename Base::CamerascameraRig_
 cameras in the rig (fixed poses wrt body and intrinsics, for each camera) More...
 
KeyVector nonUniqueKeys_
 vector of keys (one for each observation) with potentially repeated keys More...
 
- Protected Attributes inherited from gtsam::SmartProjectionFactor< CAMERA >
SmartProjectionParams params_
 
TriangulationResult result_
 result from triangulateSafe More...
 
std::vector< Pose3, Eigen::aligned_allocator< Pose3 > > cameraPosesTriangulation_
 current triangulation poses More...
 
- Protected Attributes inherited from gtsam::SmartFactorBase< CAMERA >
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...
 

Private Types

typedef SmartProjectionFactor< CAMERA > Base
 
typedef CAMERA::CalibrationType CALIBRATION
 
typedef CAMERA::Measurement MEASUREMENT
 
typedef CAMERA::MeasurementVector MEASUREMENTS
 
typedef SmartProjectionRigFactor< CAMERA > This
 

Static Private Attributes

static const int DimPose = 6
 Pose3 dimension. More...
 
static const int ZDim = 2
 Measurement dimension. More...
 

Additional Inherited Members

- Static Public Member Functions inherited from gtsam::SmartFactorBase< CAMERA >
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...
 
- Static Public Attributes inherited from gtsam::SmartFactorBase< CAMERA >
static const int Dim = traits<CAMERA>::dimension
 Camera dimension. More...
 
static const int ZDim = traits<Z>::dimension
 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)
 

Detailed Description

template<class CAMERA>
class gtsam::SmartProjectionRigFactor< CAMERA >

If you are using the factor, please cite: L. Carlone, Z. Kira, C. Beall, V. Indelman, F. Dellaert, Eliminating conditionally independent sets in factor graphs: a unifying perspective based on smart factors, Int. Conf. on Robotics and Automation (ICRA), 2014. This factor assumes that camera calibration is fixed (but each measurement can be taken by a different camera in the rig, hence can have a different extrinsic and intrinsic calibration). The factor only constrains poses (variable dimension is 6 for each pose). This factor requires that values contains the involved poses (Pose3). If all measurements share the same calibration (i.e., are from the same camera), use SmartProjectionPoseFactor instead! If the calibration should be optimized, as well, use SmartProjectionFactor instead!

Definition at line 52 of file SmartProjectionRigFactor.h.

Member Typedef Documentation

◆ Base

template<class CAMERA>
typedef SmartProjectionFactor<CAMERA> gtsam::SmartProjectionRigFactor< CAMERA >::Base
private

Definition at line 54 of file SmartProjectionRigFactor.h.

◆ CALIBRATION

template<class CAMERA>
typedef CAMERA::CalibrationType gtsam::SmartProjectionRigFactor< CAMERA >::CALIBRATION
private

Definition at line 56 of file SmartProjectionRigFactor.h.

◆ Cameras

template<class CAMERA>
typedef CameraSet<CAMERA> gtsam::SmartProjectionRigFactor< CAMERA >::Cameras

Definition at line 78 of file SmartProjectionRigFactor.h.

◆ MEASUREMENT

template<class CAMERA>
typedef CAMERA::Measurement gtsam::SmartProjectionRigFactor< CAMERA >::MEASUREMENT
private

Definition at line 57 of file SmartProjectionRigFactor.h.

◆ MEASUREMENTS

template<class CAMERA>
typedef CAMERA::MeasurementVector gtsam::SmartProjectionRigFactor< CAMERA >::MEASUREMENTS
private

Definition at line 58 of file SmartProjectionRigFactor.h.

◆ shared_ptr

template<class CAMERA>
typedef std::shared_ptr<This> gtsam::SmartProjectionRigFactor< CAMERA >::shared_ptr

shorthand for a smart pointer to a factor

Definition at line 81 of file SmartProjectionRigFactor.h.

◆ This

template<class CAMERA>
typedef SmartProjectionRigFactor<CAMERA> gtsam::SmartProjectionRigFactor< CAMERA >::This
private

Definition at line 55 of file SmartProjectionRigFactor.h.

Constructor & Destructor Documentation

◆ SmartProjectionRigFactor() [1/2]

template<class CAMERA>
gtsam::SmartProjectionRigFactor< CAMERA >::SmartProjectionRigFactor ( )
inline

Default constructor, only for serialization.

Definition at line 84 of file SmartProjectionRigFactor.h.

◆ SmartProjectionRigFactor() [2/2]

template<class CAMERA>
gtsam::SmartProjectionRigFactor< CAMERA >::SmartProjectionRigFactor ( const SharedNoiseModel sharedNoiseModel,
const std::shared_ptr< Cameras > &  cameraRig,
const SmartProjectionParams params = SmartProjectionParams() 
)
inline

Constructor

Parameters
sharedNoiseModelisotropic noise model for the 2D feature measurements
cameraRigset of cameras (fixed poses wrt body and intrinsics) in the camera rig
paramsparameters for the smart projection factors

Definition at line 94 of file SmartProjectionRigFactor.h.

Member Function Documentation

◆ add() [1/2]

template<class CAMERA>
void gtsam::SmartProjectionRigFactor< CAMERA >::add ( const MEASUREMENT measured,
const Key poseKey,
const size_t cameraId = 0 
)
inline

add a new measurement, corresponding to an observation from pose "poseKey" and taken from the camera in the rig identified by "cameraId"

Parameters
measured2-dimensional location of the projection of a single landmark in a single view (the measurement)
poseKeykey corresponding to the body pose of the camera taking the measurement
cameraIdID of the camera in the rig taking the measurement (default 0)

Definition at line 120 of file SmartProjectionRigFactor.h.

◆ add() [2/2]

template<class CAMERA>
void gtsam::SmartProjectionRigFactor< CAMERA >::add ( const MEASUREMENTS measurements,
const KeyVector poseKeys,
const FastVector< size_t > &  cameraIds = FastVector<size_t>() 
)
inline

Variant of the previous "add" function in which we include multiple measurements

Parameters
measurementsvector of the 2m dimensional location of the projection of a single landmark in the m views (the measurements)
poseKeyskeys corresponding to the body poses of the cameras taking the measurements
cameraIdsIDs of the cameras in the rig taking each measurement (same order as the measurements)

Definition at line 146 of file SmartProjectionRigFactor.h.

◆ cameraIds()

template<class CAMERA>
const FastVector<size_t>& gtsam::SmartProjectionRigFactor< CAMERA >::cameraIds ( ) const
inline

return the calibration object

Definition at line 174 of file SmartProjectionRigFactor.h.

◆ cameraRig()

template<class CAMERA>
const std::shared_ptr<Cameras>& gtsam::SmartProjectionRigFactor< CAMERA >::cameraRig ( ) const
inline

return the calibration object

Definition at line 171 of file SmartProjectionRigFactor.h.

◆ cameras()

template<class CAMERA>
Base::Cameras gtsam::SmartProjectionRigFactor< CAMERA >::cameras ( const Values values) const
inlineoverridevirtual

Collect all cameras involved in this factor

Parameters
valuesValues structure which must contain body poses corresponding to keys involved in this factor
Returns
vector of cameras

Reimplemented from gtsam::SmartFactorBase< CAMERA >.

Definition at line 209 of file SmartProjectionRigFactor.h.

◆ computeJacobiansWithTriangulatedPoint()

template<class CAMERA>
void gtsam::SmartProjectionRigFactor< CAMERA >::computeJacobiansWithTriangulatedPoint ( typename Base::FBlocks Fs,
Matrix E,
Vector b,
const Cameras cameras 
) const
inline

Compute jacobian F, E and error vector at a given linearization point

Parameters
valuesValues structure which must contain camera poses corresponding to keys involved in this factor
Returns
Return arguments are the camera jacobians Fs (including the jacobian with respect to both body poses we interpolate from), the point Jacobian E, and the error vector b. Note that the jacobians are computed for a given point.

Definition at line 244 of file SmartProjectionRigFactor.h.

◆ createHessianFactor()

template<class CAMERA>
std::shared_ptr<RegularHessianFactor<DimPose> > gtsam::SmartProjectionRigFactor< CAMERA >::createHessianFactor ( const Values values,
const double &  lambda = 0.0,
bool  diagonalDamping = false 
) const
inline

linearize and return a Hessianfactor that is an approximation of error(p)

Definition at line 262 of file SmartProjectionRigFactor.h.

◆ equals()

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

equals

Reimplemented from gtsam::SmartProjectionFactor< CAMERA >.

Definition at line 195 of file SmartProjectionRigFactor.h.

◆ error()

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

error calculates the error of the factor.

Reimplemented from gtsam::SmartProjectionFactor< CAMERA >.

Definition at line 227 of file SmartProjectionRigFactor.h.

◆ linearize()

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

linearize

Reimplemented from gtsam::SmartProjectionFactor< CAMERA >.

Definition at line 346 of file SmartProjectionRigFactor.h.

◆ linearizeDamped()

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

Linearize to Gaussian Factor (possibly adding a damping factor Lambda for LM)

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

Definition at line 332 of file SmartProjectionRigFactor.h.

◆ nonUniqueKeys()

template<class CAMERA>
const KeyVector& gtsam::SmartProjectionRigFactor< CAMERA >::nonUniqueKeys ( ) const
inline

return (for each observation) the (possibly non unique) keys involved in the measurements

Definition at line 168 of file SmartProjectionRigFactor.h.

◆ print()

template<class CAMERA>
void gtsam::SmartProjectionRigFactor< 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::SmartProjectionFactor< CAMERA >.

Definition at line 181 of file SmartProjectionRigFactor.h.

Member Data Documentation

◆ Camera

template<class CAMERA>
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef CAMERA gtsam::SmartProjectionRigFactor< CAMERA >::Camera

Definition at line 77 of file SmartProjectionRigFactor.h.

◆ cameraIds_

template<class CAMERA>
FastVector<size_t> gtsam::SmartProjectionRigFactor< CAMERA >::cameraIds_
protected

vector of camera Ids (one for each observation, in the same order), identifying which camera took the measurement

Definition at line 72 of file SmartProjectionRigFactor.h.

◆ cameraRig_

template<class CAMERA>
std::shared_ptr<typename Base::Cameras> gtsam::SmartProjectionRigFactor< CAMERA >::cameraRig_
protected

cameras in the rig (fixed poses wrt body and intrinsics, for each camera)

Definition at line 68 of file SmartProjectionRigFactor.h.

◆ DimPose

template<class CAMERA>
const int gtsam::SmartProjectionRigFactor< CAMERA >::DimPose = 6
staticprivate

Pose3 dimension.

Definition at line 60 of file SmartProjectionRigFactor.h.

◆ nonUniqueKeys_

template<class CAMERA>
KeyVector gtsam::SmartProjectionRigFactor< CAMERA >::nonUniqueKeys_
protected

vector of keys (one for each observation) with potentially repeated keys

Definition at line 65 of file SmartProjectionRigFactor.h.

◆ ZDim

template<class CAMERA>
const int gtsam::SmartProjectionRigFactor< CAMERA >::ZDim = 2
staticprivate

Measurement dimension.

Definition at line 61 of file SmartProjectionRigFactor.h.


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


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