|
const boost::shared_ptr< CALIBRATION > | 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 |
|
| SmartProjectionPoseFactor () |
|
| SmartProjectionPoseFactor (const SharedNoiseModel &sharedNoiseModel, const boost::shared_ptr< CALIBRATION > K, const SmartProjectionParams ¶ms=SmartProjectionParams()) |
|
| SmartProjectionPoseFactor (const SharedNoiseModel &sharedNoiseModel, const boost::shared_ptr< CALIBRATION > K, const boost::optional< Pose3 > body_P_sensor, const SmartProjectionParams ¶ms=SmartProjectionParams()) |
|
| ~SmartProjectionPoseFactor () override |
|
void | computeJacobiansWithTriangulatedPoint (std::vector< typename Base::MatrixZD, Eigen::aligned_allocator< typename Base::MatrixZD > > &Fblocks, Matrix &E, Vector &b, const Cameras &cameras) const |
|
boost::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...
|
|
boost::shared_ptr< JacobianFactorQ< Base::Dim, 2 > > | createJacobianQFactor (const Cameras &cameras, double lambda) const |
| create factor More...
|
|
boost::shared_ptr< JacobianFactorQ< Base::Dim, 2 > > | createJacobianQFactor (const Values &values, double lambda) const |
| Create a factor, takes values. More...
|
|
boost::shared_ptr< JacobianFactor > | createJacobianSVDFactor (const Cameras &cameras, double lambda) const |
| different (faster) way to compute Jacobian factor More...
|
|
boost::shared_ptr< RegularImplicitSchurFactor< PinholePose< CALIBRATION > > > | 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 | equals (const NonlinearFactor &p, double tol=1e-9) const override |
| equals More...
|
|
double | error (const Values &values) const override |
| Calculate total reprojection error. More...
|
|
bool | isDegenerate () const |
|
bool | isFarPoint () const |
|
bool | isOutlier () const |
|
bool | isPointBehindCamera () const |
|
bool | isValid () const |
| Is result valid? More...
|
|
boost::shared_ptr< GaussianFactor > | linearize (const Values &values) const override |
| linearize More...
|
|
boost::shared_ptr< GaussianFactor > | linearizeDamped (const Cameras &cameras, const double lambda=0.0) const |
|
boost::shared_ptr< GaussianFactor > | linearizeDamped (const Values &values, const double lambda=0.0) const |
|
virtual boost::shared_ptr< RegularHessianFactor< Base::Dim > > | linearizeToHessian (const Values &values, double lambda=0.0) const |
| linearize to a Hessianfactor More...
|
|
virtual boost::shared_ptr< RegularImplicitSchurFactor< PinholePose< CALIBRATION > > > | linearizeToImplicit (const Values &values, double lambda=0.0) const |
| linearize to an Implicit Schur factor More...
|
|
virtual boost::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 |
|
void | print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override |
|
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, boost::optional< Point3 > externalPoint=boost::none) const |
|
bool | triangulateAndComputeE (Matrix &E, const Cameras &cameras) const |
|
bool | triangulateAndComputeE (Matrix &E, const Values &values) const |
|
bool | triangulateAndComputeJacobians (std::vector< typename Base::MatrixZD, Eigen::aligned_allocator< typename Base::MatrixZD > > &Fblocks, Matrix &E, Vector &b, const Values &values) const |
| Version that takes values, and creates the point. More...
|
|
bool | triangulateAndComputeJacobiansSVD (std::vector< typename Base::MatrixZD, Eigen::aligned_allocator< typename Base::MatrixZD > > &Fblocks, 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...
|
|
| ~SmartProjectionFactor () override |
|
void | add (const Z &measured, const Key &key) |
|
void | add (const ZVector &measurements, const KeyVector &cameraKeys) |
|
void | add (const SFM_TRACK &trackToAdd) |
|
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 |
| SVD version. More...
|
|
virtual void | correctForMissingMeasurements (const Cameras &cameras, Vector &ue, boost::optional< typename Cameras::FBlocks & > Fs=boost::none, boost::optional< Matrix & > E=boost::none) const |
|
boost::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...
|
|
boost::shared_ptr< JacobianFactorQ< Dim, ZDim > > | createJacobianQFactor (const Cameras &cameras, const Point3 &point, double lambda=0.0, bool diagonalDamping=false) const |
|
boost::shared_ptr< JacobianFactor > | createJacobianSVDFactor (const Cameras &cameras, const Point3 &point, double lambda=0.0) const |
|
boost::shared_ptr< RegularImplicitSchurFactor< PinholePose< CALIBRATION > > > | 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 |
| get the dimension (number of rows!) of the factor More...
|
|
const ZVector & | measured () const |
|
| SmartFactorBase () |
| Default Constructor, for serialization. More...
|
|
| SmartFactorBase (const SharedNoiseModel &sharedNoiseModel, boost::optional< Pose3 > body_P_sensor=boost::none, size_t expectedNumberCameras=10) |
| Constructor. More...
|
|
double | totalReprojectionError (const Cameras &cameras, const POINT &point) const |
|
Vector | unwhitenedError (const Cameras &cameras, const POINT &point, boost::optional< typename Cameras::FBlocks & > Fs=boost::none, boost::optional< Matrix & > E=boost::none) 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...
|
|
| NonlinearFactor () |
|
template<typename CONTAINER > |
| NonlinearFactor (const CONTAINER &keys) |
|
virtual | ~NonlinearFactor () |
|
virtual bool | active (const Values &) const |
|
virtual shared_ptr | clone () const |
|
shared_ptr | rekey (const std::map< Key, Key > &rekey_mapping) const |
|
shared_ptr | rekey (const KeyVector &new_keys) const |
|
virtual | ~Factor ()=default |
| Default destructor. 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...
|
|
KeyVector & | keys () |
|
iterator | begin () |
|
iterator | end () |
|
template<class CALIBRATION>
class gtsam::SmartProjectionPoseFactor< CALIBRATION >
Definition at line 45 of file SmartProjectionPoseFactor.h.