Public Types | Public Member Functions | Protected Attributes | List of all members
gtsam::ProjectionFactorRollingShutter Class Reference

#include <ProjectionFactorRollingShutter.h>

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

Public Types

typedef NoiseModelFactor3< Pose3, Pose3, Point3Base
 shorthand for base class type More...
 
typedef std::shared_ptr< Thisshared_ptr
 shorthand for a smart pointer to a factor More...
 
typedef ProjectionFactorRollingShutter This
 shorthand for this class More...
 
- Public Types inherited from gtsam::NoiseModelFactorN< Pose3, Pose3, Point3 >
enum  
 N is the number of variables (N-way factor) More...
 
using ValueType = typename std::tuple_element< I - 1, std::tuple< ValueTypes... > >::type
 
- Public Types inherited from gtsam::NoiseModelFactor
typedef std::shared_ptr< Thisshared_ptr
 
- 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 alpha () const
 
const std::shared_ptr< Cal3_S2calibration () const
 
gtsam::NonlinearFactor::shared_ptr clone () const override
 
bool equals (const NonlinearFactor &p, double tol=1e-9) const override
 equals More...
 
Vector evaluateError (const Pose3 &pose_a, const Pose3 &pose_b, const Point3 &point, OptionalMatrixType H1, OptionalMatrixType H2, OptionalMatrixType H3) const override
 Evaluate error h(x)-z and optionally derivatives. More...
 
const Point2measured () const
 
void print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
 
 ProjectionFactorRollingShutter ()
 Default constructor. More...
 
 ProjectionFactorRollingShutter (const Point2 &measured, double alpha, const SharedNoiseModel &model, Key poseKey_a, Key poseKey_b, Key pointKey, const std::shared_ptr< Cal3_S2 > &K, std::optional< Pose3 > body_P_sensor={})
 
 ProjectionFactorRollingShutter (const Point2 &measured, double alpha, const SharedNoiseModel &model, Key poseKey_a, Key poseKey_b, Key pointKey, const std::shared_ptr< Cal3_S2 > &K, bool throwCheirality, bool verboseCheirality, std::optional< Pose3 > body_P_sensor={})
 
bool throwCheirality () const
 
bool verboseCheirality () const
 
virtual ~ProjectionFactorRollingShutter ()
 
- Public Member Functions inherited from gtsam::NoiseModelFactorN< Pose3, Pose3, Point3 >
Key key () const
 
 ~NoiseModelFactorN () override
 
 NoiseModelFactorN ()
 Default Constructor for I/O. More...
 
 NoiseModelFactorN (const SharedNoiseModel &noiseModel, KeyType< ValueTypes >... keys)
 
 NoiseModelFactorN (const SharedNoiseModel &noiseModel, CONTAINER keys)
 
Vector unwhitenedError (const Values &x, OptionalMatrixVecType H=nullptr) const override
 
virtual Vector evaluateError (const ValueTypes &... x, OptionalMatrixTypeT< ValueTypes >... H) const=0
 
Vector evaluateError (const ValueTypes &... x, MatrixTypeT< ValueTypes > &... H) const
 
Vector evaluateError (const ValueTypes &... x) const
 
AreAllMatrixRefs< Vector, OptionalJacArgs... > evaluateError (const ValueTypes &... x, OptionalJacArgs &&... H) const
 
AreAllMatrixPtrs< Vector, OptionalJacArgs... > evaluateError (const ValueTypes &... x, OptionalJacArgs &&... H) const
 
Key key1 () const
 
Key key2 () const
 
Key key3 () const
 
Key key4 () const
 
Key key5 () const
 
Key key6 () const
 
- Public Member Functions inherited from gtsam::NoiseModelFactor
shared_ptr cloneWithNewNoiseModel (const SharedNoiseModel newNoise) const
 
size_t dim () const override
 
double error (const Values &c) const override
 
std::shared_ptr< GaussianFactorlinearize (const Values &x) const override
 
const SharedNoiseModelnoiseModel () const
 access to the noise model More...
 
 NoiseModelFactor ()
 
template<typename CONTAINER >
 NoiseModelFactor (const SharedNoiseModel &noiseModel, const CONTAINER &keys)
 
Vector unweightedWhitenedError (const Values &c) const
 
Vector unwhitenedError (const Values &x, std::vector< Matrix > &H) const
 
double weight (const Values &c) const
 
Vector whitenedError (const Values &c) const
 
 ~NoiseModelFactor () override
 
- 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 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 ()
 

Protected Attributes

double alpha_
 
std::optional< Pose3body_P_sensor_
 The pose of the sensor in the body frame. More...
 
std::shared_ptr< Cal3_S2K_
 shared pointer to calibration object More...
 
Point2 measured_
 2D measurement More...
 
bool throwCheirality_
 
bool verboseCheirality_
 
- Protected Attributes inherited from gtsam::NoiseModelFactor
SharedNoiseModel noiseModel_
 
- Protected Attributes inherited from gtsam::Factor
KeyVector keys_
 The keys involved in this factor. More...
 

Additional Inherited Members

- Protected Types inherited from gtsam::NoiseModelFactorN< Pose3, Pose3, Point3 >
using Base = NoiseModelFactor
 
using KeyType = Key
 
using MatrixTypeT = Matrix
 
using OptionalMatrixTypeT = Matrix *
 
using This = NoiseModelFactorN< ValueTypes... >
 
using IsConvertible = typename std::enable_if< std::is_convertible< From, To >::value, void >::type
 
using IndexIsValid = typename std::enable_if<(I >=1) &&(I<=N), void >::type
 
using ContainerElementType = typename std::decay< decltype(*std::declval< Container >().begin())>::type
 
using IsContainerOfKeys = IsConvertible< ContainerElementType< Container >, Key >
 
using AreAllMatrixRefs = std::enable_if_t<(... &&std::is_convertible< Args, Matrix &>::value), Ret >
 
using IsMatrixPointer = std::is_same< typename std::decay_t< Arg >, Matrix *>
 
using IsNullpointer = std::is_same< typename std::decay_t< Arg >, std::nullptr_t >
 
using AreAllMatrixPtrs = std::enable_if_t<(... &&(IsMatrixPointer< Args >::value||IsNullpointer< Args >::value)), Ret >
 
- Protected Types inherited from gtsam::NoiseModelFactor
typedef NonlinearFactor Base
 
typedef NoiseModelFactor This
 
- Protected Types inherited from gtsam::NonlinearFactor
typedef Factor Base
 
typedef NonlinearFactor This
 
- Protected Member Functions inherited from gtsam::NoiseModelFactor
 NoiseModelFactor (const SharedNoiseModel &noiseModel)
 
- 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

Non-linear factor for 2D projection measurement obtained using a rolling shutter camera. The calibration is known here. This version takes rolling shutter information into account as follows: consider two consecutive poses A and B, and a Point2 measurement taken starting at time A using a rolling shutter camera. Pose A has timestamp t_A, and Pose B has timestamp t_B. The Point2 measurement has timestamp t_p (with t_A <= t_p <= t_B) corresponding to the time of exposure of the row of the image the pixel belongs to. Let us define the alpha = (t_p - t_A) / (t_B - t_A), we will use the pose interpolated between A and B by the alpha to project the corresponding landmark to Point2.

Definition at line 43 of file ProjectionFactorRollingShutter.h.

Member Typedef Documentation

◆ Base

shorthand for base class type

Definition at line 62 of file ProjectionFactorRollingShutter.h.

◆ shared_ptr

shorthand for a smart pointer to a factor

Definition at line 72 of file ProjectionFactorRollingShutter.h.

◆ This

shorthand for this class

Definition at line 69 of file ProjectionFactorRollingShutter.h.

Constructor & Destructor Documentation

◆ ProjectionFactorRollingShutter() [1/3]

gtsam::ProjectionFactorRollingShutter::ProjectionFactorRollingShutter ( )
inline

Default constructor.

Definition at line 75 of file ProjectionFactorRollingShutter.h.

◆ ProjectionFactorRollingShutter() [2/3]

gtsam::ProjectionFactorRollingShutter::ProjectionFactorRollingShutter ( const Point2 measured,
double  alpha,
const SharedNoiseModel model,
Key  poseKey_a,
Key  poseKey_b,
Key  pointKey,
const std::shared_ptr< Cal3_S2 > &  K,
std::optional< Pose3 body_P_sensor = {} 
)
inline

Constructor

Parameters
measuredis the 2-dimensional pixel location of point in the image (the measurement)
alphain [0,1] is the rolling shutter parameter for the measurement
modelis the noise model
poseKey_ais the key of the first camera
poseKey_bis the key of the second camera
pointKeyis the key of the landmark
Kshared pointer to the constant calibration
body_P_sensoris the transform from body to sensor frame (default identity)

Definition at line 94 of file ProjectionFactorRollingShutter.h.

◆ ProjectionFactorRollingShutter() [3/3]

gtsam::ProjectionFactorRollingShutter::ProjectionFactorRollingShutter ( const Point2 measured,
double  alpha,
const SharedNoiseModel model,
Key  poseKey_a,
Key  poseKey_b,
Key  pointKey,
const std::shared_ptr< Cal3_S2 > &  K,
bool  throwCheirality,
bool  verboseCheirality,
std::optional< Pose3 body_P_sensor = {} 
)
inline

Constructor with exception-handling flags

Parameters
measuredis the 2-dimensional pixel location of point in the image (the measurement)
alphain [0,1] is the rolling shutter parameter for the measurement
modelis the noise model
poseKey_ais the key of the first camera
poseKey_bis the key of the second camera
pointKeyis the key of the landmark
Kshared pointer to the constant calibration
throwCheiralitydetermines whether Cheirality exceptions are rethrown
verboseCheiralitydetermines whether exceptions are printed for Cheirality
body_P_sensoris the transform from body to sensor frame (default identity)

Definition at line 124 of file ProjectionFactorRollingShutter.h.

◆ ~ProjectionFactorRollingShutter()

virtual gtsam::ProjectionFactorRollingShutter::~ProjectionFactorRollingShutter ( )
inlinevirtual

Virtual destructor

Definition at line 139 of file ProjectionFactorRollingShutter.h.

Member Function Documentation

◆ alpha()

double gtsam::ProjectionFactorRollingShutter::alpha ( ) const
inline

returns the rolling shutter interp param

Definition at line 188 of file ProjectionFactorRollingShutter.h.

◆ calibration()

const std::shared_ptr<Cal3_S2> gtsam::ProjectionFactorRollingShutter::calibration ( ) const
inline

return the calibration object

Definition at line 185 of file ProjectionFactorRollingShutter.h.

◆ clone()

gtsam::NonlinearFactor::shared_ptr gtsam::ProjectionFactorRollingShutter::clone ( ) const
inlineoverridevirtual
Returns
a deep copy of this factor

Reimplemented from gtsam::NonlinearFactor.

Definition at line 142 of file ProjectionFactorRollingShutter.h.

◆ equals()

bool gtsam::ProjectionFactorRollingShutter::equals ( const NonlinearFactor p,
double  tol = 1e-9 
) const
inlineoverridevirtual

equals

Reimplemented from gtsam::NoiseModelFactor.

Definition at line 164 of file ProjectionFactorRollingShutter.h.

◆ evaluateError()

Vector gtsam::ProjectionFactorRollingShutter::evaluateError ( const Pose3 pose_a,
const Pose3 pose_b,
const Point3 point,
OptionalMatrixType  H1,
OptionalMatrixType  H2,
OptionalMatrixType  H3 
) const
override

Evaluate error h(x)-z and optionally derivatives.

Definition at line 22 of file ProjectionFactorRollingShutter.cpp.

◆ measured()

const Point2& gtsam::ProjectionFactorRollingShutter::measured ( ) const
inline

return the measurement

Definition at line 182 of file ProjectionFactorRollingShutter.h.

◆ print()

void gtsam::ProjectionFactorRollingShutter::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::NoiseModelFactor.

Definition at line 152 of file ProjectionFactorRollingShutter.h.

◆ throwCheirality()

bool gtsam::ProjectionFactorRollingShutter::throwCheirality ( ) const
inline

return flag for throwing cheirality exceptions

Definition at line 194 of file ProjectionFactorRollingShutter.h.

◆ verboseCheirality()

bool gtsam::ProjectionFactorRollingShutter::verboseCheirality ( ) const
inline

return verbosity

Definition at line 191 of file ProjectionFactorRollingShutter.h.

Member Data Documentation

◆ alpha_

double gtsam::ProjectionFactorRollingShutter::alpha_
protected

interpolation parameter in [0,1] corresponding to the point2 measurement

Definition at line 48 of file ProjectionFactorRollingShutter.h.

◆ body_P_sensor_

std::optional<Pose3> gtsam::ProjectionFactorRollingShutter::body_P_sensor_
protected

The pose of the sensor in the body frame.

Definition at line 52 of file ProjectionFactorRollingShutter.h.

◆ K_

std::shared_ptr<Cal3_S2> gtsam::ProjectionFactorRollingShutter::K_
protected

shared pointer to calibration object

Definition at line 50 of file ProjectionFactorRollingShutter.h.

◆ measured_

Point2 gtsam::ProjectionFactorRollingShutter::measured_
protected

2D measurement

Definition at line 47 of file ProjectionFactorRollingShutter.h.

◆ throwCheirality_

bool gtsam::ProjectionFactorRollingShutter::throwCheirality_
protected

If true, rethrows Cheirality exceptions (default: false)

Definition at line 55 of file ProjectionFactorRollingShutter.h.

◆ verboseCheirality_

bool gtsam::ProjectionFactorRollingShutter::verboseCheirality_
protected

If true, prints text for Cheirality exceptions (default: false)

Definition at line 57 of file ProjectionFactorRollingShutter.h.


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


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