#include <SmartStereoProjectionPoseFactor.h>
Public Types | |
typedef std::shared_ptr< This > | shared_ptr |
shorthand for a smart pointer to a factor More... | |
typedef SmartStereoProjectionPoseFactor | This |
shorthand for this class More... | |
Public Types inherited from gtsam::SmartStereoProjectionFactor | |
typedef CameraSet< StereoCamera > | Cameras |
Vector of cameras. More... | |
typedef PinholeCamera< Cal3_S2 > | MonoCamera |
Vector of monocular cameras (stereo treated as 2 monocular) More... | |
typedef CameraSet< MonoCamera > | MonoCameras |
typedef MonoCamera::MeasurementVector | MonoMeasurements |
typedef std::shared_ptr< SmartStereoProjectionFactor > | shared_ptr |
shorthand for a smart pointer to a factor More... | |
Public Types inherited from gtsam::SmartFactorBase< StereoCamera > | |
typedef CameraSet< StereoCamera > | 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 | |
void | add (const std::vector< StereoPoint2 > &measurements, const KeyVector &poseKeys, const std::shared_ptr< Cal3_S2Stereo > &K) |
void | add (const std::vector< StereoPoint2 > &measurements, const KeyVector &poseKeys, const std::vector< std::shared_ptr< Cal3_S2Stereo >> &Ks) |
void | add (const StereoPoint2 &measured, const Key &poseKey, const std::shared_ptr< Cal3_S2Stereo > &K) |
std::vector< std::shared_ptr< Cal3_S2Stereo > > | calibration () const |
Base::Cameras | cameras (const Values &values) const override |
bool | equals (const NonlinearFactor &p, double tol=1e-9) const override |
equals More... | |
double | error (const Values &values) const override |
void | print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override |
SmartStereoProjectionPoseFactor (const SharedNoiseModel &sharedNoiseModel, const SmartStereoProjectionParams ¶ms=SmartStereoProjectionParams(), const std::optional< Pose3 > &body_P_sensor={}) | |
Public Member Functions inherited from gtsam::SmartStereoProjectionFactor | |
void | computeJacobiansWithTriangulatedPoint (FBlocks &Fs, Matrix &E, Vector &b, const Cameras &cameras) const |
void | correctForMissingMeasurements (const Cameras &cameras, Vector &ue, typename Cameras::FBlocks *Fs=nullptr, Matrix *E=nullptr) const override |
std::shared_ptr< RegularHessianFactor< Base::Dim > > | createHessianFactor (const Cameras &cameras, const double lambda=0.0, bool diagonalDamping=false) const |
linearize returns a Hessianfactor that is an approximation of error(p) More... | |
std::shared_ptr< JacobianFactor > | createJacobianSVDFactor (const Cameras &cameras, double lambda) const |
different (faster) way to compute Jacobian factor More... | |
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< GaussianFactor > | linearize (const Values &values) const override |
linearize More... | |
std::shared_ptr< GaussianFactor > | linearizeDamped (const Cameras &cameras, const double lambda=0.0) const |
std::shared_ptr< GaussianFactor > | linearizeDamped (const Values &values, const double lambda=0.0) const |
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... | |
SmartStereoProjectionFactor (const SharedNoiseModel &sharedNoiseModel, const SmartStereoProjectionParams ¶ms=SmartStereoProjectionParams(), const std::optional< Pose3 > body_P_sensor={}) | |
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 (FBlocks &Fs, Matrix &E, Vector &b, const Values &values) const |
Version that takes values, and creates the point. More... | |
bool | triangulateAndComputeJacobiansSVD (FBlocks &Fs, Matrix &Enull, Vector &b, const Values &values) const |
takes values More... | |
bool | triangulateForLinearize (const Cameras &cameras) const |
triangulate More... | |
TriangulationResult | triangulateSafe (const Cameras &cameras) const |
triangulateSafe More... | |
~SmartStereoProjectionFactor () override | |
Public Member Functions inherited from gtsam::SmartFactorBase< StereoCamera > | |
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 |
void | computeJacobians (FBlocks &Fs, Matrix &E, Vector &b, const Cameras &cameras, const POINT &point) const |
void | computeJacobiansSVD (FBlocks &Fs, Matrix &Enull, Vector &b, const Cameras &cameras, const POINT &point) const |
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< JacobianFactor > | createJacobianSVDFactor (const Cameras &cameras, const Point3 &point, double lambda=0.0) const |
std::shared_ptr< RegularImplicitSchurFactor< StereoCamera > > | 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... | |
double | totalReprojectionError (const Cameras &cameras, const POINT &point) const |
Vector | unwhitenedError (const Cameras &cameras, const POINT &point, OptArgs &&... optArgs) const |
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 |
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 size_t | dim () const =0 |
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 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 () |
Public Attributes | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef SmartStereoProjectionFactor | Base |
shorthand for base class type More... | |
Public Attributes inherited from gtsam::SmartFactorBase< StereoCamera > | |
GTSAM_MAKE_ALIGNED_OPERATOR_NEW typedef std::shared_ptr< This > | shared_ptr |
shorthand for a smart pointer to a factor. More... | |
Protected Attributes | |
std::vector< std::shared_ptr< Cal3_S2Stereo > > | K_all_ |
shared pointer to calibration object (one for each camera) More... | |
Protected Attributes inherited from gtsam::SmartStereoProjectionFactor | |
const SmartStereoProjectionParams | params_ |
TriangulationResult | result_ |
result from triangulateSafe More... | |
std::vector< Pose3 > | cameraPosesTriangulation_ |
current triangulation poses More... | |
Protected Attributes inherited from gtsam::SmartFactorBase< StereoCamera > | |
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... | |
Additional Inherited Members | |
Static Public Member Functions inherited from gtsam::SmartFactorBase< StereoCamera > | |
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< StereoCamera > | |
static const int | Dim |
Camera dimension. More... | |
static const int | ZDim |
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) |
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 camera has its own calibration. The factor only constrains poses (variable dimension is 6). This factor requires that values contains the involved poses (Pose3).
Definition at line 46 of file SmartStereoProjectionPoseFactor.h.
typedef std::shared_ptr<This> gtsam::SmartStereoProjectionPoseFactor::shared_ptr |
shorthand for a smart pointer to a factor
Definition at line 62 of file SmartStereoProjectionPoseFactor.h.
shorthand for this class
Definition at line 59 of file SmartStereoProjectionPoseFactor.h.
gtsam::SmartStereoProjectionPoseFactor::SmartStereoProjectionPoseFactor | ( | const SharedNoiseModel & | sharedNoiseModel, |
const SmartStereoProjectionParams & | params = SmartStereoProjectionParams() , |
||
const std::optional< Pose3 > & | body_P_sensor = {} |
||
) |
Constructor
Isotropic | measurement noise |
params | internal parameters of the smart factors |
Definition at line 26 of file SmartStereoProjectionPoseFactor.cpp.
void gtsam::SmartStereoProjectionPoseFactor::add | ( | const std::vector< StereoPoint2 > & | measurements, |
const KeyVector & | poseKeys, | ||
const std::shared_ptr< Cal3_S2Stereo > & | K | ||
) |
Variant of the previous one in which we include a set of measurements with the same noise and calibration
measurements | vector of the 2m dimensional location of the projection of a single landmark in the m view (the measurement) |
poseKeys | vector of keys corresponding to the camera observing the same landmark |
K | the (known) camera calibration (same for all measurements) |
Definition at line 48 of file SmartStereoProjectionPoseFactor.cpp.
void gtsam::SmartStereoProjectionPoseFactor::add | ( | const std::vector< StereoPoint2 > & | measurements, |
const KeyVector & | poseKeys, | ||
const std::vector< std::shared_ptr< Cal3_S2Stereo >> & | Ks | ||
) |
Variant of the previous one in which we include a set of measurements
measurements | vector of the 2m dimensional location of the projection of a single landmark in the m view (the measurement) |
poseKeys | vector of keys corresponding to the camera observing the same landmark |
Ks | vector of calibration objects |
Definition at line 39 of file SmartStereoProjectionPoseFactor.cpp.
void gtsam::SmartStereoProjectionPoseFactor::add | ( | const StereoPoint2 & | measured, |
const Key & | poseKey, | ||
const std::shared_ptr< Cal3_S2Stereo > & | K | ||
) |
add a new measurement and pose key
measured | is the 2m dimensional location of the projection of a single landmark in the m view (the measurement) |
poseKey | is key corresponding to the camera observing the same landmark |
K | is the (fixed) camera calibration |
Definition at line 32 of file SmartStereoProjectionPoseFactor.cpp.
|
inline |
return the calibration object
Definition at line 127 of file SmartStereoProjectionPoseFactor.h.
|
overridevirtual |
Collect all cameras involved in this factor
values | Values structure which must contain camera poses corresponding to keys involved in this factor |
Reimplemented from gtsam::SmartFactorBase< StereoCamera >.
Definition at line 84 of file SmartStereoProjectionPoseFactor.cpp.
|
overridevirtual |
equals
Reimplemented from gtsam::SmartStereoProjectionFactor.
Definition at line 67 of file SmartStereoProjectionPoseFactor.cpp.
|
overridevirtual |
error calculates the error of the factor.
Reimplemented from gtsam::SmartStereoProjectionFactor.
Definition at line 75 of file SmartStereoProjectionPoseFactor.cpp.
|
overridevirtual |
s | optional string naming the factor |
keyFormatter | optional formatter useful for printing Symbols |
Reimplemented from gtsam::SmartStereoProjectionFactor.
Definition at line 58 of file SmartStereoProjectionPoseFactor.cpp.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef SmartStereoProjectionFactor gtsam::SmartStereoProjectionPoseFactor::Base |
shorthand for base class type
Definition at line 56 of file SmartStereoProjectionPoseFactor.h.
|
protected |
shared pointer to calibration object (one for each camera)
Definition at line 50 of file SmartStereoProjectionPoseFactor.h.