23#include <gtsam/slam/SmartFactorParams.h>
29#include <boost/optional.hpp>
30#include <boost/make_shared.hpp>
64 mutable std::vector<Pose3, Eigen::aligned_allocator<Pose3> >
90 :
Base(sharedNoiseModel),
104 DefaultKeyFormatter)
const override {
105 std::cout << s <<
"SmartProjectionFactor\n";
108 std::cout <<
"triangulationParameters:\n" << params_.triangulation
110 std::cout <<
"result:\n" <<
result_ << std::endl;
116 const This *e =
dynamic_cast<const This*
>(&p);
137 bool retriangulate =
false;
143 retriangulate =
true;
146 if (!retriangulate) {
147 for (
size_t i = 0; i <
cameras.size(); i++) {
150 retriangulate =
true;
160 for (
size_t i = 0; i < m; i++)
165 return retriangulate;
178 return TriangulationResult::Degenerate();
183 params_.triangulation);
201 bool diagonalDamping =
false)
const {
202 size_t numKeys = this->
keys_.size();
205 std::vector<Matrix> Gs(numKeys * (numKeys + 1) / 2);
206 std::vector<Vector> gs(numKeys);
208 if (this->
measured_.size() != cameras.size())
209 throw std::runtime_error(
210 "SmartProjectionHessianFactor: this->measured_"
211 ".size() inconsistent with input");
218 for (Vector& v : gs) v = Vector::Zero(
Base::Dim);
219 return boost::make_shared<RegularHessianFactor<Base::Dim> >(this->
keys_,
224 typename Base::FBlocks Fs;
236 return boost::make_shared<RegularHessianFactor<Base::Dim> >(
237 this->
keys_, augmentedHessian);
241 boost::shared_ptr<RegularImplicitSchurFactor<CAMERA> > createRegularImplicitSchurFactor(
242 const Cameras&
cameras,
double lambda)
const {
247 return boost::shared_ptr<RegularImplicitSchurFactor<CAMERA> >();
257 return boost::make_shared<JacobianFactorQ<Base::Dim, 2> >(this->
keys_);
262 const Values& values,
double lambda)
const {
273 return boost::make_shared<JacobianFactorSVD<Base::Dim, 2> >(this->
keys_);
278 const Values& values,
double lambda = 0.0)
const {
284 const Values& values,
double lambda = 0.0)
const {
285 return createRegularImplicitSchurFactor(this->
cameras(values), lambda);
290 const Values& values,
double lambda = 0.0)
const {
300 const double lambda = 0.0)
const {
306 return createRegularImplicitSchurFactor(
cameras, lambda);
312 throw std::runtime_error(
"SmartFactorlinearize: unknown mode");
322 const double lambda = 0.0)
const {
330 const Values& values)
const override {
342 return nonDegenerate;
358 typename Base::FBlocks& Fs, Matrix& E, Vector& b,
364 Unit3 backProjected =
cameras[0].backprojectPointAtInfinity(
375 typename Base::FBlocks& Fs, Matrix& E, Vector& b,
376 const Values& values)
const {
381 return nonDegenerate;
386 typename Base::FBlocks& Fs, Matrix& Enull, Vector& b,
387 const Values& values)
const {
392 return nonDegenerate;
402 return Vector::Zero(
cameras.size() * 2);
412 boost::optional<Point3> externalPoint = boost::none)
const {
424 Unit3 backprojected =
cameras.front().backprojectPointAtInfinity(
434 if (this->
active(values)) {
471 template<
class ARCHIVE>
472 void serialize(ARCHIVE & ar,
const unsigned int version) {
473 ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(
Base);
474 ar & BOOST_SERIALIZATION_NVP(params_);
475 ar & BOOST_SERIALIZATION_NVP(
result_);
482template<
class CAMERA>
484 SmartProjectionFactor<CAMERA> > {
Functions for triangulation.
utility functions for loading datasets
Base class to create smart factors on poses or cameras.
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
TriangulationResult triangulateSafe(const CameraSet< CAMERA > &cameras, const typename CAMERA::MeasurementVector &measured, const TriangulationParameters ¶ms)
triangulateSafe: extensive checking of the outcome
Definition: triangulation.h:444
noiseModel::Base::shared_ptr SharedNoiseModel
Note, deliberately not in noiseModel namespace.
Definition: NoiseModel.h:736
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
Definition: SymmetricBlockMatrix.h:52
A helper that implements the traits interface for GTSAM types.
Definition: Testable.h:151
A set of cameras, all with their own calibration.
Definition: CameraSet.h:35
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
ZVector project2(const POINT &point, boost::optional< FBlocks & > Fs=boost::none, boost::optional< Matrix & > E=boost::none) const
Project a point (possibly Unit3 at infinity), with derivatives Note that F is a sparse block-diagonal...
Definition: CameraSet.h:110
TriangulationResult is an optional point, along with the reasons why it is invalid.
Definition: triangulation.h:373
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
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
Nonlinear factor base class.
Definition: NonlinearFactor.h:43
virtual bool active(const Values &) const
Checks whether a factor should be used based on a set of values.
Definition: NonlinearFactor.h:106
A non-templated config holding any types of Manifold-group elements.
Definition: Values.h:63
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
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
static const int Dim
Camera dimension.
Definition: SmartFactorBase.h:60
virtual Cameras cameras(const Values &values) const
Collect all cameras: important that in key order.
Definition: SmartFactorBase.h:162
double totalReprojectionError(const Cameras &cameras, const POINT &point) const
Calculate the error of the factor.
Definition: SmartFactorBase.h:267
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
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
void whitenJacobians(FBlocks &F, Matrix &E, Vector &b) const
Whiten the Jacobians computed by computeJacobians using noiseModel_.
Definition: SmartFactorBase.h:347
boost::shared_ptr< JacobianFactor > createJacobianSVDFactor(const Cameras &cameras, const Point3 &point, double lambda=0.0) const
Return Jacobians as JacobianFactorSVD.
Definition: SmartFactorBase.h:386
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
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print
Definition: SmartFactorBase.h:174
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
equals
Definition: SmartFactorBase.h:187
Definition: SmartFactorParams.h:42
LinearizationMode linearizationMode
How to linearize the factor.
Definition: SmartFactorParams.h:44
double retriangulationThreshold
threshold to decide whether to re-triangulate
Definition: SmartFactorParams.h:50
DegeneracyMode degeneracyMode
How to linearize the factor.
Definition: SmartFactorParams.h:45
SmartProjectionFactor: triangulates point and keeps an estimate of it around.
Definition: SmartProjectionFactor.h:45
bool decideIfTriangulate(const Cameras &cameras) const
Check if the new linearization point is the same as the one used for previous triangulation.
Definition: SmartProjectionFactor.h:128
boost::shared_ptr< JacobianFactorQ< Base::Dim, 2 > > createJacobianQFactor(const Values &values, double lambda) const
Create JacobianFactorQ factor, takes values.
Definition: SmartProjectionFactor.h:261
boost::shared_ptr< JacobianFactor > createJacobianSVDFactor(const Cameras &cameras, double lambda) const
Different (faster) way to compute a JacobianFactorSVD factor.
Definition: SmartProjectionFactor.h:267
void computeJacobiansWithTriangulatedPoint(typename Base::FBlocks &Fs, Matrix &E, Vector &b, const Cameras &cameras) const
Compute F, E only (called below in both vanilla and SVD versions) Assumes the point has been computed...
Definition: SmartProjectionFactor.h:357
virtual boost::shared_ptr< RegularHessianFactor< Base::Dim > > linearizeToHessian(const Values &values, double lambda=0.0) const
Linearize to a Hessianfactor.
Definition: SmartProjectionFactor.h:277
bool isOutlier() const
return the outlier state
Definition: SmartProjectionFactor.h:462
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print
Definition: SmartProjectionFactor.h:103
bool triangulateAndComputeE(Matrix &E, const Values &values) const
Triangulate and compute derivative of error with respect to point.
Definition: SmartProjectionFactor.h:349
boost::shared_ptr< GaussianFactor > linearizeDamped(const Cameras &cameras, const double lambda=0.0) const
Linearize to Gaussian Factor.
Definition: SmartProjectionFactor.h:299
bool isFarPoint() const
return the farPoint state
Definition: SmartProjectionFactor.h:465
TriangulationResult result_
result from triangulateSafe
Definition: SmartProjectionFactor.h:63
boost::shared_ptr< RegularHessianFactor< Base::Dim > > createHessianFactor(const Cameras &cameras, const double lambda=0.0, bool diagonalDamping=false) const
Create a Hessianfactor that is an approximation of error(p).
Definition: SmartProjectionFactor.h:199
TriangulationResult triangulateSafe(const Cameras &cameras) const
Call gtsam::triangulateSafe iff we need to re-triangulate.
Definition: SmartProjectionFactor.h:174
~SmartProjectionFactor() override
Virtual destructor.
Definition: SmartProjectionFactor.h:95
double error(const Values &values) const override
Calculate total reprojection error.
Definition: SmartProjectionFactor.h:433
bool isValid() const
Is result valid?
Definition: SmartProjectionFactor.h:453
std::vector< Pose3, Eigen::aligned_allocator< Pose3 > > cameraPosesTriangulation_
current triangulation poses
Definition: SmartProjectionFactor.h:65
bool triangulateAndComputeE(Matrix &E, const Cameras &cameras) const
Triangulate and compute derivative of error with respect to point.
Definition: SmartProjectionFactor.h:338
virtual boost::shared_ptr< RegularImplicitSchurFactor< CAMERA > > linearizeToImplicit(const Values &values, double lambda=0.0) const
Linearize to an Implicit Schur factor.
Definition: SmartProjectionFactor.h:283
double totalReprojectionError(const Cameras &cameras, boost::optional< Point3 > externalPoint=boost::none) const
Calculate the error of the factor.
Definition: SmartProjectionFactor.h:411
virtual boost::shared_ptr< JacobianFactorQ< Base::Dim, 2 > > linearizeToJacobian(const Values &values, double lambda=0.0) const
Linearize to a JacobianfactorQ.
Definition: SmartProjectionFactor.h:289
bool isDegenerate() const
return the degenerate state
Definition: SmartProjectionFactor.h:456
bool triangulateAndComputeJacobians(typename Base::FBlocks &Fs, Matrix &E, Vector &b, const Values &values) const
Version that takes values, and creates the point.
Definition: SmartProjectionFactor.h:374
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
equals
Definition: SmartProjectionFactor.h:115
CAMERA Camera
shorthand for a set of cameras
Definition: SmartProjectionFactor.h:74
boost::shared_ptr< JacobianFactorQ< Base::Dim, 2 > > createJacobianQFactor(const Cameras &cameras, double lambda) const
Create JacobianFactorQ factor.
Definition: SmartProjectionFactor.h:251
friend class boost::serialization::access
Serialization function.
Definition: SmartProjectionFactor.h:470
TriangulationResult point(const Values &values) const
COMPUTE the landmark.
Definition: SmartProjectionFactor.h:447
SmartProjectionFactor(const SharedNoiseModel &sharedNoiseModel, const SmartProjectionParams ¶ms=SmartProjectionParams())
Constructor.
Definition: SmartProjectionFactor.h:87
bool isPointBehindCamera() const
return the cheirality status flag
Definition: SmartProjectionFactor.h:459
boost::shared_ptr< GaussianFactor > linearize(const Values &values) const override
linearize
Definition: SmartProjectionFactor.h:329
bool triangulateAndComputeJacobiansSVD(typename Base::FBlocks &Fs, Matrix &Enull, Vector &b, const Values &values) const
takes values
Definition: SmartProjectionFactor.h:385
Vector reprojectionErrorAfterTriangulation(const Values &values) const
Calculate vector of re-projection errors, before applying noise model.
Definition: SmartProjectionFactor.h:396
TriangulationResult point() const
return the landmark
Definition: SmartProjectionFactor.h:442
bool triangulateForLinearize(const Cameras &cameras) const
Possibly re-triangulate before calculating Jacobians.
Definition: SmartProjectionFactor.h:193
boost::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
Definition: SmartProjectionFactor.h:71
SmartProjectionFactor()
Default constructor, only for serialization.
Definition: SmartProjectionFactor.h:80
boost::shared_ptr< GaussianFactor > linearizeDamped(const Values &values, const double lambda=0.0) const
Linearize to Gaussian Factor.
Definition: SmartProjectionFactor.h:321