Go to the documentation of this file.
   36 template <
class CAMERA>
 
   37 class CameraSet : 
public std::vector<CAMERA, Eigen::aligned_allocator<CAMERA>> {
 
   39   using Base = std::vector<CAMERA, typename Eigen::aligned_allocator<CAMERA>>;
 
   46   typedef typename CAMERA::MeasurementVector 
ZVector;
 
   54     size_t m = predicted.size();
 
   56       throw std::runtime_error(
"CameraSet::errors: size mismatch");
 
   79   using FBlocks = std::vector<MatrixZD, Eigen::aligned_allocator<MatrixZD>>;
 
   86   virtual void print(
const std::string& 
s = 
"")
 const {
 
   87     std::cout << 
s << 
"CameraSet, cameras = \n";
 
   88     for (
size_t k = 0; 
k < this->
size(); ++
k) this->at(
k).print(
s);
 
   93     if (this->
size() != p.size()) 
return false;
 
   94     bool camerasAreEqual = 
true;
 
   95     for (
size_t i = 0; 
i < this->
size(); 
i++) {
 
   96       if (this->at(
i).equals(
p.at(
i), 
tol) == 
false) camerasAreEqual = 
false;
 
   99     return camerasAreEqual;
 
  108   template <
class POINT>
 
  115     size_t m = this->
size();
 
  121     if (Fs) Fs->resize(
m);
 
  124     for (
size_t i = 0; 
i < 
m; 
i++) {
 
  128       if (Fs) (*Fs)[
i] = Fi;
 
  141   template <
class POINT, 
class... OptArgs>
 
  143       const POINT& 
point, OptArgs&... 
args)
 const {
 
  149   template <
class POINT>
 
  160   template <
class POINT, 
class... OptArgs, 
typename = 
std::enable_if_t<
sizeof...(OptArgs)!=0>>
 
  162                            OptArgs&... 
args) 
const {
 
  181     size_t m = Fs.size();
 
  185     size_t M1 = ND * 
m + 1;
 
  186     std::vector<DenseIndex> dims(
m + 1);  
 
  187     std::fill(dims.begin(), dims.end() - 1, ND);
 
  192     for (
size_t i = 0; 
i < 
m; 
i++) {  
 
  195       const auto FiT = Fi.transpose();
 
  212           FiT * (Fi - Ei_P * 
E.block(
ZDim * 
i, 0, 
ZDim, 
N).transpose() * Fi));
 
  215       for (
size_t j = 
i + 1; 
j < 
m; 
j++) {  
 
  221             -FiT * (Ei_P * 
E.block(
ZDim * 
j, 0, 
ZDim, 
N).transpose() * Fj));
 
  226     return augmentedHessian;
 
  242   template <
int N, 
int ND, 
int NDD>
 
  249     size_t nrNonuniqueKeys = jacobianKeys.size();
 
  250     size_t nrUniqueKeys = hessianKeys.size();
 
  256     std::vector<DenseIndex> dims(nrUniqueKeys + 1);
 
  257     std::fill(dims.begin(), dims.end() - 1, NDD);
 
  262     if (nrUniqueKeys == nrNonuniqueKeys) {
 
  269       std::vector<DenseIndex> nonuniqueDims(nrNonuniqueKeys + 1);  
 
  270       std::fill(nonuniqueDims.begin(), nonuniqueDims.end() - 1, NDD);
 
  271       nonuniqueDims.back() = 1;
 
  277       std::map<Key, size_t> keyToSlotMap;
 
  278       for (
size_t k = 0; 
k < nrUniqueKeys; 
k++) {
 
  279         keyToSlotMap[hessianKeys[
k]] = 
k;
 
  284           dims, Matrix::Zero(NDD * nrUniqueKeys + 1, NDD * nrUniqueKeys + 1));
 
  289       for (
size_t i = 0; 
i < nrNonuniqueKeys; 
i++) {  
 
  290         Key key_i = jacobianKeys.at(
i);
 
  294             keyToSlotMap[key_i], nrUniqueKeys,
 
  298         for (
size_t j = 
i; 
j < nrNonuniqueKeys; 
j++) {  
 
  299           Key key_j = jacobianKeys.at(
j);
 
  304             if (keyToSlotMap[key_i] != keyToSlotMap[key_j]) {
 
  306                   keyToSlotMap[key_i], keyToSlotMap[key_j],
 
  320           nrUniqueKeys, augmentedHessian.
diagonalBlock(nrNonuniqueKeys));
 
  322     return augmentedHessianUniqueKeys;
 
  337     return SchurComplement<N, D>(Fs, 
E, 
P, 
b);
 
  346                                      bool diagonalDamping = 
false) {
 
  349     if (diagonalDamping) {  
 
  350       EtE.diagonal() += 
lambda * EtE.diagonal();
 
  353       EtE += 
lambda * Eigen::MatrixXd::Identity(
n, 
n);
 
  361                          bool diagonalDamping = 
false) {
 
  364       ComputePointCovariance<2>(
P2, 
E, 
lambda, diagonalDamping);
 
  368       ComputePointCovariance<3>(
P3, 
E, 
lambda, diagonalDamping);
 
  379                                               const double lambda = 0.0,
 
  380                                               bool diagonalDamping = 
false) {
 
  383       ComputePointCovariance<2>(
P, 
E, 
lambda, diagonalDamping);
 
  384       return SchurComplement<2>(Fblocks, 
E, 
P, 
b);
 
  387       ComputePointCovariance<3>(
P, 
E, 
lambda, diagonalDamping);
 
  388       return SchurComplement<3>(Fblocks, 
E, 
P, 
b);
 
  402     assert(
keys.size() == Fs.size());
 
  403     assert(
keys.size() <= allKeys.size());
 
  406     for (
size_t slot = 0; slot < allKeys.size(); slot++)
 
  407       KeySlotMap.emplace(allKeys[slot], slot);
 
  414     size_t m = Fs.size();  
 
  415     size_t M = (augmentedHessian.
rows() - 1) / 
D;  
 
  416     assert(allKeys.size() == 
M);
 
  419     for (
size_t i = 0; 
i < 
m; 
i++) {  
 
  422       const auto FiT = Fi.transpose();
 
  424           E.template block<ZDim, N>(
ZDim * 
i, 0) * 
P;
 
  451              Ei_P * 
E.template block<ZDim, N>(
ZDim * 
i, 0).transpose() * Fi)))
 
  455       for (
size_t j = 
i + 1; 
j < 
m; 
j++) {  
 
  466             -FiT * (Ei_P * 
E.template block<ZDim, N>(
ZDim * 
j, 0).transpose() *
 
  475 #if GTSAM_ENABLE_BOOST_SERIALIZATION   
  476   friend class boost::serialization::access; 
  478   template <
class ARCHIVE>
 
  479   void serialize(ARCHIVE& ar, 
const unsigned int ) {
 
  488 template <
class CAMERA>
 
  491 template <
class CAMERA>
 
  494 template <
class CAMERA>
 
  497 template <
class CAMERA>
 
  
const EIGEN_DEVICE_FUNC InverseReturnType inverse() const
static Matrix PointCov(const Matrix &E, const double lambda=0.0, bool diagonalDamping=false)
Computes Point Covariance P, with lambda parameter, dynamic version.
void setOffDiagonalBlock(DenseIndex I, DenseIndex J, const XprType &xpr)
Set an off-diagonal block. Only the upper triangular portion of xpr is evaluated.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
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)
Concept check for values that can be used in unit tests.
static SymmetricBlockMatrix SchurComplement(const FBlocks &Fblocks, const Matrix &E, const Vector &b, const double lambda=0.0, bool diagonalDamping=false)
ZVector project2(const POINT &point, FBlocks *Fs=nullptr, Matrix *E=nullptr) const
Eigen::SelfAdjointView< constBlock, Eigen::Upper > selfadjointView(DenseIndex I, DenseIndex J) const
Return the square sub-matrix that contains blocks(i:j, i:j).
void setDiagonalBlock(DenseIndex I, const XprType &xpr)
Set a diagonal block. Only the upper triangular portion of xpr is evaluated.
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)
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Vector reprojectionError(const POINT &point, const ZVector &measured, FBlocks *Fs=nullptr, Matrix *E=nullptr) const
Calculate vector [project2(point)-z] of re-projection errors.
Calibrated camera for which only pose is unknown.
A set of cameras, all with their own calibration.
virtual void print(const std::string &s="") const
GenericMeasurement< Point2, Point2 > Measurement
STL compatible allocator to use with types requiring a non standrad alignment.
std::vector< MatrixZD, Eigen::aligned_allocator< MatrixZD > > FBlocks
Vector reprojectionError(const POINT &point, const ZVector &measured, OptArgs &... args) const
const MATRIX::ConstRowXpr row(const MATRIX &A, size_t j)
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)
Access to matrices via blocks of pre-defined sizes. Used in GaussianFactor and GaussianConditional.
std::enable_if<(sizeof...(OptArgs) !=0), ZVector >::type project2(const POINT &point, OptArgs &... args) const
bool equals(const CameraSet &p, double tol=1e-9) const
equals
CAMERA::MeasurementVector ZVector
static const int ZDim
Measurement dimension.
DenseIndex rows() const
Row size.
void updateDiagonalBlock(DenseIndex I, const XprType &xpr)
Increment the diagonal block by the values in xpr. Only reads the upper triangular part of xpr.
ptrdiff_t DenseIndex
The index type for Eigen objects.
void updateOffDiagonalBlock(DenseIndex I, DenseIndex J, const XprType &xpr)
static const int D
Camera dimension.
Eigen::SelfAdjointView< Block, Eigen::Upper > diagonalBlock(DenseIndex J)
Return the J'th diagonal block as a self adjoint view.
The matrix class, also used for vectors and row-vectors.
Give fixed size dimension of a type, fails at compile time if dynamic.
constBlock aboveDiagonalBlock(DenseIndex I, DenseIndex J) const
Get block above the diagonal (I, J).
static Vector ErrorVector(const ZVector &predicted, const ZVector &measured)
Make a vector of re-projection errors.
abc_eqf_lib::State< N > M
std::uint64_t Key
Integer nonlinear key type.
typename std::enable_if< B, T >::type enable_if_t
from cpp_future import (convenient aliases from C++14/17)
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
std::vector< MatrixZD, Eigen::aligned_allocator< MatrixZD > > FBlocks
static void ComputePointCovariance(Eigen::Matrix< double, N, N > &P, const Matrix &E, double lambda, bool diagonalDamping=false)
Computes Point Covariance P, with lambda parameter.
static constexpr double k
A thin wrapper around std::map that uses boost's fast_pool_allocator.
virtual ~CameraSet()=default
Destructor.
gtsam
Author(s): 
autogenerated on Wed May 28 2025 03:00:58