23 #include <gtsam/slam/SmartFactorParams.h> 26 #include <gtsam/inference/Symbol.h> 29 #include <boost/optional.hpp> 30 #include <boost/make_shared.hpp> 44 template<
class CAMERA>
86 const boost::optional<Pose3> body_P_sensor = boost::none,
88 Base(sharedNoiseModel, body_P_sensor), params_(params),
102 DefaultKeyFormatter)
const {
103 std::cout << s <<
"SmartProjectionFactor\n";
106 std::cout <<
"triangulationParameters:\n" << params_.triangulation
108 std::cout <<
"result:\n" <<
result_ << std::endl;
114 const This *e = dynamic_cast<const This*>(&p);
127 bool retriangulate =
false;
132 retriangulate =
true;
134 if (!retriangulate) {
135 for (
size_t i = 0; i <
cameras.size(); i++) {
138 retriangulate =
true;
147 for (
size_t i = 0; i < m; i++)
152 return retriangulate;
160 return TriangulationResult::Degenerate();
165 params_.triangulation);
177 const Cameras&
cameras,
const double lambda = 0.0,
bool diagonalDamping =
180 size_t numKeys = this->
keys_.size();
183 std::vector<Matrix> Gs(numKeys * (numKeys + 1) / 2);
184 std::vector<Vector> gs(numKeys);
186 if (this->
measured_.size() != cameras.size())
187 throw std::runtime_error(
"SmartProjectionHessianFactor: this->measured_" 188 ".size() inconsistent with input");
198 return boost::make_shared<RegularHessianFactor<Base::Dim> >(this->
keys_,
203 std::vector<typename Base::MatrixZD, Eigen::aligned_allocator<typename Base::MatrixZD> > Fblocks;
215 return boost::make_shared<RegularHessianFactor<Base::Dim> >(this->
keys_,
220 boost::shared_ptr<RegularImplicitSchurFactor<CAMERA> > createRegularImplicitSchurFactor(
226 return boost::shared_ptr<RegularImplicitSchurFactor<CAMERA> >();
236 return boost::make_shared<JacobianFactorQ<Base::Dim, 2> >(this->
keys_);
241 const Values& values,
double lambda)
const {
252 return boost::make_shared<JacobianFactorSVD<Base::Dim, 2> >(this->
keys_);
257 const Values& values,
double lambda = 0.0)
const {
263 const Values& values,
double lambda = 0.0)
const {
264 return createRegularImplicitSchurFactor(this->
cameras(values), lambda);
269 const Values& values,
double lambda = 0.0)
const {
279 const double lambda = 0.0)
const {
285 return createRegularImplicitSchurFactor(
cameras, lambda);
291 throw std::runtime_error(
"SmartFactorlinearize: unknown mode");
301 const double lambda = 0.0)
const {
309 const Values& values)
const {
321 return nonDegenerate;
337 std::vector<
typename Base::MatrixZD, Eigen::aligned_allocator<typename Base::MatrixZD> >& Fblocks, Matrix& E, Vector& b,
343 Unit3 backProjected =
cameras[0].backprojectPointAtInfinity(
354 std::vector<
typename Base::MatrixZD, Eigen::aligned_allocator<typename Base::MatrixZD> >& Fblocks, Matrix& E, Vector& b,
355 const Values& values)
const {
360 return nonDegenerate;
365 std::vector<
typename Base::MatrixZD, Eigen::aligned_allocator<typename Base::MatrixZD> >& Fblocks, Matrix& Enull, Vector& b,
366 const Values& values)
const {
371 return nonDegenerate;
381 return Vector::Zero(
cameras.size() * 2);
391 boost::optional<Point3> externalPoint = boost::none)
const {
403 Unit3 backprojected =
cameras.front().backprojectPointAtInfinity(
413 if (this->
active(values)) {
449 friend class boost::serialization::access;
450 template<
class ARCHIVE>
451 void serialize(ARCHIVE & ar,
const unsigned int version) {
452 ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(
Base);
453 ar & BOOST_SERIALIZATION_NVP(params_);
454 ar & BOOST_SERIALIZATION_NVP(
result_);
461 template<
class CAMERA>
463 SmartProjectionFactor<CAMERA> > {
SmartProjectionFactor(const SharedNoiseModel &sharedNoiseModel, const boost::optional< Pose3 > body_P_sensor=boost::none, const SmartProjectionParams ¶ms=SmartProjectionParams())
Constructor.
Definition: SmartProjectionFactor.h:85
This is the base class for all factor types.
Definition: Factor.h:54
void computeJacobiansWithTriangulatedPoint(std::vector< typename Base::MatrixZD, Eigen::aligned_allocator< typename Base::MatrixZD > > &Fblocks, 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:336
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
print
Definition: SmartProjectionFactor.h:101
Functions for triangulation.
A non-templated config holding any types of Manifold-group elements.
Definition: Values.h:70
bool isValid() const
Is result valid?
Definition: SmartProjectionFactor.h:432
boost::shared_ptr< GaussianFactor > linearizeDamped(const Cameras &cameras, const double lambda=0.0) const
Linearize to Gaussian Factor.
Definition: SmartProjectionFactor.h:278
bool isPointBehindCamera() const
return the cheirality status flag
Definition: SmartProjectionFactor.h:438
Base class to create smart factors on poses or cameras.
LinearizationMode linearizationMode
How to linearize the factor.
Definition: SmartFactorParams.h:44
utility functions for loading datasets
bool triangulateAndComputeJacobians(std::vector< typename Base::MatrixZD, Eigen::aligned_allocator< typename Base::MatrixZD > > &Fblocks, Matrix &E, Vector &b, const Values &values) const
Version that takes values, and creates the point.
Definition: SmartProjectionFactor.h:353
virtual boost::shared_ptr< RegularHessianFactor< Base::Dim > > linearizeToHessian(const Values &values, double lambda=0.0) const
linearize to a Hessianfactor
Definition: SmartProjectionFactor.h:256
DegeneracyMode degeneracyMode
How to linearize the factor.
Definition: SmartFactorParams.h:45
bool triangulateAndComputeE(Matrix &E, const Values &values) const
Triangulate and compute derivative of error with respect to point.
Definition: SmartProjectionFactor.h:328
virtual boost::shared_ptr< JacobianFactorQ< Base::Dim, 2 > > linearizeToJacobian(const Values &values, double lambda=0.0) const
linearize to a JacobianfactorQ
Definition: SmartProjectionFactor.h:268
A set of cameras, all with their own calibration.
Definition: CameraSet.h:35
double totalReprojectionError(const Cameras &cameras, boost::optional< Point3 > externalPoint=boost::none) const
Calculate the error of the factor.
Definition: SmartProjectionFactor.h:390
SmartProjectionFactor: triangulates point and keeps an estimate of it around.
Definition: SmartProjectionFactor.h:45
bool triangulateForLinearize(const Cameras &cameras) const
triangulate
Definition: SmartProjectionFactor.h:170
bool equals(const CameraSet &p, double tol=1e-9) const
equals
Definition: CameraSet.h:88
void computeJacobiansSVD(FBlocks &Fs, Matrix &Enull, Vector &b, const Cameras &cameras, const POINT &point) const
SVD version.
Definition: SmartFactorBase.h:274
double totalReprojectionError(const Cameras &cameras, const POINT &point) const
Calculate the error of the factor.
Definition: SmartFactorBase.h:245
CameraSet< CAMERA > Cameras
shorthand for a set of cameras
Definition: SmartProjectionFactor.h:73
Vector reprojectionErrorAfterTriangulation(const Values &values) const
Calculate vector of re-projection errors, before applying noise model.
Definition: SmartProjectionFactor.h:375
virtual Cameras cameras(const Values &values) const
Collect all cameras: important that in key order.
Definition: SmartFactorBase.h:164
bool isOutlier() const
return the outlier state
Definition: SmartProjectionFactor.h:441
double retriangulationThreshold
threshold to decide whether to re-triangulate
Definition: SmartFactorParams.h:50
A helper that implements the traits interface for GTSAM types.
Definition: Testable.h:150
bool triangulateAndComputeJacobiansSVD(std::vector< typename Base::MatrixZD, Eigen::aligned_allocator< typename Base::MatrixZD > > &Fblocks, Matrix &Enull, Vector &b, const Values &values) const
takes values
Definition: SmartProjectionFactor.h:364
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:330
boost::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:33
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:263
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:107
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:203
Nonlinear factor base class.
Definition: NonlinearFactor.h:50
virtual ~SmartProjectionFactor()
Virtual destructor.
Definition: SmartProjectionFactor.h:93
TriangulationResult triangulateSafe(const CameraSet< CAMERA > &cameras, const typename CAMERA::MeasurementVector &measured, const TriangulationParameters ¶ms)
triangulateSafe: extensive checking of the outcome
Definition: triangulation.h:460
bool isDegenerate() const
return the degenerate state
Definition: SmartProjectionFactor.h:435
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
Definition: SmartFactorParams.h:42
virtual boost::shared_ptr< GaussianFactor > linearize(const Values &values) const
linearize
Definition: SmartProjectionFactor.h:308
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:56
A manifold defines a space in which there is a notion of a linear tangent space that can be centered ...
Definition: concepts.h:30
boost::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
Definition: SmartProjectionFactor.h:70
TriangulationResult is an optional point, along with the reasons why it is invalid.
Definition: triangulation.h:389
virtual bool equals(const NonlinearFactor &p, double tol=1e-9) const
equals
Definition: SmartFactorBase.h:189
TriangulationResult result_
result from triangulateSafe
Definition: SmartProjectionFactor.h:63
Base class for smart factors This base class has no internal point, but it has a measurement,...
Definition: SmartFactorBase.h:47
boost::shared_ptr< GaussianFactor > linearizeDamped(const Values &values, const double lambda=0.0) const
Linearize to Gaussian Factor.
Definition: SmartProjectionFactor.h:300
static SymmetricBlockMatrix SchurComplement(const FBlocks &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:149
virtual bool active(const Values &) const
Checks whether a factor should be used based on a set of values.
Definition: NonlinearFactor.h:113
boost::shared_ptr< JacobianFactor > createJacobianSVDFactor(const Cameras &cameras, double lambda) const
different (faster) way to compute Jacobian factor
Definition: SmartProjectionFactor.h:246
Definition: SymmetricBlockMatrix.h:51
TriangulationResult point() const
return the landmark
Definition: SmartProjectionFactor.h:421
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
print
Definition: SmartFactorBase.h:176
virtual boost::shared_ptr< RegularImplicitSchurFactor< CAMERA > > linearizeToImplicit(const Values &values, double lambda=0.0) const
linearize to an Implicit Schur factor
Definition: SmartProjectionFactor.h:262
noiseModel::Base::shared_ptr SharedNoiseModel
Note, deliberately not in noiseModel namespace.
Definition: NoiseModel.h:1072
KeyVector keys_
The keys involved in this factor.
Definition: Factor.h:72
boost::shared_ptr< JacobianFactor > createJacobianSVDFactor(const Cameras &cameras, const Point3 &point, double lambda=0.0) const
Return Jacobians as JacobianFactorSVD TODO lambda is currently ignored.
Definition: SmartFactorBase.h:362
bool isFarPoint() const
return the farPoint state
Definition: SmartProjectionFactor.h:444
virtual double error(const Values &values) const
Calculate total reprojection error.
Definition: SmartProjectionFactor.h:412
TriangulationResult triangulateSafe(const Cameras &cameras) const
triangulateSafe
Definition: SmartProjectionFactor.h:156
bool triangulateAndComputeE(Matrix &E, const Cameras &cameras) const
Triangulate and compute derivative of error with respect to point.
Definition: SmartProjectionFactor.h:317
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:345
std::vector< Pose3, Eigen::aligned_allocator< Pose3 > > cameraPosesTriangulation_
current triangulation poses
Definition: SmartProjectionFactor.h:64
SmartProjectionFactor()
Default constructor, only for serialization.
Definition: SmartProjectionFactor.h:78
boost::shared_ptr< JacobianFactorQ< Base::Dim, 2 > > createJacobianQFactor(const Cameras &cameras, double lambda) const
create factor
Definition: SmartProjectionFactor.h:230
static const int Dim
Camera dimension.
Definition: SmartFactorBase.h:57
virtual bool equals(const NonlinearFactor &p, double tol=1e-9) const
equals
Definition: SmartProjectionFactor.h:113
void whitenJacobians(FBlocks &F, Matrix &E, Vector &b) const
Whiten the Jacobians computed by computeJacobians using noiseModel_.
Definition: SmartFactorBase.h:321
boost::shared_ptr< JacobianFactorQ< Base::Dim, 2 > > createJacobianQFactor(const Values &values, double lambda) const
Create a factor, takes values.
Definition: SmartProjectionFactor.h:240
boost::shared_ptr< RegularHessianFactor< Base::Dim > > createHessianFactor(const Cameras &cameras, const double lambda=0.0, bool diagonalDamping=false) const
linearize returns a Hessianfactor that is an approximation of error(p)
Definition: SmartProjectionFactor.h:176
TriangulationResult point(const Values &values) const
COMPUTE the landmark.
Definition: SmartProjectionFactor.h:426
ZVector measured_
2D measurement and noise model for each of the m views We keep a copy of measurements for I/O and com...
Definition: SmartFactorBase.h:76
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:120