gtsam 4.2
gtsam
Loading...
Searching...
No Matches
SmartStereoProjectionFactor.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
20
21#pragma once
22
30#include <gtsam/slam/dataset.h>
31#include <gtsam_unstable/dllexport.h>
32
33#include <boost/make_shared.hpp>
34#include <boost/optional.hpp>
35#include <vector>
36
37namespace gtsam {
38
39/*
40 * Parameters for the smart stereo projection factors (identical to the SmartProjectionParams)
41 */
42typedef SmartProjectionParams SmartStereoProjectionParams;
43
53 : public SmartFactorBase<StereoCamera> {
54 private:
55
57
58protected:
59
62 const SmartStereoProjectionParams params_;
64
68 mutable std::vector<Pose3> cameraPosesTriangulation_;
70
71public:
72
74 typedef boost::shared_ptr<SmartStereoProjectionFactor> shared_ptr;
75
78
81 typedef CameraSet<MonoCamera> MonoCameras;
82 typedef MonoCamera::MeasurementVector MonoMeasurements;
83
89 const SmartStereoProjectionParams& params = SmartStereoProjectionParams(),
90 const boost::optional<Pose3> body_P_sensor = boost::none) :
91 Base(sharedNoiseModel, body_P_sensor), //
92 params_(params), //
93 result_(TriangulationResult::Degenerate()) {
94 }
95
99
105 void print(const std::string& s = "", const KeyFormatter& keyFormatter =
106 DefaultKeyFormatter) const override {
107 std::cout << s << "SmartStereoProjectionFactor\n";
108 std::cout << "linearizationMode:\n" << params_.linearizationMode << std::endl;
109 std::cout << "triangulationParameters:\n" << params_.triangulation << std::endl;
110 std::cout << "result:\n" << result_ << std::endl;
111 Base::print("", keyFormatter);
112 }
113
115 bool equals(const NonlinearFactor& p, double tol = 1e-9) const override {
117 dynamic_cast<const SmartStereoProjectionFactor*>(&p);
118 return e && params_.linearizationMode == e->params_.linearizationMode
119 && Base::equals(p, tol);
120 }
121
124 // several calls to linearize will be done from the same linearization point_, hence it is not needed to re-triangulate
125 // Note that this is not yet "selecting linearization", that will come later, and we only check if the
126 // current linearization is the "same" (up to tolerance) w.r.t. the last time we triangulated the point_
127
128 size_t m = cameras.size();
129
130 bool retriangulate = false;
131
132 // if we do not have a previous linearization point_ or the new linearization point_ includes more poses
133 if (cameraPosesTriangulation_.empty()
134 || cameras.size() != cameraPosesTriangulation_.size())
135 retriangulate = true;
136
137 if (!retriangulate) {
138 for (size_t i = 0; i < cameras.size(); i++) {
139 if (!cameras[i].pose().equals(cameraPosesTriangulation_[i],
140 params_.retriangulationThreshold)) {
141 retriangulate = true; // at least two poses are different, hence we retriangulate
142 break;
143 }
144 }
145 }
146
147 if (retriangulate) { // we store the current poses used for triangulation
149 cameraPosesTriangulation_.reserve(m);
150 for (size_t i = 0; i < m; i++)
151 // cameraPosesTriangulation_[i] = cameras[i].pose();
152 cameraPosesTriangulation_.push_back(cameras[i].pose());
153 }
154
155 return retriangulate; // if we arrive to this point_ all poses are the same and we don't need re-triangulation
156 }
157
158// /// triangulateSafe
159// size_t triangulateSafe(const Values& values) const {
160// return triangulateSafe(this->cameras(values));
161// }
162
165
166 size_t m = cameras.size();
167 bool retriangulate = decideIfTriangulate(cameras);
168
169 // triangulate stereo measurements by treating each stereocamera as a pair of monocular cameras
170 MonoCameras monoCameras;
171 MonoMeasurements monoMeasured;
172 for(size_t i = 0; i < m; i++) {
173 const Pose3 leftPose = cameras[i].pose();
174 const Cal3_S2 monoCal = cameras[i].calibration().calibration();
175 const MonoCamera leftCamera_i(leftPose,monoCal);
176 const Pose3 left_Pose_right = Pose3(Rot3(),Point3(cameras[i].baseline(),0.0,0.0));
177 const Pose3 rightPose = leftPose.compose( left_Pose_right );
178 const MonoCamera rightCamera_i(rightPose,monoCal);
179 const StereoPoint2 zi = measured_[i];
180 monoCameras.push_back(leftCamera_i);
181 monoMeasured.push_back(Point2(zi.uL(),zi.v()));
182 if(!std::isnan(zi.uR())){ // if right point is valid
183 monoCameras.push_back(rightCamera_i);
184 monoMeasured.push_back(Point2(zi.uR(),zi.v()));
185 }
186 }
187 if (retriangulate)
188 result_ = gtsam::triangulateSafe(monoCameras, monoMeasured,
189 params_.triangulation);
190 return result_;
191 }
192
195 triangulateSafe(cameras); // imperative, might reset result_
196 return bool(result_);
197 }
198
200 boost::shared_ptr<RegularHessianFactor<Base::Dim> > createHessianFactor(
201 const Cameras& cameras, const double lambda = 0.0, bool diagonalDamping =
202 false) const {
203
204 size_t numKeys = this->keys_.size();
205 // Create structures for Hessian Factors
206 KeyVector js;
207 std::vector<Matrix> Gs(numKeys * (numKeys + 1) / 2);
208 std::vector<Vector> gs(numKeys);
209
210 if (this->measured_.size() != cameras.size())
211 throw std::runtime_error("SmartStereoProjectionHessianFactor: this->"
212 "measured_.size() inconsistent with input");
213
215
216 if (params_.degeneracyMode == ZERO_ON_DEGENERACY && !result_) {
217 // failed: return"empty" Hessian
218 for(Matrix& m: Gs)
219 m = Matrix::Zero(Base::Dim, Base::Dim);
220 for(Vector& v: gs)
221 v = Vector::Zero(Base::Dim);
222 return boost::make_shared<RegularHessianFactor<Base::Dim> >(this->keys_,
223 Gs, gs, 0.0);
224 }
225
226 // Jacobian could be 3D Point3 OR 2D Unit3, difference is E.cols().
227 Base::FBlocks Fs;
228 Matrix F, E;
229 Vector b;
231
232 // Whiten using noise model
233 Base::whitenJacobians(Fs, E, b);
234
235 // build augmented hessian
236 SymmetricBlockMatrix augmentedHessian = //
237 Cameras::SchurComplement(Fs, E, b, lambda, diagonalDamping);
238
239 return boost::make_shared<RegularHessianFactor<Base::Dim> >(this->keys_,
240 augmentedHessian);
241 }
242
243 // create factor
244// boost::shared_ptr<RegularImplicitSchurFactor<StereoCamera> > createRegularImplicitSchurFactor(
245// const Cameras& cameras, double lambda) const {
246// if (triangulateForLinearize(cameras))
247// return Base::createRegularImplicitSchurFactor(cameras, *result_, lambda);
248// else
249// // failed: return empty
250// return boost::shared_ptr<RegularImplicitSchurFactor<StereoCamera> >();
251// }
252//
253// /// create factor
254// boost::shared_ptr<JacobianFactorQ<Base::Dim, Base::ZDim> > createJacobianQFactor(
255// const Cameras& cameras, double lambda) const {
256// if (triangulateForLinearize(cameras))
257// return Base::createJacobianQFactor(cameras, *result_, lambda);
258// else
259// // failed: return empty
260// return boost::make_shared<JacobianFactorQ<Base::Dim, Base::ZDim> >(this->keys_);
261// }
262//
263// /// Create a factor, takes values
264// boost::shared_ptr<JacobianFactorQ<Base::Dim, Base::ZDim> > createJacobianQFactor(
265// const Values& values, double lambda) const {
266// return createJacobianQFactor(this->cameras(values), lambda);
267// }
268
270 boost::shared_ptr<JacobianFactor> createJacobianSVDFactor(
271 const Cameras& cameras, double lambda) const {
274 else
275 return boost::make_shared<JacobianFactorSVD<Base::Dim, ZDim> >(this->keys_);
276 }
277
278// /// linearize to a Hessianfactor
279// virtual boost::shared_ptr<RegularHessianFactor<Base::Dim> > linearizeToHessian(
280// const Values& values, double lambda = 0.0) const {
281// return createHessianFactor(this->cameras(values), lambda);
282// }
283
284// /// linearize to an Implicit Schur factor
285// virtual boost::shared_ptr<RegularImplicitSchurFactor<StereoCamera> > linearizeToImplicit(
286// const Values& values, double lambda = 0.0) const {
287// return createRegularImplicitSchurFactor(this->cameras(values), lambda);
288// }
289//
290// /// linearize to a JacobianfactorQ
291// virtual boost::shared_ptr<JacobianFactorQ<Base::Dim, Base::ZDim> > linearizeToJacobian(
292// const Values& values, double lambda = 0.0) const {
293// return createJacobianQFactor(this->cameras(values), lambda);
294// }
295
301 boost::shared_ptr<GaussianFactor> linearizeDamped(const Cameras& cameras,
302 const double lambda = 0.0) const {
303 // depending on flag set on construction we may linearize to different linear factors
304 switch (params_.linearizationMode) {
305 case HESSIAN:
306 return createHessianFactor(cameras, lambda);
307// case IMPLICIT_SCHUR:
308// return createRegularImplicitSchurFactor(cameras, lambda);
309 case JACOBIAN_SVD:
310 return createJacobianSVDFactor(cameras, lambda);
311// case JACOBIAN_Q:
312// return createJacobianQFactor(cameras, lambda);
313 default:
314 throw std::runtime_error("SmartStereoFactorlinearize: unknown mode");
315 }
316 }
317
323 boost::shared_ptr<GaussianFactor> linearizeDamped(const Values& values,
324 const double lambda = 0.0) const {
325 // depending on flag set on construction we may linearize to different linear factors
326 Cameras cameras = this->cameras(values);
327 return linearizeDamped(cameras, lambda);
328 }
329
331 boost::shared_ptr<GaussianFactor> linearize(
332 const Values& values) const override {
333 return linearizeDamped(values);
334 }
335
340 bool triangulateAndComputeE(Matrix& E, const Cameras& cameras) const {
341 bool nonDegenerate = triangulateForLinearize(cameras);
342 if (nonDegenerate)
343 cameras.project2(*result_, boost::none, E);
344 return nonDegenerate;
345 }
346
351 bool triangulateAndComputeE(Matrix& E, const Values& values) const {
352 Cameras cameras = this->cameras(values);
354 }
355
356
361 FBlocks& Fs,
362 Matrix& E, Vector& b,
363 const Cameras& cameras) const {
364
365 if (!result_) {
366 throw ("computeJacobiansWithTriangulatedPoint");
367// // Handle degeneracy
368// // TODO check flag whether we should do this
369// Unit3 backProjected; /* = cameras[0].backprojectPointAtInfinity(
370// this->measured_.at(0)); */
371//
372// Base::computeJacobians(Fs, E, b, cameras, backProjected);
373 } else {
374 // valid result: just return Base version
376 }
377 }
378
381 FBlocks& Fs, Matrix& E, Vector& b,
382 const Values& values) const {
383 Cameras cameras = this->cameras(values);
384 bool nonDegenerate = triangulateForLinearize(cameras);
385 if (nonDegenerate)
387 return nonDegenerate;
388 }
389
392 FBlocks& Fs, Matrix& Enull, Vector& b,
393 const Values& values) const {
394 Cameras cameras = this->cameras(values);
395 bool nonDegenerate = triangulateForLinearize(cameras);
396 if (nonDegenerate)
398 return nonDegenerate;
399 }
400
402 Vector reprojectionErrorAfterTriangulation(const Values& values) const {
403 Cameras cameras = this->cameras(values);
404 bool nonDegenerate = triangulateForLinearize(cameras);
405 if (nonDegenerate)
407 else
408 return Vector::Zero(cameras.size() * Base::ZDim);
409 }
410
418 boost::optional<Point3> externalPoint = boost::none) const {
419
420 if (externalPoint)
421 result_ = TriangulationResult(*externalPoint);
422 else
424
425 if (result_)
426 // All good, just use version in base class
428 else if (params_.degeneracyMode == HANDLE_INFINITY) {
429 throw(std::runtime_error("Backproject at infinity not implemented for SmartStereo."));
430// // Otherwise, manage the exceptions with rotation-only factors
431// const StereoPoint2& z0 = this->measured_.at(0);
432// Unit3 backprojected; //= cameras.front().backprojectPointAtInfinity(z0);
433//
434// return Base::totalReprojectionError(cameras, backprojected);
435 } else {
436 // if we don't want to manage the exceptions we discard the factor
437 return 0.0;
438 }
439 }
440
442 double error(const Values& values) const override {
443 if (this->active(values)) {
445 } else { // else of active flag
446 return 0.0;
447 }
448 }
449
455 const Cameras& cameras, Vector& ue,
456 boost::optional<typename Cameras::FBlocks&> Fs = boost::none,
457 boost::optional<Matrix&> E = boost::none) const override {
458 // when using stereo cameras, some of the measurements might be missing:
459 for (size_t i = 0; i < cameras.size(); i++) {
460 const StereoPoint2& z = measured_.at(i);
461 if (std::isnan(z.uR())) // if the right 2D measurement is invalid
462 {
463 if (Fs) { // delete influence of right point on jacobian Fs
464 MatrixZD& Fi = Fs->at(i);
465 for (size_t ii = 0; ii < Dim; ii++) Fi(1, ii) = 0.0;
466 }
467 if (E) // delete influence of right point on jacobian E
468 E->row(ZDim * i + 1) = Matrix::Zero(1, E->cols());
469
470 // set the corresponding entry of vector ue to zero
471 ue(ZDim * i + 1) = 0.0;
472 }
473 }
474 }
475
478 return result_;
479 }
480
482 TriangulationResult point(const Values& values) const {
483 Cameras cameras = this->cameras(values);
484 return triangulateSafe(cameras);
485 }
486
488 bool isValid() const { return result_.valid(); }
489
491 bool isDegenerate() const { return result_.degenerate(); }
492
494 bool isPointBehindCamera() const { return result_.behindCamera(); }
495
497 bool isOutlier() const { return result_.outlier(); }
498
500 bool isFarPoint() const { return result_.farPoint(); }
501
502private:
503
506 template<class ARCHIVE>
507 void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
508 ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
509 ar & BOOST_SERIALIZATION_NVP(params_.throwCheirality);
510 ar & BOOST_SERIALIZATION_NVP(params_.verboseCheirality);
511 }
512};
513
515template<>
517 SmartStereoProjectionFactor> {
518};
519
520} // \ namespace gtsam
3D Pose
Functions for triangulation.
A Stereo Camera based on two Simple Cameras.
A non-linear factor for stereo measurements.
utility functions for loading datasets
Base class to create smart factors on poses or cameras.
Collect common parameters for SmartProjection and SmartStereoProjection factors.
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
Vector2 Point2
As of GTSAM 4, in order to make GTSAM more lean, it is now possible to just typedef Point2 to Vector2...
Definition Point2.h:27
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
TriangulationResult triangulateSafe(const CameraSet< CAMERA > &cameras, const typename CAMERA::MeasurementVector &measured, const TriangulationParameters &params)
triangulateSafe: extensive checking of the outcome
Definition triangulation.h:680
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:36
noiseModel::Base::shared_ptr SharedNoiseModel
Aliases.
Definition NoiseModel.h:724
A manifold defines a space in which there is a notion of a linear tangent space that can be centered ...
Definition concepts.h:30
This class stores a dense matrix and allows it to be accessed as a collection of blocks.
Definition SymmetricBlockMatrix.h:52
A helper that implements the traits interface for GTSAM types.
Definition Testable.h:151
The most common 5DOF 3D->2D calibration.
Definition Cal3_S2.h:34
A set of cameras, all with their own calibration.
Definition CameraSet.h:36
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:150
A pinhole camera class that has a Pose3 and a Calibration.
Definition PinholeCamera.h:33
A 3D pose (R,t) : (Rot3,Point3).
Definition Pose3.h:37
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition Rot3.h:58
A 2D stereo point, v will be same for rectified images.
Definition StereoPoint2.h:32
double uR() const
get uR
Definition StereoPoint2.h:109
double uL() const
get uL
Definition StereoPoint2.h:106
double v() const
get v
Definition StereoPoint2.h:112
TriangulationResult is an optional point, along with the reasons why it is invalid.
Definition triangulation.h:626
KeyVector keys_
The keys involved in this factor.
Definition Factor.h:85
Nonlinear factor base class.
Definition NonlinearFactor.h:42
virtual bool active(const Values &) const
Checks whether a factor should be used based on a set of values.
Definition NonlinearFactor.h:118
A non-templated config holding any types of Manifold-group elements.
Definition Values.h:65
void computeJacobians(FBlocks &Fs, Matrix &E, Vector &b, const Cameras &cameras, const POINT &point) const
Definition SmartFactorBase.h:285
static const int Dim
Definition SmartFactorBase.h:60
virtual Cameras cameras(const Values &values) const
Definition SmartFactorBase.h:162
double totalReprojectionError(const Cameras &cameras, const POINT &point) const
Definition SmartFactorBase.h:267
void computeJacobiansSVD(FBlocks &Fs, Matrix &Enull, Vector &b, const Cameras &cameras, const POINT &point) const
Definition SmartFactorBase.h:300
ZVector measured_
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
Definition SmartFactorBase.h:204
SmartFactorBase()
Definition SmartFactorBase.h:97
void whitenJacobians(FBlocks &F, Matrix &E, Vector &b) const
Definition SmartFactorBase.h:347
boost::shared_ptr< JacobianFactor > createJacobianSVDFactor(const Cameras &cameras, const Point3 &point, double lambda=0.0) const
Definition SmartFactorBase.h:386
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Definition SmartFactorBase.h:174
static const int ZDim
Definition SmartFactorBase.h:61
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
Definition SmartFactorBase.h:187
Definition SmartFactorParams.h:42
LinearizationMode linearizationMode
How to linearize the factor.
Definition SmartFactorParams.h:44
SmartStereoProjectionFactor: triangulates point and keeps an estimate of it around.
Definition SmartStereoProjectionFactor.h:53
boost::shared_ptr< GaussianFactor > linearizeDamped(const Values &values, const double lambda=0.0) const
Linearize to Gaussian Factor.
Definition SmartStereoProjectionFactor.h:323
void computeJacobiansWithTriangulatedPoint(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 SmartStereoProjectionFactor.h:360
bool decideIfTriangulate(const Cameras &cameras) const
Check if the new linearization point_ is the same as the one used for previous triangulation.
Definition SmartStereoProjectionFactor.h:123
boost::shared_ptr< GaussianFactor > linearize(const Values &values) const override
linearize
Definition SmartStereoProjectionFactor.h:331
~SmartStereoProjectionFactor() override
Virtual destructor.
Definition SmartStereoProjectionFactor.h:97
boost::shared_ptr< JacobianFactor > createJacobianSVDFactor(const Cameras &cameras, double lambda) const
different (faster) way to compute Jacobian factor
Definition SmartStereoProjectionFactor.h:270
void correctForMissingMeasurements(const Cameras &cameras, Vector &ue, boost::optional< typename Cameras::FBlocks & > Fs=boost::none, boost::optional< Matrix & > E=boost::none) const override
This corrects the Jacobians and error vector for the case in which the right 2D measurement in the mo...
Definition SmartStereoProjectionFactor.h:454
boost::shared_ptr< SmartStereoProjectionFactor > shared_ptr
shorthand for a smart pointer to a factor
Definition SmartStereoProjectionFactor.h:74
TriangulationResult triangulateSafe(const Cameras &cameras) const
triangulateSafe
Definition SmartStereoProjectionFactor.h:164
Vector reprojectionErrorAfterTriangulation(const Values &values) const
Calculate vector of re-projection errors, before applying noise model.
Definition SmartStereoProjectionFactor.h:402
std::vector< Pose3 > cameraPosesTriangulation_
current triangulation poses
Definition SmartStereoProjectionFactor.h:68
double totalReprojectionError(const Cameras &cameras, boost::optional< Point3 > externalPoint=boost::none) const
Calculate the error of the factor.
Definition SmartStereoProjectionFactor.h:417
TriangulationResult result_
result from triangulateSafe
Definition SmartStereoProjectionFactor.h:67
PinholeCamera< Cal3_S2 > MonoCamera
Vector of monocular cameras (stereo treated as 2 monocular).
Definition SmartStereoProjectionFactor.h:80
bool isOutlier() const
return the outlier state
Definition SmartStereoProjectionFactor.h:497
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
equals
Definition SmartStereoProjectionFactor.h:115
double error(const Values &values) const override
Calculate total reprojection error.
Definition SmartStereoProjectionFactor.h:442
bool triangulateAndComputeE(Matrix &E, const Values &values) const
Triangulate and compute derivative of error with respect to point.
Definition SmartStereoProjectionFactor.h:351
SmartStereoProjectionFactor(const SharedNoiseModel &sharedNoiseModel, const SmartStereoProjectionParams &params=SmartStereoProjectionParams(), const boost::optional< Pose3 > body_P_sensor=boost::none)
Constructor.
Definition SmartStereoProjectionFactor.h:88
bool triangulateAndComputeJacobians(FBlocks &Fs, Matrix &E, Vector &b, const Values &values) const
Version that takes values, and creates the point.
Definition SmartStereoProjectionFactor.h:380
friend class boost::serialization::access
Serialization function.
Definition SmartStereoProjectionFactor.h:505
CameraSet< StereoCamera > Cameras
Vector of cameras.
Definition SmartStereoProjectionFactor.h:77
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print
Definition SmartStereoProjectionFactor.h:105
boost::shared_ptr< GaussianFactor > linearizeDamped(const Cameras &cameras, const double lambda=0.0) const
Linearize to Gaussian Factor.
Definition SmartStereoProjectionFactor.h:301
bool isDegenerate() const
return the degenerate state
Definition SmartStereoProjectionFactor.h:491
TriangulationResult point() const
return the landmark
Definition SmartStereoProjectionFactor.h:477
bool triangulateAndComputeJacobiansSVD(FBlocks &Fs, Matrix &Enull, Vector &b, const Values &values) const
takes values
Definition SmartStereoProjectionFactor.h:391
bool isPointBehindCamera() const
return the cheirality status flag
Definition SmartStereoProjectionFactor.h:494
bool triangulateAndComputeE(Matrix &E, const Cameras &cameras) const
Triangulate and compute derivative of error with respect to point.
Definition SmartStereoProjectionFactor.h:340
bool triangulateForLinearize(const Cameras &cameras) const
triangulate
Definition SmartStereoProjectionFactor.h:194
bool isFarPoint() const
return the farPoint state
Definition SmartStereoProjectionFactor.h:500
bool isValid() const
Is result valid?
Definition SmartStereoProjectionFactor.h:488
TriangulationResult point(const Values &values) const
COMPUTE the landmark.
Definition SmartStereoProjectionFactor.h:482
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 SmartStereoProjectionFactor.h:200