|
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< GaussianFactor > | linearize (const Values &values) const override |
| linearize More...
|
|
std::shared_ptr< GaussianFactor > | linearizeDamped (const Values &values, const double &lambda=0.0) const |
|
const KeyVector & | nonUniqueKeys () 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 ¶ms=SmartProjectionParams()) |
|
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< JacobianFactor > | createJacobianSVDFactor (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< 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 |
|
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 ¶ms=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 |
|
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 |
|
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...
|
|
const ZVector & | measured () 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 , 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...
|
|
| 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 |
|
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 () |
|
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.