SmartFactorBase.h
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
22 #pragma once
23 
27 
31 
32 #include <optional>
33 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
34 #include <boost/serialization/optional.hpp>
35 #endif
36 #include <vector>
37 
38 namespace gtsam {
39 
50 template<class CAMERA>
52 
53 private:
56  typedef typename CAMERA::Measurement Z;
57  typedef typename CAMERA::MeasurementVector ZVector;
58 
59 public:
60 
61  static const int Dim = traits<CAMERA>::dimension;
62  static const int ZDim = traits<Z>::dimension;
63  typedef Eigen::Matrix<double, ZDim, Dim> MatrixZD; // F blocks (derivatives wrpt camera)
64  typedef std::vector<MatrixZD, Eigen::aligned_allocator<MatrixZD> > FBlocks; // vector of F blocks
65 
66 protected:
74 
81 
82  std::optional<Pose3>
84 
85  // Cache for Fblocks, to avoid a malloc ever time we re-linearize
86  mutable FBlocks Fs;
87 
88  public:
90 
92  typedef std::shared_ptr<This> shared_ptr;
93 
96 
99 
101  SmartFactorBase(const SharedNoiseModel& sharedNoiseModel,
102  std::optional<Pose3> body_P_sensor = {},
103  size_t expectedNumberCameras = 10)
104  : body_P_sensor_(body_P_sensor), Fs(expectedNumberCameras) {
105 
106  if (!sharedNoiseModel)
107  throw std::runtime_error("SmartFactorBase: sharedNoiseModel is required");
108 
109  SharedIsotropic sharedIsotropic = std::dynamic_pointer_cast<
110  noiseModel::Isotropic>(sharedNoiseModel);
111 
112  if (!sharedIsotropic)
113  throw std::runtime_error("SmartFactorBase: needs isotropic");
114 
115  noiseModel_ = sharedIsotropic;
116  }
117 
119  ~SmartFactorBase() override {
120  }
121 
127  void add(const Z& measured, const Key& key) {
128  if(std::find(keys_.begin(), keys_.end(), key) != keys_.end()) {
129  throw std::invalid_argument(
130  "SmartFactorBase::add: adding duplicate measurement for key.");
131  }
132  this->measured_.push_back(measured);
133  this->keys_.push_back(key);
134  }
135 
137  void add(const ZVector& measurements, const KeyVector& cameraKeys) {
138 #ifndef NDEBUG
139  if (measurements.size() != cameraKeys.size()) {
140  throw std::runtime_error("Number of measurements and camera keys do not match");
141  }
142 #endif
143  for (size_t i = 0; i < measurements.size(); i++) {
144  this->add(measurements[i], cameraKeys[i]);
145  }
146  }
147 
152  template<class SFM_TRACK>
153  void add(const SFM_TRACK& trackToAdd) {
154  for (size_t k = 0; k < trackToAdd.numberMeasurements(); k++) {
155  this->measured_.push_back(trackToAdd.measurements[k].second);
156  this->keys_.push_back(trackToAdd.measurements[k].first);
157  }
158  }
159 
161  size_t dim() const override { return ZDim * this->measured_.size(); }
162 
164  const ZVector& measured() const { return measured_; }
165 
167  virtual Cameras cameras(const Values& values) const {
169  for(const Key& k: this->keys_) {
170  cameras.push_back(values.at<CAMERA>(k));
171  }
172  return cameras;
173  }
174 
180  void print(const std::string& s = "", const KeyFormatter& keyFormatter =
181  DefaultKeyFormatter) const override {
182  std::cout << s << "SmartFactorBase, z = \n";
183  for (size_t k = 0; k < measured_.size(); ++k) {
184  std::cout << "measurement " << k<<", px = \n" << measured_[k] << "\n";
185  noiseModel_->print("noise model = ");
186  }
187  if(body_P_sensor_)
188  body_P_sensor_->print("body_P_sensor_:\n");
189  Base::print("", keyFormatter);
190  }
191 
193  bool equals(const NonlinearFactor& p, double tol = 1e-9) const override {
194  if (const This* e = dynamic_cast<const This*>(&p)) {
195  // Check that all measurements are the same.
196  for (size_t i = 0; i < measured_.size(); i++) {
197  if (!traits<Z>::Equals(this->measured_.at(i), e->measured_.at(i), tol))
198  return false;
199  }
200  // If so, check base class.
201  return Base::equals(p, tol);
202  } else {
203  return false;
204  }
205  }
206 
212  template <class POINT>
214  const Cameras& cameras, const POINT& point,
215  typename Cameras::FBlocks* Fs = nullptr, //
216  Matrix* E = nullptr) const {
217  // Reproject, with optional derivatives.
219 
220  // Apply chain rule if body_P_sensor_ is given.
221  if (body_P_sensor_ && Fs) {
222  const Pose3 sensor_P_body = body_P_sensor_->inverse();
223  constexpr int camera_dim = traits<CAMERA>::dimension;
224  constexpr int pose_dim = traits<Pose3>::dimension;
225 
226  for (size_t i = 0; i < Fs->size(); i++) {
227  const Pose3 world_P_body = cameras[i].pose() * sensor_P_body;
229  J.setZero();
231  // Call compose to compute Jacobian for camera extrinsics
232  world_P_body.compose(*body_P_sensor_, H);
233  // Assign extrinsics part of the Jacobian
234  J.template block<pose_dim, pose_dim>(0, 0) = H;
235  Fs->at(i) = Fs->at(i) * J;
236  }
237  }
238 
239  // Correct the Jacobians in case some measurements are missing.
241 
242  return error;
243  }
244 
251  template<class POINT, class ...OptArgs, typename = std::enable_if_t<sizeof...(OptArgs)!=0>>
253  const Cameras& cameras, const POINT& point,
254  OptArgs&&... optArgs) const {
255  return unwhitenedError(cameras, point, (&optArgs)...);
256  }
257 
264  const Cameras& cameras, Vector& ue,
265  typename Cameras::FBlocks* Fs = nullptr,
266  Matrix* E = nullptr) const {}
267 
274  template<class ...OptArgs>
276  const Cameras& cameras, Vector& ue,
277  OptArgs&&... optArgs) const {
278  correctForMissingMeasurements(cameras, ue, (&optArgs)...);
279  }
280 
285  template<class POINT>
286  Vector whitenedError(const Cameras& cameras, const POINT& point) const {
288  if (noiseModel_)
289  noiseModel_->whitenInPlace(error);
290  return error;
291  }
292 
301  template<class POINT>
303  const POINT& point) const {
305  return 0.5 * error.dot(error);
306  }
307 
309  static Matrix PointCov(const Matrix& E) {
310  return (E.transpose() * E).inverse();
311  }
312 
319  template<class POINT>
321  const Cameras& cameras, const POINT& point) const {
322  // Project into Camera set and calculate derivatives
323  // As in expressionFactor, RHS vector b = - (h(x_bar) - z) = z-h(x_bar)
324  // Indeed, nonlinear error |h(x_bar+dx)-z| ~ |h(x_bar) + A*dx - z|
325  // = |A*dx - (z-h(x_bar))|
326  b = -unwhitenedError(cameras, point, &Fs, &E);
327  }
328 
334  template<class POINT>
336  Vector& b, const Cameras& cameras, const POINT& point) const {
337 
338  Matrix E;
340 
341  static const int N = FixedDimension<POINT>::value; // 2 (Unit3) or 3 (Point3)
342 
343  // Do SVD on A.
345  size_t m = this->keys_.size();
346  Enull = svd.matrixU().block(0, N, ZDim * m, ZDim * m - N); // last ZDim*m-N columns
347  }
348 
350  // TODO(dellaert): Not used/tested anywhere and not properly whitened.
351  std::shared_ptr<RegularHessianFactor<Dim> > createHessianFactor(
352  const Cameras& cameras, const Point3& point, const double lambda = 0.0,
353  bool diagonalDamping = false) const {
354 
355  Matrix E;
356  Vector b;
358 
359  // build augmented hessian
360  SymmetricBlockMatrix augmentedHessian = Cameras::SchurComplement(Fs, E, b);
361 
362  return std::make_shared<RegularHessianFactor<Dim> >(keys_,
363  augmentedHessian);
364  }
365 
372  const double lambda, bool diagonalDamping,
373  SymmetricBlockMatrix& augmentedHessian,
374  const KeyVector allKeys) const {
375  Matrix E;
376  Vector b;
378  Cameras::UpdateSchurComplement(Fs, E, b, allKeys, keys_, augmentedHessian);
379  }
380 
382  void whitenJacobians(FBlocks& F, Matrix& E, Vector& b) const {
383  noiseModel_->WhitenSystem(E, b);
384  // TODO make WhitenInPlace work with any dense matrix type
385  for (size_t i = 0; i < F.size(); i++)
386  F[i] = noiseModel_->Whiten(F[i]);
387  }
388 
390  std::shared_ptr<RegularImplicitSchurFactor<CAMERA> > //
392  double lambda = 0.0, bool diagonalDamping = false) const {
393  Matrix E;
394  Vector b;
395  FBlocks F;
397  whitenJacobians(F, E, b);
398  Matrix P = Cameras::PointCov(E, lambda, diagonalDamping);
399  return std::make_shared<RegularImplicitSchurFactor<CAMERA> >(keys_, F, E,
400  P, b);
401  }
402 
404  std::shared_ptr<JacobianFactorQ<Dim, ZDim> > createJacobianQFactor(
405  const Cameras& cameras, const Point3& point, double lambda = 0.0,
406  bool diagonalDamping = false) const {
407  Matrix E;
408  Vector b;
409  FBlocks F;
411  const size_t M = b.size();
412  Matrix P = Cameras::PointCov(E, lambda, diagonalDamping);
414  return std::make_shared<JacobianFactorQ<Dim, ZDim> >(keys_, F, E, P, b, n);
415  }
416 
421  std::shared_ptr<JacobianFactor> createJacobianSVDFactor(
422  const Cameras& cameras, const Point3& point, double lambda = 0.0) const {
423  size_t m = this->keys_.size();
424  FBlocks F;
425  Vector b;
426  const size_t M = ZDim * m;
427  Matrix E0(M, M - 3);
430  noiseModel_->sigma());
431  return std::make_shared<JacobianFactorSVD<Dim, ZDim> >(keys_, F, E0, b, n);
432  }
433 
435  static void FillDiagonalF(const FBlocks& Fs, Matrix& F) {
436  size_t m = Fs.size();
437  F.resize(ZDim * m, Dim * m);
438  F.setZero();
439  for (size_t i = 0; i < m; ++i)
440  F.block<ZDim, Dim>(ZDim * i, Dim * i) = Fs.at(i);
441  }
442 
443  // Return sensor pose.
445  if(body_P_sensor_)
446  return *body_P_sensor_;
447  else
448  return Pose3(); // if unspecified, the transformation is the identity
449  }
450 
451 private:
452 
453 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
454  friend class boost::serialization::access;
456  template<class ARCHIVE>
457  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
458  ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
459  ar & BOOST_SERIALIZATION_NVP(noiseModel_);
460  ar & BOOST_SERIALIZATION_NVP(measured_);
461  ar & BOOST_SERIALIZATION_NVP(body_P_sensor_);
462  }
463 #endif
464 };
465 // end class SmartFactorBase
466 
467 // Definitions need to avoid link errors (above are only declarations)
468 template<class CAMERA> const int SmartFactorBase<CAMERA>::Dim;
469 template<class CAMERA> const int SmartFactorBase<CAMERA>::ZDim;
470 
471 } // \ namespace gtsam
H
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate set rrange[*:*] noreverse nowriteback set trange[*:*] noreverse nowriteback set urange[*:*] noreverse nowriteback set vrange[*:*] noreverse nowriteback set xlabel matrix size set x2label set timefmt d m y n H
Definition: gnuplot_common_settings.hh:74
gtsam::SmartFactorBase::unwhitenedError
Vector unwhitenedError(const Cameras &cameras, const POINT &point, typename Cameras::FBlocks *Fs=nullptr, Matrix *E=nullptr) const
Definition: SmartFactorBase.h:213
gtsam::SmartFactorBase::body_P_sensor_
std::optional< Pose3 > body_P_sensor_
Pose of the camera in the body frame.
Definition: SmartFactorBase.h:83
CameraSet.h
Base class to create smart factors on poses or cameras.
gtsam::SmartFactorBase::body_P_sensor
Pose3 body_P_sensor() const
Definition: SmartFactorBase.h:444
gtsam::CameraSet::PointCov
static Matrix PointCov(const Matrix &E, const double lambda=0.0, bool diagonalDamping=false)
Computes Point Covariance P, with lambda parameter, dynamic version.
Definition: CameraSet.h:360
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::CameraSet::UpdateSchurComplement
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)
Definition: CameraSet.h:398
gtsam::SmartFactorBase::SmartFactorBase
SmartFactorBase(const SharedNoiseModel &sharedNoiseModel, std::optional< Pose3 > body_P_sensor={}, size_t expectedNumberCameras=10)
Construct with given noise model and optional arguments.
Definition: SmartFactorBase.h:101
gtsam::LieGroup::compose
Class compose(const Class &g) const
Definition: Lie.h:48
gtsam::NonlinearFactor::equals
virtual bool equals(const NonlinearFactor &f, double tol=1e-9) const
Definition: NonlinearFactor.cpp:47
gtsam::SmartFactorBase::print
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Definition: SmartFactorBase.h:180
gtsam::SmartFactorBase::measured
const ZVector & measured() const
Return the 2D measurements (ZDim, in general).
Definition: SmartFactorBase.h:164
Eigen::ComputeFullU
@ ComputeFullU
Definition: Constants.h:393
gtsam::SmartFactorBase::This
SmartFactorBase< CAMERA > This
Definition: SmartFactorBase.h:55
gtsam::SmartFactorBase::createHessianFactor
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.
Definition: SmartFactorBase.h:351
gtsam::SmartFactorBase::Fs
FBlocks Fs
Definition: SmartFactorBase.h:86
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
different_sigmas::values
HybridValues values
Definition: testHybridBayesNet.cpp:245
gtsam::Factor
Definition: Factor.h:70
gtsam::SmartFactorBase::Dim
static const int Dim
Camera dimension.
Definition: SmartFactorBase.h:61
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:39
gtsam::KeyVector
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:92
gtsam::CameraSet::reprojectionError
Vector reprojectionError(const POINT &point, const ZVector &measured, FBlocks *Fs=nullptr, Matrix *E=nullptr) const
Calculate vector [project2(point)-z] of re-projection errors.
Definition: CameraSet.h:150
gtsam::CameraSet
A set of cameras, all with their own calibration.
Definition: CameraSet.h:37
gtsam::SmartFactorBase::ZVector
CAMERA::MeasurementVector ZVector
Definition: SmartFactorBase.h:57
gtsam::SmartFactorBase::MatrixZD
Eigen::Matrix< double, ZDim, Dim > MatrixZD
Definition: SmartFactorBase.h:63
gtsam::SmartFactorBase::unwhitenedError
Vector unwhitenedError(const Cameras &cameras, const POINT &point, OptArgs &&... optArgs) const
Definition: SmartFactorBase.h:252
gtsam::DefaultKeyFormatter
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
Definition: Key.cpp:30
RegularHessianFactor.h
HessianFactor class with constant sized blocks.
gtsam::SmartFactorBase::SmartFactorBase
SmartFactorBase()
Default Constructor, for serialization.
Definition: SmartFactorBase.h:98
n
int n
Definition: BiCGSTAB_simple.cpp:1
gtsam::SmartFactorBase::~SmartFactorBase
~SmartFactorBase() override
Virtual destructor, subclasses from NonlinearFactor.
Definition: SmartFactorBase.h:119
simulated2D::Measurement
GenericMeasurement< Point2, Point2 > Measurement
Definition: simulated2D.h:278
gtsam_unstable.tests.test_ProjectionFactorRollingShutter.point
point
Definition: test_ProjectionFactorRollingShutter.py:25
J
JacobiRotation< float > J
Definition: Jacobi_makeJacobi.cpp:3
gtsam::SmartFactorBase::createRegularImplicitSchurFactor
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.
Definition: SmartFactorBase.h:391
gtsam::SmartFactorBase::FillDiagonalF
static void FillDiagonalF(const FBlocks &Fs, Matrix &F)
Create BIG block-diagonal matrix F from Fblocks.
Definition: SmartFactorBase.h:435
gtsam::SmartFactorBase::whitenJacobians
void whitenJacobians(FBlocks &F, Matrix &E, Vector &b) const
Whiten the Jacobians computed by computeJacobians using noiseModel_.
Definition: SmartFactorBase.h:382
gtsam::noiseModel::Isotropic
Definition: NoiseModel.h:541
gtsam::CameraSet::SchurComplement
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)
Definition: CameraSet.h:175
gtsam::KeyFormatter
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:35
gtsam::Pose3
Definition: Pose3.h:37
gtsam::SmartFactorBase::noiseModel_
SharedIsotropic noiseModel_
Definition: SmartFactorBase.h:73
gtsam::SmartFactorBase::createJacobianQFactor
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.
Definition: SmartFactorBase.h:404
gtsam::SmartFactorBase::Cameras
CameraSet< CAMERA > Cameras
The CameraSet data structure is used to refer to a set of cameras.
Definition: SmartFactorBase.h:95
gtsam::SmartFactorBase::Base
NonlinearFactor Base
Definition: SmartFactorBase.h:54
m
Matrix3f m
Definition: AngleAxis_mimic_euler.cpp:1
gtsam::SharedNoiseModel
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:762
gtsam::SmartFactorBase::add
void add(const ZVector &measurements, const KeyVector &cameraKeys)
Add a bunch of measurements, together with the camera keys.
Definition: SmartFactorBase.h:137
JacobianFactorSVD.h
gtsam::SmartFactorBase::createJacobianSVDFactor
std::shared_ptr< JacobianFactor > createJacobianSVDFactor(const Cameras &cameras, const Point3 &point, double lambda=0.0) const
Definition: SmartFactorBase.h:421
gtsam::NonlinearFactor::print
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Definition: NonlinearFactor.cpp:37
gtsam::symbol_shorthand::F
Key F(std::uint64_t j)
Definition: inference/Symbol.h:153
gtsam::SmartFactorBase::cameras
virtual Cameras cameras(const Values &values) const
Collect all cameras: important that in key order.
Definition: SmartFactorBase.h:167
lambda
static double lambda[]
Definition: jv.c:524
gtsam::SmartFactorBase::PointCov
static Matrix PointCov(const Matrix &E)
Computes Point Covariance P from the "point Jacobian" E.
Definition: SmartFactorBase.h:309
gtsam::SmartFactorBase::shared_ptr
GTSAM_MAKE_ALIGNED_OPERATOR_NEW typedef std::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor.
Definition: SmartFactorBase.h:92
gtsam::svd
void svd(const Matrix &A, Matrix &U, Vector &S, Matrix &V)
Definition: Matrix.cpp:559
key
const gtsam::Symbol key('X', 0)
E
DiscreteKey E(5, 2)
gtsam::SmartFactorBase::FBlocks
std::vector< MatrixZD, Eigen::aligned_allocator< MatrixZD > > FBlocks
Definition: SmartFactorBase.h:64
NonlinearFactor.h
Non-linear factor base classes.
gtsam::SmartFactorBase
Base class for smart factors. This base class has no internal point, but it has a measurement,...
Definition: SmartFactorBase.h:51
gtsam::b
const G & b
Definition: Group.h:79
Eigen::JacobiSVD
Two-sided Jacobi SVD decomposition of a rectangular matrix.
Definition: ForwardDeclarations.h:278
gtsam
traits
Definition: SFMdata.h:40
gtsam::Factor::keys_
KeyVector keys_
The keys involved in this factor.
Definition: Factor.h:88
gtsam::traits
Definition: Group.h:36
gtsam::SmartFactorBase::ZDim
static const int ZDim
Measurement dimension.
Definition: SmartFactorBase.h:62
estimation_fixture::measurements
std::vector< double > measurements
Definition: testHybridEstimation.cpp:51
gtsam::Values
Definition: Values.h:65
gtsam::NonlinearFactor
Definition: NonlinearFactor.h:69
gtsam::SmartFactorBase::whitenedError
Vector whitenedError(const Cameras &cameras, const POINT &point) const
Definition: SmartFactorBase.h:286
p
float * p
Definition: Tutorial_Map_using.cpp:9
gtsam::SmartFactorBase::correctForMissingMeasurements
void correctForMissingMeasurements(const Cameras &cameras, Vector &ue, OptArgs &&... optArgs) const
Definition: SmartFactorBase.h:275
gtsam::SmartFactorBase::totalReprojectionError
double totalReprojectionError(const Cameras &cameras, const POINT &point) const
Definition: SmartFactorBase.h:302
P
static double P[]
Definition: ellpe.c:68
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
gtsam::SharedIsotropic
noiseModel::Isotropic::shared_ptr SharedIsotropic
Definition: NoiseModel.h:766
Eigen::Matrix
The matrix class, also used for vectors and row-vectors.
Definition: 3rdparty/Eigen/Eigen/src/Core/Matrix.h:178
gtsam::noiseModel::Isotropic::Sigma
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
Definition: NoiseModel.cpp:625
RegularImplicitSchurFactor.h
A subclass of GaussianFactor specialized to structureless SFM.
gtsam::SmartFactorBase::correctForMissingMeasurements
virtual void correctForMissingMeasurements(const Cameras &cameras, Vector &ue, typename Cameras::FBlocks *Fs=nullptr, Matrix *E=nullptr) const
Definition: SmartFactorBase.h:263
N
#define N
Definition: igam.h:9
gtsam::FixedDimension
Give fixed size dimension of a type, fails at compile time if dynamic.
Definition: Manifold.h:161
gtsam::SmartFactorBase::updateAugmentedHessian
void updateAugmentedHessian(const Cameras &cameras, const Point3 &point, const double lambda, bool diagonalDamping, SymmetricBlockMatrix &augmentedHessian, const KeyVector allKeys) const
Definition: SmartFactorBase.h:371
gtsam::SmartFactorBase::add
void add(const Z &measured, const Key &key)
Definition: SmartFactorBase.h:127
Base
Definition: test_virtual_functions.cpp:156
gtsam::SmartFactorBase::Z
CAMERA::Measurement Z
Definition: SmartFactorBase.h:56
gtsam::SmartFactorBase::equals
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
equals
Definition: SmartFactorBase.h:193
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
gtsam::SmartFactorBase::add
void add(const SFM_TRACK &trackToAdd)
Definition: SmartFactorBase.h:153
gtsam::SymmetricBlockMatrix
Definition: SymmetricBlockMatrix.h:53
enable_if_t
typename std::enable_if< B, T >::type enable_if_t
from cpp_future import (convenient aliases from C++14/17)
Definition: wrap/pybind11/include/pybind11/detail/common.h:654
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
Definition: types.h:279
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
gtsam::SmartFactorBase::computeJacobiansSVD
void computeJacobiansSVD(FBlocks &Fs, Matrix &Enull, Vector &b, const Cameras &cameras, const POINT &point) const
Definition: SmartFactorBase.h:335
gtsam::CameraSet::FBlocks
std::vector< MatrixZD, Eigen::aligned_allocator< MatrixZD > > FBlocks
Definition: CameraSet.h:79
gtsam::SmartFactorBase::dim
size_t dim() const override
Return the dimension (number of rows!) of the factor.
Definition: SmartFactorBase.h:161
gtsam::SmartFactorBase::measured_
ZVector measured_
Definition: SmartFactorBase.h:80
gtsam::SmartFactorBase::computeJacobians
void computeJacobians(FBlocks &Fs, Matrix &E, Vector &b, const Cameras &cameras, const POINT &point) const
Definition: SmartFactorBase.h:320
gtsam::NonlinearFactor::error
virtual double error(const Values &c) const
Definition: NonlinearFactor.cpp:27
JacobianFactorQ.h
M
Matrix< RealScalar, Dynamic, Dynamic > M
Definition: bench_gemm.cpp:51


gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:13:26