24#include <gtsam/slam/JacobianFactorQ.h>
25#include <gtsam/slam/JacobianFactorSVD.h>
32#include <boost/optional.hpp>
33#include <boost/serialization/optional.hpp>
34#include <boost/make_shared.hpp>
55 typedef typename CAMERA::Measurement Z;
56 typedef typename CAMERA::MeasurementVector ZVector;
62 typedef Eigen::Matrix<double, ZDim, Dim> MatrixZD;
63 typedef std::vector<MatrixZD, Eigen::aligned_allocator<MatrixZD> > FBlocks;
81 boost::optional<Pose3>
101 boost::optional<Pose3> body_P_sensor = boost::none,
102 size_t expectedNumberCameras = 10)
105 if (!sharedNoiseModel)
106 throw std::runtime_error(
"SmartFactorBase: sharedNoiseModel is required");
108 SharedIsotropic sharedIsotropic = boost::dynamic_pointer_cast<
111 if (!sharedIsotropic)
112 throw std::runtime_error(
"SmartFactorBase: needs isotropic");
128 throw std::invalid_argument(
129 "SmartFactorBase::add: adding duplicate measurement for key.");
131 this->measured_.push_back(
measured);
132 this->
keys_.push_back(key);
137 assert(measurements.size() == cameraKeys.size());
138 for (
size_t i = 0; i < measurements.size(); i++) {
139 this->
add(measurements[i], cameraKeys[i]);
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);
156 size_t dim()
const override {
return ZDim * this->measured_.size(); }
165 cameras.push_back(values.
at<CAMERA>(k));
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";
188 if (
const This* e =
dynamic_cast<const This*
>(&p)) {
190 for (
size_t i = 0; i <
measured_.size(); i++) {
203 template <
class POINT>
206 boost::optional<typename Cameras::FBlocks&> Fs = boost::none,
207 boost::optional<Matrix&> E = boost::none)
const {
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;
221 Eigen::Matrix<double, pose_dim, pose_dim> H;
225 J.template block<pose_dim, pose_dim>(0, 0) = H;
226 Fs->at(i) = Fs->at(i) * J;
243 boost::optional<typename Cameras::FBlocks&> Fs = boost::none,
244 boost::optional<Matrix&> E = boost::none)
const {}
250 template<
class POINT>
266 template<
class POINT>
268 const POINT& point)
const {
275 return (E.transpose() * E).inverse();
284 template<
class POINT>
299 template<
class POINT>
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);
318 bool diagonalDamping =
false)
const {
327 return boost::make_shared<RegularHessianFactor<Dim> >(
keys_,
337 const double lambda,
bool diagonalDamping,
350 for (
size_t i = 0; i < F.size(); i++)
355 boost::shared_ptr<RegularImplicitSchurFactor<CAMERA> >
357 double lambda = 0.0,
bool diagonalDamping =
false)
const {
364 return boost::make_shared<RegularImplicitSchurFactor<CAMERA> >(
keys_, F, E,
371 bool diagonalDamping =
false)
const {
376 const size_t M = b.size();
379 return boost::make_shared<JacobianFactorQ<Dim, ZDim> >(
keys_, F, E, P, b, n);
388 size_t m = this->
keys_.size();
391 const size_t M =
ZDim * m;
396 return boost::make_shared<JacobianFactorSVD<Dim, ZDim> >(
keys_, F, E0, b, n);
401 size_t m = Fs.size();
404 for (
size_t i = 0; i < m; ++i)
409 Pose3 body_P_sensor()
const{
420 template<
class ARCHIVE>
421 void serialize(ARCHIVE & ar,
const unsigned int ) {
422 ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(
Base);
#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
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