GTSAM  4.0.2
C++ library for smoothing and mapping (SAM)
Public Types | Public Member Functions | Static Public Member Functions | Static Public Attributes | Protected Attributes | List of all members
gtsam::SmartProjectionPoseFactorRollingShutter< CAMERA > Class Template Reference

#include <SmartProjectionPoseFactorRollingShutter.h>

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

Public Types

typedef Eigen::Matrix< double, ZDim, DimBlockMatrixZD
 
typedef std::vector< MatrixZD, Eigen::aligned_allocator< MatrixZD > > FBlocks
 
typedef CAMERA Camera
 
typedef CameraSet< CAMERA > Cameras
 
typedef std::shared_ptr< Thisshared_ptr
 shorthand for a smart pointer to a factor
 
typedef KeyVector::iterator iterator
 Iterator over keys.
 
typedef KeyVector::const_iterator const_iterator
 Const iterator over keys.
 

Public Member Functions

 SmartProjectionPoseFactorRollingShutter ()
 Default constructor, only for serialization.
 
 SmartProjectionPoseFactorRollingShutter (const SharedNoiseModel &sharedNoiseModel, const std::shared_ptr< Cameras > &cameraRig, const SmartProjectionParams &params=SmartProjectionParams())
 
void add (const MEASUREMENT &measured, const Key &world_P_body_key1, const Key &world_P_body_key2, const double &alpha, const size_t &cameraId=0)
 
void add (const MEASUREMENTS &measurements, const std::vector< std::pair< Key, Key >> &world_P_body_key_pairs, const std::vector< double > &alphas, const FastVector< size_t > &cameraIds=FastVector< size_t >())
 
const std::vector< std::pair< Key, Key > > & world_P_body_key_pairs () const
 
const std::vector< double > & alphas () const
 return the interpolation factors alphas
 
const std::shared_ptr< Cameras > & cameraRig () const
 return the calibration object
 
const FastVector< size_t > & cameraIds () const
 return the calibration object
 
void print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
 
bool equals (const NonlinearFactor &p, double tol=1e-9) const override
 equals
 
Base::Cameras cameras (const Values &values) const override
 
double error (const Values &values) const override
 
void computeJacobiansWithTriangulatedPoint (FBlocks &Fs, Matrix &E, Vector &b, const Values &values) 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)
 
std::shared_ptr< GaussianFactorlinearizeDamped (const Values &values, const double &lambda=0.0) const
 
std::shared_ptr< GaussianFactorlinearize (const Values &values) const override
 linearize
 
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...
 
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).
 
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.
 
std::shared_ptr< RegularImplicitSchurFactor< CAMERA > > createRegularImplicitSchurFactor (const Cameras &cameras, double lambda) 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.
 
std::shared_ptr< JacobianFactorQ< Base::Dim, 2 > > createJacobianQFactor (const Cameras &cameras, double lambda) const
 Create JacobianFactorQ factor.
 
std::shared_ptr< JacobianFactorQ< Base::Dim, 2 > > createJacobianQFactor (const Values &values, double lambda) const
 Create JacobianFactorQ factor, takes values.
 
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.
 
std::shared_ptr< JacobianFactorcreateJacobianSVDFactor (const Cameras &cameras, double lambda) const
 Different (faster) way to compute a JacobianFactorSVD factor.
 
std::shared_ptr< JacobianFactorcreateJacobianSVDFactor (const Cameras &cameras, const Point3 &point, 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.
 
virtual std::shared_ptr< RegularImplicitSchurFactor< CAMERA > > linearizeToImplicit (const Values &values, double lambda=0.0) const
 Linearize to an Implicit Schur factor.
 
virtual std::shared_ptr< JacobianFactorQ< Base::Dim, 2 > > linearizeToJacobian (const Values &values, double lambda=0.0) const
 Linearize to a JacobianfactorQ.
 
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
 
bool triangulateAndComputeE (Matrix &E, const Cameras &cameras) const
 
bool triangulateAndComputeE (Matrix &E, const Values &values) const
 
void computeJacobiansWithTriangulatedPoint (typename Base::FBlocks &Fs, Matrix &E, Vector &b, const Cameras &cameras) const
 
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, std::optional< Point3 > externalPoint={}) const
 
template<class POINT >
double totalReprojectionError (const Cameras &cameras, const POINT &point) const
 
TriangulationResult point () const
 
TriangulationResult point (const Values &values) const
 
bool isValid () const
 Is result valid?
 
bool isDegenerate () const
 
bool isPointBehindCamera () const
 
bool isOutlier () const
 
bool isFarPoint () const
 
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.
 
template<class SFM_TRACK >
void add (const SFM_TRACK &trackToAdd)
 
size_t dim () const override
 Return the dimension (number of rows!) of the factor.
 
const ZVector & measured () const
 Return the 2D measurements (ZDim, in general).
 
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
 
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
 
template<class POINT >
Vector whitenedError (const Cameras &cameras, const POINT &point) 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
 
void updateAugmentedHessian (const Cameras &cameras, const Point3 &point, const double lambda, bool diagonalDamping, SymmetricBlockMatrix &augmentedHessian, const KeyVector allKeys) const
 
void whitenJacobians (FBlocks &F, Matrix &E, Vector &b) const
 Whiten the Jacobians computed by computeJacobians using noiseModel_.
 
Pose3 body_P_sensor () const
 
Testable
bool equals (const This &other, double tol=1e-9) const
 check equality
 
virtual void printKeys (const std::string &s="Factor", const KeyFormatter &formatter=DefaultKeyFormatter) const
 print only keys
 
Standard Interface
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
 
Standard Interface
bool empty () const
 Whether the factor is empty (involves zero variables).
 
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
 
const_iterator end () const
 
size_t size () const
 
Advanced Interface
KeyVectorkeys ()
 
iterator begin ()
 
iterator end ()
 

Static Public Member Functions

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.
 

Static Public Attributes

static EIGEN_MAKE_ALIGNED_OPERATOR_NEW const int DimBlock
 
static const int DimPose = 6
 Pose3 dimension.
 
static const int ZDim = 2
 Measurement dimension (Point2)
 
static const int Dim = traits<CAMERA>::dimension
 Camera dimension.
 

Static Protected Member Functions

Standard Constructors
template<typename CONTAINER >
static Factor FromKeys (const CONTAINER &keys)
 
template<typename ITERATOR >
static Factor FromIterators (ITERATOR first, ITERATOR last)
 

Protected Attributes

std::vector< std::pair< Key, Key > > world_P_body_key_pairs_
 
std::vector< double > alphas_
 
std::shared_ptr< typename Base::Cameras > cameraRig_
 
FastVector< size_t > cameraIds_
 
SharedIsotropic noiseModel_
 
ZVector measured_
 
std::optional< Pose3body_P_sensor_
 Pose of the camera in the body frame.
 
FBlocks Fs
 
KeyVector keys_
 The keys involved in this factor.
 
Parameters
SmartProjectionParams params_
 
Caching triangulation
TriangulationResult result_
 result from triangulateSafe
 
std::vector< Pose3, Eigen::aligned_allocator< Pose3 > > cameraPosesTriangulation_
 current triangulation poses
 

Detailed Description

template<class CAMERA>
class gtsam::SmartProjectionPoseFactorRollingShutter< 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 optimizes two consecutive poses of the body assuming a rolling shutter model of the camera with given readout time. The factor requires that values contain (for each pixel observation) two consecutive camera poses from which the pixel observation pose can be interpolated.

Constructor & Destructor Documentation

◆ SmartProjectionPoseFactorRollingShutter()

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

Constructor

Parameters
Isotropicmeasurement noise
cameraRigset of cameras (fixed poses wrt body and intrinsics) taking the measurements
paramsinternal parameters of the smart factors

Member Function Documentation

◆ active()

virtual bool gtsam::NonlinearFactor::active ( const Values ) const
inlinevirtualinherited

Checks whether a factor should be used based on a set of values. This is primarily used to implement inequality constraints that require a variable active set. For all others, the default implementation returning true solves this problem.

In an inequality/bounding constraint, this active() returns true when the constraint is NOT fulfilled.

Returns
true if the constraint is active

Reimplemented in gtsam::BoundingConstraint2< VALUE1, VALUE2 >, gtsam::AntiFactor, and gtsam::BoundingConstraint1< VALUE >.

◆ add() [1/4]

template<class CAMERA>
void gtsam::SmartFactorBase< CAMERA >::add ( const Z &  measured,
const Key key 
)
inlineinherited

Add a new measurement and pose/camera key.

Parameters
measuredis the 2m dimensional projection of a single landmark
keyis the index corresponding to the camera observing the landmark

◆ add() [2/4]

template<class CAMERA>
void gtsam::SmartProjectionPoseFactorRollingShutter< CAMERA >::add ( const MEASUREMENT &  measured,
const Key world_P_body_key1,
const Key world_P_body_key2,
const double &  alpha,
const size_t &  cameraId = 0 
)
inline

add a new measurement, with 2 pose keys, interpolation factor, and cameraId

Parameters
measured2-dimensional location of the projection of a single landmark in a single view (the measurement), interpolated from the 2 poses
world_P_body_key1key corresponding to the first body poses (time <= time pixel is acquired)
world_P_body_key2key corresponding to the second body poses (time >= time pixel is acquired)
alphainterpolation factor in [0,1], such that if alpha = 0 the interpolated pose is the same as world_P_body_key1
cameraIdID of the camera taking the measurement (default 0)

◆ add() [3/4]

template<class CAMERA>
template<class SFM_TRACK >
void gtsam::SmartFactorBase< CAMERA >::add ( const SFM_TRACK &  trackToAdd)
inlineinherited

Add an entire SfM_track (collection of cameras observing a single point). The noise is assumed to be the same for all measurements.

◆ add() [4/4]

template<class CAMERA>
void gtsam::SmartProjectionPoseFactorRollingShutter< CAMERA >::add ( const MEASUREMENTS &  measurements,
const std::vector< std::pair< Key, Key >> &  world_P_body_key_pairs,
const std::vector< double > &  alphas,
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)
world_P_body_key_pairsvector where the i-th element contains a pair of keys corresponding to the pair of poses from which the observation pose for the i0-th measurement can be interpolated
alphasvector of interpolation params (in [0,1]), one for each measurement (in the same order)
cameraIdsIDs of the cameras taking each measurement (same order as the measurements)

◆ begin() [1/2]

const_iterator gtsam::Factor::begin ( ) const
inlineinherited

Iterator at beginning of involved variable keys

◆ begin() [2/2]

iterator gtsam::Factor::begin ( )
inlineinherited

Iterator at beginning of involved variable keys

◆ cameras()

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

Collect all cameras involved in this factor

Parameters
valuesValues structure which must contain camera poses corresponding to keys involved in this factor
Returns
Cameras

Reimplemented from gtsam::SmartFactorBase< CAMERA >.

◆ clone()

virtual shared_ptr gtsam::NonlinearFactor::clone ( ) const
inlinevirtualinherited

Creates a shared_ptr clone of the factor - needs to be specialized to allow for subclasses

By default, throws exception if subclass does not implement the function.

Reimplemented in gtsam::EssentialMatrixFactor4< CALIBRATION >, gtsam::NonlinearEquality2< T >, gtsam::CombinedImuFactor, gtsam::ImuFactor2, gtsam::EssentialMatrixFactor3, gtsam::NonlinearEquality1< VALUE >, gtsam::GeneralSFMFactor2< CALIBRATION >, gtsam::ImuFactor, gtsam::LinearizedHessianFactor, gtsam::PendulumFactorPk1, gtsam::FunctorizedFactor2< R, T1, T2 >, gtsam::MagFactor3, gtsam::Pose3AttitudeFactor, gtsam::SmartRangeFactor, gtsam::NonlinearEquality< VALUE >, gtsam::AHRSFactor, gtsam::EssentialMatrixFactor2, gtsam::ExpressionFactor< T >, gtsam::ExpressionFactor< BearingRange< A1, A2 > >, gtsam::ExpressionFactor< double >, gtsam::MagFactor2, gtsam::PendulumFactorPk, gtsam::GPSFactor2, gtsam::ProjectionFactorRollingShutter, gtsam::RangeFactorWithTransform< A1, A2, T >, gtsam::LinearContainerFactor, gtsam::LinearizedJacobianFactor, gtsam::Rot3AttitudeFactor, gtsam::MagFactor1, gtsam::GenericProjectionFactor< POSE, LANDMARK, CALIBRATION >, gtsam::DiscreteEulerPoincareHelicopter, gtsam::MultiProjectionFactor< POSE, LANDMARK, CALIBRATION >, gtsam::GeneralSFMFactor< CAMERA, LANDMARK >, gtsam::ProjectionFactorPPP< POSE, LANDMARK, CALIBRATION >, gtsam::TransformBtwRobotsUnaryFactorEM< VALUE >, gtsam::GenericStereoFactor< POSE, LANDMARK >, gtsam::TriangulationFactor< CAMERA >, gtsam::RotateDirectionsFactor, gtsam::PendulumFactor2, gtsam::ReferenceFrameFactor< POINT, TRANSFORM >, gtsam::FunctorizedFactor< R, T >, gtsam::PartialPriorFactor< VALUE >, gtsam::FunctorizedFactor< Vector, ParameterMatrix< M > >, gtsam::FunctorizedFactor< double, BASIS::Parameters >, gtsam::FunctorizedFactor< double, Vector >, gtsam::FunctorizedFactor< T, ParameterMatrix< traits< T >::dimension > >, gtsam::FunctorizedFactor< double, ParameterMatrix< P > >, gtsam::PartialPriorFactor< PoseRTV >, gtsam::MagPoseFactor< POSE >, gtsam::ProjectionFactorPPPC< POSE, LANDMARK, CALIBRATION >, gtsam::TransformBtwRobotsUnaryFactor< VALUE >, gtsam::BetweenFactor< VALUE >, gtsam::EssentialMatrixFactor, gtsam::VelocityConstraint, gtsam::PriorFactor< VALUE >, gtsam::GPSFactor, gtsam::PoseToPointFactor< POSE, POINT >, gtsam::BarometricFactor, gtsam::EssentialMatrixConstraint, gtsam::DummyFactor, gtsam::PoseBetweenFactor< POSE >, gtsam::BearingRangeFactor< A1, A2, B, R >, gtsam::PosePriorFactor< POSE >, gtsam::MagFactor, gtsam::PoseTranslationPrior< POSE >, gtsam::PoseRotationPrior< POSE >, gtsam::FullIMUFactor< POSE >, gtsam::AntiFactor, gtsam::RangeFactor< A1, A2, T >, gtsam::IMUFactor< POSE >, gtsam::RelativeElevationFactor, gtsam::PendulumFactor1, gtsam::Reconstruction, gtsam::RotateFactor, and gtsam::VelocityConstraint3.

◆ computeJacobians()

template<class CAMERA>
template<class POINT >
void gtsam::SmartFactorBase< CAMERA >::computeJacobians ( FBlocks &  Fs,
Matrix &  E,
Vector &  b,
const Cameras cameras,
const POINT &  point 
) const
inlineinherited

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.

◆ computeJacobiansSVD()

template<class CAMERA>
template<class POINT >
void gtsam::SmartFactorBase< CAMERA >::computeJacobiansSVD ( FBlocks &  Fs,
Matrix &  Enull,
Vector &  b,
const Cameras cameras,
const POINT &  point 
) const
inlineinherited

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.

◆ computeJacobiansWithTriangulatedPoint() [1/2]

template<class CAMERA>
void gtsam::SmartProjectionPoseFactorRollingShutter< CAMERA >::computeJacobiansWithTriangulatedPoint ( FBlocks &  Fs,
Matrix &  E,
Vector &  b,
const Values values 
) 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.

◆ computeJacobiansWithTriangulatedPoint() [2/2]

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

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

◆ correctForMissingMeasurements() [1/2]

template<class CAMERA>
virtual void gtsam::SmartFactorBase< CAMERA >::correctForMissingMeasurements ( const Cameras cameras,
Vector &  ue,
typename Cameras::FBlocks *  Fs = nullptr,
Matrix *  E = nullptr 
) const
inlinevirtualinherited

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.

◆ correctForMissingMeasurements() [2/2]

template<class CAMERA>
template<class ... OptArgs>
void gtsam::SmartFactorBase< CAMERA >::correctForMissingMeasurements ( const Cameras cameras,
Vector &  ue,
OptArgs &&...  optArgs 
) const
inlineinherited

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.

◆ createJacobianSVDFactor()

template<class CAMERA>
std::shared_ptr<JacobianFactor> gtsam::SmartFactorBase< CAMERA >::createJacobianSVDFactor ( const Cameras cameras,
const Point3 point,
double  lambda = 0.0 
) const
inlineinherited

Return Jacobians as JacobianFactorSVD. TODO(dellaert): lambda is currently ignored

◆ decideIfTriangulate()

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

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.

◆ end() [1/2]

const_iterator gtsam::Factor::end ( ) const
inlineinherited

Iterator at end of involved variable keys

◆ end() [2/2]

iterator gtsam::Factor::end ( )
inlineinherited

Iterator at end of involved variable keys

◆ error() [1/2]

double gtsam::NonlinearFactor::error ( const HybridValues c) const
overridevirtualinherited

All factor types need to implement an error function. In factor graphs, this is the negative log-likelihood.

Reimplemented from gtsam::Factor.

◆ error() [2/2]

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

error calculates the error of the factor.

Reimplemented from gtsam::SmartProjectionFactor< CAMERA >.

◆ FromIterators()

template<typename ITERATOR >
static Factor gtsam::Factor::FromIterators ( ITERATOR  first,
ITERATOR  last 
)
inlinestaticprotectedinherited

Construct factor from iterator keys. This is called internally from derived factor static factor methods, as a workaround for not being able to call the protected constructors above.

◆ FromKeys()

template<typename CONTAINER >
static Factor gtsam::Factor::FromKeys ( const CONTAINER &  keys)
inlinestaticprotectedinherited

Construct factor from container of keys. This is called internally from derived factor static factor methods, as a workaround for not being able to call the protected constructors above.

◆ isDegenerate()

template<class CAMERA>
bool gtsam::SmartProjectionFactor< CAMERA >::isDegenerate ( ) const
inlineinherited

return the degenerate state

◆ isFarPoint()

template<class CAMERA>
bool gtsam::SmartProjectionFactor< CAMERA >::isFarPoint ( ) const
inlineinherited

return the farPoint state

◆ isOutlier()

template<class CAMERA>
bool gtsam::SmartProjectionFactor< CAMERA >::isOutlier ( ) const
inlineinherited

return the outlier state

◆ isPointBehindCamera()

template<class CAMERA>
bool gtsam::SmartProjectionFactor< CAMERA >::isPointBehindCamera ( ) const
inlineinherited

return the cheirality status flag

◆ keys()

KeyVector& gtsam::Factor::keys ( )
inlineinherited
Returns
keys involved in this factor

◆ linearizeDamped() [1/3]

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

Linearize to Gaussian Factor

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

◆ linearizeDamped() [2/3]

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

Linearize to Gaussian Factor

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

◆ linearizeDamped() [3/3]

template<class CAMERA>
std::shared_ptr<GaussianFactor> gtsam::SmartProjectionPoseFactorRollingShutter< 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

◆ point() [1/2]

template<class CAMERA>
TriangulationResult gtsam::SmartProjectionFactor< CAMERA >::point ( ) const
inlineinherited

return the landmark

◆ point() [2/2]

template<class CAMERA>
TriangulationResult gtsam::SmartProjectionFactor< CAMERA >::point ( const Values values) const
inlineinherited

COMPUTE the landmark

◆ print()

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

◆ rekey() [1/2]

virtual shared_ptr gtsam::NonlinearFactor::rekey ( const std::map< Key, Key > &  rekey_mapping) const
virtualinherited

Creates a shared_ptr clone of the factor with different keys using a map from old->new keys

Reimplemented in gtsam::LinearContainerFactor.

◆ rekey() [2/2]

virtual shared_ptr gtsam::NonlinearFactor::rekey ( const KeyVector new_keys) const
virtualinherited

Clones a factor and fully replaces its keys

Parameters
new_keysis the full replacement set of keys

Reimplemented in gtsam::LinearContainerFactor.

◆ sendable()

virtual bool gtsam::NonlinearFactor::sendable ( ) const
inlinevirtualinherited

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)

Reimplemented in gtsam::CustomFactor.

◆ size()

size_t gtsam::Factor::size ( ) const
inlineinherited
Returns
the number of variables involved in this factor

◆ totalReprojectionError() [1/2]

template<class CAMERA>
template<class POINT >
double gtsam::SmartFactorBase< CAMERA >::totalReprojectionError ( const Cameras cameras,
const POINT &  point 
) const
inlineinherited

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. Will be used in "error(Values)" function required by NonlinearFactor base class

◆ totalReprojectionError() [2/2]

template<class CAMERA>
double gtsam::SmartProjectionFactor< CAMERA >::totalReprojectionError ( const Cameras cameras,
std::optional< Point3 externalPoint = {} 
) const
inlineinherited

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
inlineinherited

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
inlineinherited

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
inlineinherited

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
inlineinherited

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

Parameters
cameras
Returns
TriangulationResult

◆ unwhitenedError() [1/2]

template<class CAMERA>
template<class POINT >
Vector gtsam::SmartFactorBase< CAMERA >::unwhitenedError ( const Cameras cameras,
const POINT &  point,
typename Cameras::FBlocks *  Fs = nullptr,
Matrix *  E = nullptr 
) const
inlineinherited

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.

◆ unwhitenedError() [2/2]

template<class CAMERA>
template<class POINT , class ... OptArgs, typename = std::enable_if_t<sizeof...(OptArgs)!=0>>
Vector gtsam::SmartFactorBase< CAMERA >::unwhitenedError ( const Cameras cameras,
const POINT &  point,
OptArgs &&...  optArgs 
) const
inlineinherited

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.

◆ updateAugmentedHessian()

template<class CAMERA>
void gtsam::SmartFactorBase< CAMERA >::updateAugmentedHessian ( const Cameras cameras,
const Point3 point,
const double  lambda,
bool  diagonalDamping,
SymmetricBlockMatrix augmentedHessian,
const KeyVector  allKeys 
) const
inlineinherited

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

◆ whitenedError()

template<class CAMERA>
template<class POINT >
Vector gtsam::SmartFactorBase< CAMERA >::whitenedError ( const Cameras cameras,
const POINT &  point 
) const
inlineinherited

Calculate vector of re-projection errors [h(x)-z] = [cameras.project(p) - z], with the noise model applied.

◆ world_P_body_key_pairs()

template<class CAMERA>
const std::vector<std::pair<Key, Key> >& gtsam::SmartProjectionPoseFactorRollingShutter< CAMERA >::world_P_body_key_pairs ( ) const
inline

return (for each observation) the keys of the pair of poses from which we interpolate

Member Data Documentation

◆ alphas_

template<class CAMERA>
std::vector<double> gtsam::SmartProjectionPoseFactorRollingShutter< CAMERA >::alphas_
protected

interpolation factor (one for each observation) to interpolate between pair of consecutive poses

◆ cameraIds_

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

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

◆ cameraRig_

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

one or more cameras taking observations (fixed poses wrt body + fixed intrinsics)

◆ DimBlock

template<class CAMERA>
EIGEN_MAKE_ALIGNED_OPERATOR_NEW const int gtsam::SmartProjectionPoseFactorRollingShutter< CAMERA >::DimBlock
static
Initial value:
=
12

size of the variable stacking 2 poses from which the observation pose is interpolated

◆ measured_

template<class CAMERA>
ZVector gtsam::SmartFactorBase< CAMERA >::measured_
protectedinherited

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.

◆ noiseModel_

template<class CAMERA>
SharedIsotropic gtsam::SmartFactorBase< CAMERA >::noiseModel_
protectedinherited

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.

◆ world_P_body_key_pairs_

template<class CAMERA>
std::vector<std::pair<Key, Key> > gtsam::SmartProjectionPoseFactorRollingShutter< CAMERA >::world_P_body_key_pairs_
protected

The keys of the pose of the body (with respect to an external world frame): two consecutive poses for each observation


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