gtsam 4.1.1
gtsam
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
24#include <gtsam/slam/JacobianFactorQ.h>
25#include <gtsam/slam/JacobianFactorSVD.h>
27
31
32#include <boost/optional.hpp>
33#include <boost/serialization/optional.hpp>
34#include <boost/make_shared.hpp>
35#include <vector>
36
37namespace gtsam {
38
49template<class CAMERA>
51
52private:
53 typedef NonlinearFactor Base;
55 typedef typename CAMERA::Measurement Z;
56 typedef typename CAMERA::MeasurementVector ZVector;
57
58public:
59
60 static const int Dim = traits<CAMERA>::dimension;
61 static const int ZDim = traits<Z>::dimension;
62 typedef Eigen::Matrix<double, ZDim, Dim> MatrixZD; // F blocks (derivatives wrpt camera)
63 typedef std::vector<MatrixZD, Eigen::aligned_allocator<MatrixZD> > FBlocks; // vector of F blocks
64
65protected:
72 SharedIsotropic noiseModel_;
73
79 ZVector measured_;
80
81 boost::optional<Pose3>
83
84 // Cache for Fblocks, to avoid a malloc ever time we re-linearize
85 mutable FBlocks Fs;
86
87 public:
89
91 typedef boost::shared_ptr<This> shared_ptr;
92
95
98
100 SmartFactorBase(const SharedNoiseModel& sharedNoiseModel,
101 boost::optional<Pose3> body_P_sensor = boost::none,
102 size_t expectedNumberCameras = 10)
103 : body_P_sensor_(body_P_sensor), Fs(expectedNumberCameras) {
104
105 if (!sharedNoiseModel)
106 throw std::runtime_error("SmartFactorBase: sharedNoiseModel is required");
107
108 SharedIsotropic sharedIsotropic = boost::dynamic_pointer_cast<
109 noiseModel::Isotropic>(sharedNoiseModel);
110
111 if (!sharedIsotropic)
112 throw std::runtime_error("SmartFactorBase: needs isotropic");
113
114 noiseModel_ = sharedIsotropic;
115 }
116
118 ~SmartFactorBase() override {
119 }
120
126 void add(const Z& measured, const Key& key) {
127 if(std::find(keys_.begin(), keys_.end(), key) != keys_.end()) {
128 throw std::invalid_argument(
129 "SmartFactorBase::add: adding duplicate measurement for key.");
130 }
131 this->measured_.push_back(measured);
132 this->keys_.push_back(key);
133 }
134
136 void add(const ZVector& measurements, const KeyVector& cameraKeys) {
137 assert(measurements.size() == cameraKeys.size());
138 for (size_t i = 0; i < measurements.size(); i++) {
139 this->add(measurements[i], cameraKeys[i]);
140 }
141 }
142
147 template<class SFM_TRACK>
148 void add(const SFM_TRACK& trackToAdd) {
149 for (size_t k = 0; k < trackToAdd.number_measurements(); k++) {
150 this->measured_.push_back(trackToAdd.measurements[k].second);
151 this->keys_.push_back(trackToAdd.measurements[k].first);
152 }
153 }
154
156 size_t dim() const override { return ZDim * this->measured_.size(); }
157
159 const ZVector& measured() const { return measured_; }
160
162 virtual Cameras cameras(const Values& values) const {
164 for(const Key& k: this->keys_)
165 cameras.push_back(values.at<CAMERA>(k));
166 return cameras;
167 }
168
174 void print(const std::string& s = "", const KeyFormatter& keyFormatter =
175 DefaultKeyFormatter) const override {
176 std::cout << s << "SmartFactorBase, z = \n";
177 for (size_t k = 0; k < measured_.size(); ++k) {
178 std::cout << "measurement " << k<<", px = \n" << measured_[k] << "\n";
179 noiseModel_->print("noise model = ");
180 }
182 body_P_sensor_->print("body_P_sensor_:\n");
183 Base::print("", keyFormatter);
184 }
185
187 bool equals(const NonlinearFactor& p, double tol = 1e-9) const override {
188 if (const This* e = dynamic_cast<const This*>(&p)) {
189 // Check that all measurements are the same.
190 for (size_t i = 0; i < measured_.size(); i++) {
191 if (!traits<Z>::Equals(this->measured_.at(i), e->measured_.at(i), tol))
192 return false;
193 }
194 // If so, check base class.
195 return Base::equals(p, tol);
196 } else {
197 return false;
198 }
199 }
200
203 template <class POINT>
205 const Cameras& cameras, const POINT& point,
206 boost::optional<typename Cameras::FBlocks&> Fs = boost::none, //
207 boost::optional<Matrix&> E = boost::none) const {
208 // Reproject, with optional derivatives.
209 Vector error = cameras.reprojectionError(point, measured_, Fs, E);
210
211 // Apply chain rule if body_P_sensor_ is given.
212 if (body_P_sensor_ && Fs) {
213 const Pose3 sensor_P_body = body_P_sensor_->inverse();
214 constexpr int camera_dim = traits<CAMERA>::dimension;
215 constexpr int pose_dim = traits<Pose3>::dimension;
216
217 for (size_t i = 0; i < Fs->size(); i++) {
218 const Pose3 world_P_body = cameras[i].pose() * sensor_P_body;
219 Eigen::Matrix<double, camera_dim, camera_dim> J;
220 J.setZero();
221 Eigen::Matrix<double, pose_dim, pose_dim> H;
222 // Call compose to compute Jacobian for camera extrinsics
223 world_P_body.compose(*body_P_sensor_, H);
224 // Assign extrinsics part of the Jacobian
225 J.template block<pose_dim, pose_dim>(0, 0) = H;
226 Fs->at(i) = Fs->at(i) * J;
227 }
228 }
229
230 // Correct the Jacobians in case some measurements are missing.
232
233 return error;
234 }
235
242 const Cameras& cameras, Vector& ue,
243 boost::optional<typename Cameras::FBlocks&> Fs = boost::none,
244 boost::optional<Matrix&> E = boost::none) const {}
245
250 template<class POINT>
251 Vector whitenedError(const Cameras& cameras, const POINT& point) const {
252 Vector error = cameras.reprojectionError(point, measured_);
253 if (noiseModel_)
254 noiseModel_->whitenInPlace(error);
255 return error;
256 }
257
266 template<class POINT>
268 const POINT& point) const {
269 Vector error = whitenedError(cameras, point);
270 return 0.5 * error.dot(error);
271 }
272
274 static Matrix PointCov(const Matrix& E) {
275 return (E.transpose() * E).inverse();
276 }
277
284 template<class POINT>
285 void computeJacobians(FBlocks& Fs, Matrix& E, Vector& b,
286 const Cameras& cameras, const POINT& point) const {
287 // Project into Camera set and calculate derivatives
288 // As in expressionFactor, RHS vector b = - (h(x_bar) - z) = z-h(x_bar)
289 // Indeed, nonlinear error |h(x_bar+dx)-z| ~ |h(x_bar) + A*dx - z|
290 // = |A*dx - (z-h(x_bar))|
291 b = -unwhitenedError(cameras, point, Fs, E);
292 }
293
299 template<class POINT>
300 void computeJacobiansSVD(FBlocks& Fs, Matrix& Enull,
301 Vector& b, const Cameras& cameras, const POINT& point) const {
302
303 Matrix E;
304 computeJacobians(Fs, E, b, cameras, point);
305
306 static const int N = FixedDimension<POINT>::value; // 2 (Unit3) or 3 (Point3)
307
308 // Do SVD on A.
309 Eigen::JacobiSVD<Matrix> svd(E, Eigen::ComputeFullU);
310 size_t m = this->keys_.size();
311 Enull = svd.matrixU().block(0, N, ZDim * m, ZDim * m - N); // last ZDim*m-N columns
312 }
313
315 // TODO(dellaert): Not used/tested anywhere and not properly whitened.
316 boost::shared_ptr<RegularHessianFactor<Dim> > createHessianFactor(
317 const Cameras& cameras, const Point3& point, const double lambda = 0.0,
318 bool diagonalDamping = false) const {
319
320 Matrix E;
321 Vector b;
322 computeJacobians(Fs, E, b, cameras, point);
323
324 // build augmented hessian
325 SymmetricBlockMatrix augmentedHessian = Cameras::SchurComplement(Fs, E, b);
326
327 return boost::make_shared<RegularHessianFactor<Dim> >(keys_,
328 augmentedHessian);
329 }
330
336 void updateAugmentedHessian(const Cameras& cameras, const Point3& point,
337 const double lambda, bool diagonalDamping,
338 SymmetricBlockMatrix& augmentedHessian,
339 const KeyVector allKeys) const {
340 Matrix E;
341 Vector b;
342 computeJacobians(Fs, E, b, cameras, point);
343 Cameras::UpdateSchurComplement(Fs, E, b, allKeys, keys_, augmentedHessian);
344 }
345
347 void whitenJacobians(FBlocks& F, Matrix& E, Vector& b) const {
348 noiseModel_->WhitenSystem(E, b);
349 // TODO make WhitenInPlace work with any dense matrix type
350 for (size_t i = 0; i < F.size(); i++)
351 F[i] = noiseModel_->Whiten(F[i]);
352 }
353
355 boost::shared_ptr<RegularImplicitSchurFactor<CAMERA> > //
357 double lambda = 0.0, bool diagonalDamping = false) const {
358 Matrix E;
359 Vector b;
360 FBlocks F;
361 computeJacobians(F, E, b, cameras, point);
362 whitenJacobians(F, E, b);
363 Matrix P = Cameras::PointCov(E, lambda, diagonalDamping);
364 return boost::make_shared<RegularImplicitSchurFactor<CAMERA> >(keys_, F, E,
365 P, b);
366 }
367
369 boost::shared_ptr<JacobianFactorQ<Dim, ZDim> > createJacobianQFactor(
370 const Cameras& cameras, const Point3& point, double lambda = 0.0,
371 bool diagonalDamping = false) const {
372 Matrix E;
373 Vector b;
374 FBlocks F;
375 computeJacobians(F, E, b, cameras, point);
376 const size_t M = b.size();
377 Matrix P = Cameras::PointCov(E, lambda, diagonalDamping);
378 SharedIsotropic n = noiseModel::Isotropic::Sigma(M, noiseModel_->sigma());
379 return boost::make_shared<JacobianFactorQ<Dim, ZDim> >(keys_, F, E, P, b, n);
380 }
381
386 boost::shared_ptr<JacobianFactor> createJacobianSVDFactor(
387 const Cameras& cameras, const Point3& point, double lambda = 0.0) const {
388 size_t m = this->keys_.size();
389 FBlocks F;
390 Vector b;
391 const size_t M = ZDim * m;
392 Matrix E0(M, M - 3);
393 computeJacobiansSVD(F, E0, b, cameras, point);
394 SharedIsotropic n = noiseModel::Isotropic::Sigma(M - 3,
395 noiseModel_->sigma());
396 return boost::make_shared<JacobianFactorSVD<Dim, ZDim> >(keys_, F, E0, b, n);
397 }
398
400 static void FillDiagonalF(const FBlocks& Fs, Matrix& F) {
401 size_t m = Fs.size();
402 F.resize(ZDim * m, Dim * m);
403 F.setZero();
404 for (size_t i = 0; i < m; ++i)
405 F.block<ZDim, Dim>(ZDim * i, Dim * i) = Fs.at(i);
406 }
407
408 // Return sensor pose.
409 Pose3 body_P_sensor() const{
411 return *body_P_sensor_;
412 else
413 return Pose3(); // if unspecified, the transformation is the identity
414 }
415
416private:
417
420 template<class ARCHIVE>
421 void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
422 ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
423 ar & BOOST_SERIALIZATION_NVP(noiseModel_);
424 ar & BOOST_SERIALIZATION_NVP(measured_);
425 ar & BOOST_SERIALIZATION_NVP(body_P_sensor_);
426 }
427};
428// end class SmartFactorBase
429
430// Definitions need to avoid link errors (above are only declarations)
431template<class CAMERA> const int SmartFactorBase<CAMERA>::Dim;
432template<class CAMERA> const int SmartFactorBase<CAMERA>::ZDim;
433
434} // \ namespace gtsam
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
This marks a GTSAM object to require alignment.
Definition: types.h:277
Base class to create smart factors on poses or cameras.
HessianFactor class with constant sized blocks.
Non-linear factor base classes.
A subclass of GaussianFactor specialized to structureless SFM.
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:86
void svd(const Matrix &A, Matrix &U, Vector &S, Matrix &V)
SVD computes economy SVD A=U*S*V'.
Definition: Matrix.cpp:559
Vector3 Point3
As of GTSAM 4, in order to make GTSAM more lean, it is now possible to just typedef Point3 to Vector3...
Definition: Point3.h:35
noiseModel::Base::shared_ptr SharedNoiseModel
Note, deliberately not in noiseModel namespace.
Definition: NoiseModel.h:736
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:69
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
A manifold defines a space in which there is a notion of a linear tangent space that can be centered ...
Definition: concepts.h:30
Give fixed size dimension of a type, fails at compile time if dynamic.
Definition: Manifold.h:164
Definition: SymmetricBlockMatrix.h:52
A set of cameras, all with their own calibration.
Definition: CameraSet.h:35
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.
Definition: CameraSet.h:139
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:324
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)
Applies Schur complement (exploiting block structure) to get a smart factor on cameras,...
Definition: CameraSet.h:360
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)
Do Schur complement, given Jacobian as Fs,E,P, return SymmetricBlockMatrix G = F' * F - F' * E * P * ...
Definition: CameraSet.h:153
Definition: Pose3.h:37
This is the base class for all factor types.
Definition: Factor.h:56
KeyVector keys_
The keys involved in this factor.
Definition: Factor.h:73
An isotropic noise model corresponds to a scaled diagonal covariance To construct,...
Definition: NoiseModel.h:530
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
An isotropic noise model created by specifying a standard devation sigma.
Definition: NoiseModel.cpp:567
Nonlinear factor base class.
Definition: NonlinearFactor.h:43
virtual bool equals(const NonlinearFactor &f, double tol=1e-9) const
Check if two factors are equal.
Definition: NonlinearFactor.cpp:36
virtual double error(const Values &c) const =0
Calculate the error of the factor This is typically equal to log-likelihood, e.g.
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print
Definition: NonlinearFactor.cpp:26
A non-templated config holding any types of Manifold-group elements.
Definition: Values.h:63
const ValueType at(Key j) const
Retrieve a variable by key j.
Definition: Values-inl.h:346
Base class for smart factors.
Definition: SmartFactorBase.h:50
void computeJacobians(FBlocks &Fs, Matrix &E, Vector &b, const Cameras &cameras, const POINT &point) const
Compute F, E, and b (called below in both vanilla and SVD versions), where F is a vector of derivativ...
Definition: SmartFactorBase.h:285
void add(const Z &measured, const Key &key)
Add a new measurement and pose/camera key.
Definition: SmartFactorBase.h:126
~SmartFactorBase() override
Virtual destructor, subclasses from NonlinearFactor.
Definition: SmartFactorBase.h:118
void updateAugmentedHessian(const Cameras &cameras, const Point3 &point, const double lambda, bool diagonalDamping, SymmetricBlockMatrix &augmentedHessian, const KeyVector allKeys) const
Add the contribution of the smart factor to a pre-allocated Hessian, using sparse linear algebra.
Definition: SmartFactorBase.h:336
boost::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:356
SharedIsotropic noiseModel_
As of Feb 22, 2015, the noise model is the same for all measurements and is isotropic.
Definition: SmartFactorBase.h:72
static const int Dim
Camera dimension.
Definition: SmartFactorBase.h:60
Vector whitenedError(const Cameras &cameras, const POINT &point) const
Calculate vector of re-projection errors [h(x)-z] = [cameras.project(p) - z], with the noise model ap...
Definition: SmartFactorBase.h:251
virtual Cameras cameras(const Values &values) const
Collect all cameras: important that in key order.
Definition: SmartFactorBase.h:162
static void FillDiagonalF(const FBlocks &Fs, Matrix &F)
Create BIG block-diagonal matrix F from Fblocks.
Definition: SmartFactorBase.h:400
double totalReprojectionError(const Cameras &cameras, const POINT &point) const
Calculate the error of the factor.
Definition: SmartFactorBase.h:267
void add(const ZVector &measurements, const KeyVector &cameraKeys)
Add a bunch of measurements, together with the camera keys.
Definition: SmartFactorBase.h:136
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.
Definition: SmartFactorBase.h:316
void computeJacobiansSVD(FBlocks &Fs, Matrix &Enull, Vector &b, const Cameras &cameras, const POINT &point) const
SVD version that produces smaller Jacobian matrices by doing an SVD decomposition on E,...
Definition: SmartFactorBase.h:300
ZVector measured_
Measurements for each of the m views.
Definition: SmartFactorBase.h:79
GTSAM_MAKE_ALIGNED_OPERATOR_NEW typedef boost::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor.
Definition: SmartFactorBase.h:91
Vector unwhitenedError(const Cameras &cameras, const POINT &point, boost::optional< typename Cameras::FBlocks & > Fs=boost::none, boost::optional< Matrix & > E=boost::none) const
Compute reprojection errors [h(x)-z] = [cameras.project(p)-z] and derivatives.
Definition: SmartFactorBase.h:204
SmartFactorBase()
Default Constructor, for serialization.
Definition: SmartFactorBase.h:97
void whitenJacobians(FBlocks &F, Matrix &E, Vector &b) const
Whiten the Jacobians computed by computeJacobians using noiseModel_.
Definition: SmartFactorBase.h:347
SmartFactorBase(const SharedNoiseModel &sharedNoiseModel, boost::optional< Pose3 > body_P_sensor=boost::none, size_t expectedNumberCameras=10)
Construct with given noise model and optional arguments.
Definition: SmartFactorBase.h:100
void add(const SFM_TRACK &trackToAdd)
Add an entire SfM_track (collection of cameras observing a single point).
Definition: SmartFactorBase.h:148
const ZVector & measured() const
Return the 2D measurements (ZDim, in general).
Definition: SmartFactorBase.h:159
boost::shared_ptr< JacobianFactor > createJacobianSVDFactor(const Cameras &cameras, const Point3 &point, double lambda=0.0) const
Return Jacobians as JacobianFactorSVD.
Definition: SmartFactorBase.h:386
size_t dim() const override
Return the dimension (number of rows!) of the factor.
Definition: SmartFactorBase.h:156
boost::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:369
friend class boost::serialization::access
Serialization function.
Definition: SmartFactorBase.h:419
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print
Definition: SmartFactorBase.h:174
boost::optional< Pose3 > body_P_sensor_
Pose of the camera in the body frame.
Definition: SmartFactorBase.h:82
virtual void correctForMissingMeasurements(const Cameras &cameras, Vector &ue, boost::optional< typename Cameras::FBlocks & > Fs=boost::none, boost::optional< Matrix & > E=boost::none) const
This corrects the Jacobians for the case in which some 2D measurement is missing (nan).
Definition: SmartFactorBase.h:241
static const int ZDim
Measurement dimension.
Definition: SmartFactorBase.h:61
static Matrix PointCov(const Matrix &E)
Computes Point Covariance P from the "point Jacobian" E.
Definition: SmartFactorBase.h:274
CameraSet< CAMERA > Cameras
The CameraSet data structure is used to refer to a set of cameras.
Definition: SmartFactorBase.h:94
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
equals
Definition: SmartFactorBase.h:187