|
| TriangulationResult | triangulateSafe (const typename CAMERA::MeasurementVector &measured, const TriangulationParameters ¶ms) const |
| | triangulateSafe More...
|
| |
| virtual | ~PinholeSet () |
| |
|
| void | print (const std::string &s="") const override |
| | print More...
|
| |
| bool | equals (const PinholeSet &p, double tol=1e-9) const |
| | equals More...
|
| |
| | Base ()=default |
| |
| | Base (const Base &)=delete |
| |
| bool | equals (const CameraSet &p, double tol=1e-9) const |
| | equals More...
|
| |
| template<class POINT > |
| ZVector | project2 (const POINT &point, FBlocks *Fs=nullptr, Matrix *E=nullptr) const |
| |
| template<class POINT , class... OptArgs> |
| std::enable_if<(sizeof...(OptArgs) !=0), ZVector >::type | project2 (const POINT &point, OptArgs &... args) const |
| |
| template<class POINT > |
| Vector | reprojectionError (const POINT &point, const ZVector &measured, FBlocks *Fs=nullptr, Matrix *E=nullptr) const |
| | Calculate vector [project2(point)-z] of re-projection errors. More...
|
| |
| template<class POINT , class... OptArgs, typename = std::enable_if_t<sizeof...(OptArgs)!=0>> |
| Vector | reprojectionError (const POINT &point, const ZVector &measured, OptArgs &... args) const |
| |
| virtual | ~CameraSet ()=default |
| | Destructor. More...
|
| |
|
| using | FBlocks = std::vector< MatrixZD, Eigen::aligned_allocator< MatrixZD > > |
| |
| using | MatrixZD = Eigen::Matrix< double, ZDim, D > |
| | Definitions for blocks of F. More...
|
| |
| template<int N> |
| static void | ComputePointCovariance (Eigen::Matrix< double, N, N > &P, const Matrix &E, double lambda, bool diagonalDamping=false) |
| | Computes Point Covariance P, with lambda parameter. More...
|
| |
| static Matrix | PointCov (const Matrix &E, const double lambda=0.0, bool diagonalDamping=false) |
| | Computes Point Covariance P, with lambda parameter, dynamic version. More...
|
| |
| static SymmetricBlockMatrix | SchurComplement (const FBlocks &Fblocks, const Matrix &E, const Vector &b, const double lambda=0.0, bool diagonalDamping=false) |
| |
| template<int N, int ND> |
| static SymmetricBlockMatrix | SchurComplement (const std::vector< Eigen::Matrix< double, ZDim, ND >, Eigen::aligned_allocator< Eigen::Matrix< double, ZDim, ND >>> &Fs, const Matrix &E, const Eigen::Matrix< double, N, N > &P, const Vector &b) |
| |
| template<int N, int ND, int NDD> |
| static SymmetricBlockMatrix | SchurComplementAndRearrangeBlocks (const std::vector< Eigen::Matrix< double, ZDim, ND >, Eigen::aligned_allocator< Eigen::Matrix< double, ZDim, ND >>> &Fs, const Matrix &E, const Eigen::Matrix< double, N, N > &P, const Vector &b, const KeyVector &jacobianKeys, const KeyVector &hessianKeys) |
| |
| template<int N> |
| static void | UpdateSchurComplement (const FBlocks &Fs, const Matrix &E, const Eigen::Matrix< double, N, N > &P, const Vector &b, const KeyVector &allKeys, const KeyVector &keys, SymmetricBlockMatrix &augmentedHessian) |
| |
| using | Base = std::vector< CAMERA, typename Eigen::aligned_allocator< CAMERA > > |
| |
| typedef CAMERA::Measurement | Z |
| |
| typedef CAMERA::MeasurementVector | ZVector |
| |
| static Vector | ErrorVector (const ZVector &predicted, const ZVector &measured) |
| | Make a vector of re-projection errors. More...
|
| |
| static const int | D = traits<CAMERA>::dimension |
| | Camera dimension. More...
|
| |
| static const int | ZDim = traits<Z>::dimension |
| | Measurement dimension. More...
|
| |
template<class CAMERA>
class gtsam::PinholeSet< CAMERA >
PinholeSet: triangulates point and keeps an estimate of it around.
Definition at line 29 of file PinholeSet.h.