A set of cameras, all with their own calibration. More...
#include <CameraSet.h>
Public Types | |
typedef std::vector< MatrixZD, Eigen::aligned_allocator< MatrixZD > > | FBlocks |
typedef Eigen::Matrix< double, ZDim, D > | MatrixZD |
Definitions for blocks of F. More... | |
Public Member Functions | |
bool | equals (const CameraSet &p, double tol=1e-9) const |
equals More... | |
virtual void | print (const std::string &s="") const |
template<class POINT > | |
ZVector | project2 (const POINT &point, boost::optional< FBlocks & > Fs=boost::none, boost::optional< Matrix & > E=boost::none) const |
template<class POINT > | |
Vector | reprojectionError (const POINT &point, const ZVector &measured, boost::optional< FBlocks & > Fs=boost::none, boost::optional< Matrix & > E=boost::none) const |
Calculate vector [project2(point)-z] of re-projection errors. More... | |
Static Public Member Functions | |
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... | |
template<int N> | |
static SymmetricBlockMatrix | SchurComplement (const FBlocks &Fs, const Matrix &E, const Eigen::Matrix< double, N, N > &P, const Vector &b) |
static SymmetricBlockMatrix | SchurComplement (const FBlocks &Fblocks, const Matrix &E, const Vector &b, const double lambda=0.0, bool diagonalDamping=false) |
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) |
Protected Types | |
typedef CAMERA::Measurement | Z |
typedef CAMERA::MeasurementVector | ZVector |
Static Protected Member Functions | |
static Vector | ErrorVector (const ZVector &predicted, const ZVector &measured) |
Make a vector of re-projection errors. More... | |
Static Protected Attributes | |
static const int | D = traits<CAMERA>::dimension |
Camera dimension. More... | |
static const int | ZDim = traits<Z>::dimension |
Measurement dimension. More... | |
Private Member Functions | |
template<class ARCHIVE > | |
void | serialize (ARCHIVE &ar, const unsigned int) |
Friends | |
class | boost::serialization::access |
Serialization function. More... | |
A set of cameras, all with their own calibration.
Definition at line 35 of file CameraSet.h.
typedef std::vector<MatrixZD, Eigen::aligned_allocator<MatrixZD> > gtsam::CameraSet< CAMERA >::FBlocks |
Definition at line 74 of file CameraSet.h.
typedef Eigen::Matrix<double, ZDim, D> gtsam::CameraSet< CAMERA >::MatrixZD |
Definitions for blocks of F.
Definition at line 73 of file CameraSet.h.
|
protected |
2D measurement and noise model for each of the m views The order is kept the same as the keys that we use to create the factor.
Definition at line 43 of file CameraSet.h.
|
protected |
Definition at line 44 of file CameraSet.h.
|
inlinestatic |
Computes Point Covariance P, with lambda parameter.
Definition at line 194 of file CameraSet.h.
|
inline |
equals
Definition at line 88 of file CameraSet.h.
|
inlinestaticprotected |
Make a vector of re-projection errors.
Definition at line 50 of file CameraSet.h.
|
inlinestatic |
Computes Point Covariance P, with lambda parameter, dynamic version.
Definition at line 210 of file CameraSet.h.
|
inlinevirtual |
s | optional string naming the factor |
keyFormatter | optional formatter useful for printing Symbols |
Reimplemented in gtsam::PinholeSet< CAMERA >.
Definition at line 81 of file CameraSet.h.
|
inline |
Project a point (possibly Unit3 at infinity), with derivatives Note that F is a sparse block-diagonal matrix, so instead of a large dense matrix this function returns the diagonal blocks. throws CheiralityException
Definition at line 107 of file CameraSet.h.
|
inline |
Calculate vector [project2(point)-z] of re-projection errors.
Definition at line 136 of file CameraSet.h.
|
inlinestatic |
Do Schur complement, given Jacobian as Fs,E,P, return SymmetricBlockMatrix G = F' * F - F' * E * P * E' * F g = F' * (b - E * P * E' * b) Fixed size version
Definition at line 149 of file CameraSet.h.
|
inlinestatic |
Do Schur complement, given Jacobian as Fs,E,P, return SymmetricBlockMatrix Dynamic version
Definition at line 227 of file CameraSet.h.
|
inlineprivate |
Definition at line 317 of file CameraSet.h.
|
inlinestatic |
Applies Schur complement (exploiting block structure) to get a smart factor on cameras, and adds the contribution of the smart factor to a pre-allocated augmented Hessian.
Definition at line 246 of file CameraSet.h.
|
friend |
Serialization function.
Definition at line 315 of file CameraSet.h.
|
staticprotected |
Camera dimension.
Definition at line 46 of file CameraSet.h.
|
staticprotected |
Measurement dimension.
Definition at line 47 of file CameraSet.h.