Base class for smart factors. This base class has no internal point, but it has a measurement, noise model and an optional sensor pose. This class mainly computes the derivatives and returns them as a variety of factors. The methods take a CameraSet<CAMERA> argument and the value of a point, which is kept in the derived class. More...
#include <SmartFactorBase.h>
Public Types | |
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, Dim > | MatrixZD |
Public Types inherited from gtsam::NonlinearFactor | |
typedef std::shared_ptr< This > | shared_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 | |
template<class SFM_TRACK > | |
void | add (const SFM_TRACK &trackToAdd) |
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... | |
Pose3 | body_P_sensor () const |
virtual Cameras | cameras (const Values &values) const |
Collect all cameras: important that in key order. More... | |
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 |
template<class ... OptArgs> | |
void | correctForMissingMeasurements (const Cameras &cameras, Vector &ue, OptArgs &&... optArgs) const |
virtual void | correctForMissingMeasurements (const Cameras &cameras, Vector &ue, typename Cameras::FBlocks *Fs=nullptr, Matrix *E=nullptr) 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< JacobianFactor > | createJacobianSVDFactor (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... | |
bool | equals (const NonlinearFactor &p, double tol=1e-9) const override |
equals More... | |
const ZVector & | measured () 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... | |
template<class POINT > | |
double | totalReprojectionError (const Cameras &cameras, const POINT &point) 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 |
template<class POINT > | |
Vector | unwhitenedError (const Cameras &cameras, const POINT &point, typename Cameras::FBlocks *Fs=nullptr, Matrix *E=nullptr) 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) | |
virtual double | error (const Values &c) const |
double | error (const HybridValues &c) const override |
virtual bool | active (const Values &) const |
virtual std::shared_ptr< GaussianFactor > | linearize (const Values &c) const =0 |
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 KeyVector & | keys () 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... | |
KeyVector & | keys () |
iterator | begin () |
iterator | end () |
Static Public Member Functions | |
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 | |
GTSAM_MAKE_ALIGNED_OPERATOR_NEW typedef std::shared_ptr< This > | shared_ptr |
shorthand for a smart pointer to a factor. More... | |
Static Public Attributes | |
static const int | Dim = traits<CAMERA>::dimension |
Camera dimension. More... | |
static const int | ZDim = traits<Z>::dimension |
Measurement dimension. More... | |
Protected Attributes | |
std::optional< Pose3 > | body_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 NonlinearFactor | Base |
typedef SmartFactorBase< CAMERA > | This |
typedef CAMERA::Measurement | Z |
typedef CAMERA::MeasurementVector | ZVector |
Additional Inherited Members | |
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) |
Base class for smart factors. This base class has no internal point, but it has a measurement, noise model and an optional sensor pose. This class mainly computes the derivatives and returns them as a variety of factors. The methods take a CameraSet<CAMERA> argument and the value of a point, which is kept in the derived class.
CAMERA | should behave like a PinholeCamera. |
Definition at line 51 of file SmartFactorBase.h.
|
private |
Definition at line 54 of file SmartFactorBase.h.
typedef CameraSet<CAMERA> gtsam::SmartFactorBase< CAMERA >::Cameras |
The CameraSet data structure is used to refer to a set of cameras.
Definition at line 95 of file SmartFactorBase.h.
typedef std::vector<MatrixZD, Eigen::aligned_allocator<MatrixZD> > gtsam::SmartFactorBase< CAMERA >::FBlocks |
Definition at line 64 of file SmartFactorBase.h.
typedef Eigen::Matrix<double, ZDim, Dim> gtsam::SmartFactorBase< CAMERA >::MatrixZD |
Definition at line 63 of file SmartFactorBase.h.
|
private |
Definition at line 55 of file SmartFactorBase.h.
|
private |
Definition at line 56 of file SmartFactorBase.h.
|
private |
Definition at line 57 of file SmartFactorBase.h.
|
inline |
Default Constructor, for serialization.
Definition at line 98 of file SmartFactorBase.h.
|
inline |
Construct with given noise model and optional arguments.
Definition at line 101 of file SmartFactorBase.h.
|
inlineoverride |
Virtual destructor, subclasses from NonlinearFactor.
Definition at line 119 of file SmartFactorBase.h.
|
inline |
Add an entire SfM_track (collection of cameras observing a single point). The noise is assumed to be the same for all measurements.
Definition at line 149 of file SmartFactorBase.h.
|
inline |
Add a new measurement and pose/camera key.
measured | is the 2m dimensional projection of a single landmark |
key | is the index corresponding to the camera observing the landmark |
Definition at line 127 of file SmartFactorBase.h.
|
inline |
Add a bunch of measurements, together with the camera keys.
Definition at line 137 of file SmartFactorBase.h.
|
inline |
Definition at line 440 of file SmartFactorBase.h.
|
inlinevirtual |
Collect all cameras: important that in key order.
Reimplemented in gtsam::SmartProjectionPoseFactorRollingShutter< CAMERA >, gtsam::SmartProjectionRigFactor< CAMERA >, gtsam::SmartStereoProjectionFactorPP, gtsam::SmartProjectionPoseFactor< CALIBRATION >, and gtsam::SmartStereoProjectionPoseFactor.
Definition at line 163 of file SmartFactorBase.h.
|
inline |
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. The value of cameras/point are passed as parameters.
Definition at line 316 of file SmartFactorBase.h.
|
inline |
SVD version that produces smaller Jacobian matrices by doing an SVD decomposition on E, and returning the left nulkl-space of E. See JacobianFactorSVD for more documentation.
Definition at line 331 of file SmartFactorBase.h.
|
inline |
An overload of correctForMissingMeasurements. This allows end users to provide optional arguments that are l-value references to the matrices and vectors that will be used to store the results instead of pointers.
Definition at line 271 of file SmartFactorBase.h.
|
inlinevirtual |
This corrects the Jacobians for the case in which some 2D measurement is missing (nan). In practice, this does not do anything in the monocular case, but it is implemented in the stereo version.
Reimplemented in gtsam::SmartStereoProjectionFactor.
Definition at line 259 of file SmartFactorBase.h.
|
inline |
Linearize to a Hessianfactor.
Definition at line 347 of file SmartFactorBase.h.
|
inline |
Return Jacobians as JacobianFactorQ.
Definition at line 400 of file SmartFactorBase.h.
|
inline |
Return Jacobians as JacobianFactorSVD. TODO(dellaert): lambda is currently ignored
Definition at line 417 of file SmartFactorBase.h.
|
inline |
Return Jacobians as RegularImplicitSchurFactor with raw access.
Definition at line 387 of file SmartFactorBase.h.
|
inlineoverridevirtual |
Return the dimension (number of rows!) of the factor.
Implements gtsam::NonlinearFactor.
Definition at line 157 of file SmartFactorBase.h.
|
inlineoverridevirtual |
equals
Reimplemented from gtsam::NonlinearFactor.
Reimplemented in gtsam::SmartProjectionPoseFactorRollingShutter< CAMERA >, gtsam::SmartProjectionRigFactor< CAMERA >, gtsam::SmartProjectionFactor< CAMERA >, and gtsam::SmartProjectionFactor< PinholePose< CALIBRATION > >.
Definition at line 189 of file SmartFactorBase.h.
|
inlinestatic |
Create BIG block-diagonal matrix F from Fblocks.
Definition at line 431 of file SmartFactorBase.h.
|
inline |
Return the 2D measurements (ZDim, in general).
Definition at line 160 of file SmartFactorBase.h.
|
inlinestatic |
Computes Point Covariance P from the "point Jacobian" E.
Definition at line 305 of file SmartFactorBase.h.
|
inlineoverridevirtual |
s | optional string naming the factor |
keyFormatter | optional formatter useful for printing Symbols |
Reimplemented from gtsam::NonlinearFactor.
Reimplemented in gtsam::SmartProjectionPoseFactorRollingShutter< CAMERA >, gtsam::SmartProjectionRigFactor< CAMERA >, gtsam::SmartProjectionFactor< CAMERA >, and gtsam::SmartProjectionFactor< PinholePose< CALIBRATION > >.
Definition at line 176 of file SmartFactorBase.h.
|
inline |
Calculate the error of the factor. This is the log-likelihood, e.g. in case of Gaussian. In this class, we take the raw prediction error , ask the noise model to transform it to , and then multiply by 0.5. Will be used in "error(Values)" function required by NonlinearFactor base class
Definition at line 298 of file SmartFactorBase.h.
|
inline |
An overload of unwhitenedError. This allows end users to provide optional arguments that are l-value references to the matrices and vectors that will be used to store the results instead of pointers.
Definition at line 248 of file SmartFactorBase.h.
|
inline |
Compute reprojection errors [h(x)-z] = [cameras.project(p)-z] and derivatives. This is the error before the noise model is applied. The templated version described above must finally get resolved to this function.
Definition at line 209 of file SmartFactorBase.h.
|
inline |
Add the contribution of the smart factor to a pre-allocated Hessian, using sparse linear algebra. More efficient than the creation of the Hessian without preallocation of the SymmetricBlockMatrix
Definition at line 367 of file SmartFactorBase.h.
|
inline |
Calculate vector of re-projection errors [h(x)-z] = [cameras.project(p) - z], with the noise model applied.
Definition at line 282 of file SmartFactorBase.h.
|
inline |
Whiten the Jacobians computed by computeJacobians using noiseModel_.
Definition at line 378 of file SmartFactorBase.h.
|
protected |
Pose of the camera in the body frame.
Definition at line 83 of file SmartFactorBase.h.
|
static |
Camera dimension.
Definition at line 61 of file SmartFactorBase.h.
|
mutableprotected |
Definition at line 86 of file SmartFactorBase.h.
|
protected |
Measurements for each of the m views. We keep a copy of the measurements for I/O and computing the error. The order is kept the same as the keys that we use to create the factor.
Definition at line 80 of file SmartFactorBase.h.
|
protected |
As of Feb 22, 2015, the noise model is the same for all measurements and is isotropic. This allows for moving most calculations of Schur complement etc. to be easily moved to CameraSet, and also agrees pragmatically with what is normally done.
Definition at line 73 of file SmartFactorBase.h.
GTSAM_MAKE_ALIGNED_OPERATOR_NEW typedef std::shared_ptr<This> gtsam::SmartFactorBase< CAMERA >::shared_ptr |
shorthand for a smart pointer to a factor.
Definition at line 92 of file SmartFactorBase.h.
|
static |
Measurement dimension.
Definition at line 62 of file SmartFactorBase.h.