31#include <gtsam_unstable/dllexport.h>
33#include <boost/make_shared.hpp>
34#include <boost/optional.hpp>
62 const SmartStereoProjectionParams params_;
74 typedef boost::shared_ptr<SmartStereoProjectionFactor>
shared_ptr;
82 typedef MonoCamera::MeasurementVector MonoMeasurements;
89 const SmartStereoProjectionParams& params = SmartStereoProjectionParams(),
90 const boost::optional<Pose3> body_P_sensor = boost::none) :
91 Base(sharedNoiseModel, body_P_sensor),
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;
130 bool retriangulate =
false;
135 retriangulate =
true;
137 if (!retriangulate) {
138 for (
size_t i = 0; i <
cameras.size(); i++) {
140 params_.retriangulationThreshold)) {
141 retriangulate =
true;
150 for (
size_t i = 0; i < m; i++)
155 return retriangulate;
170 MonoCameras monoCameras;
171 MonoMeasurements monoMeasured;
172 for(
size_t i = 0; i < m; i++) {
175 const MonoCamera leftCamera_i(leftPose,monoCal);
177 const Pose3 rightPose = leftPose.compose( left_Pose_right );
178 const MonoCamera rightCamera_i(rightPose,monoCal);
180 monoCameras.push_back(leftCamera_i);
181 monoMeasured.push_back(
Point2(zi.
uL(),zi.
v()));
182 if(!std::isnan(zi.
uR())){
183 monoCameras.push_back(rightCamera_i);
184 monoMeasured.push_back(
Point2(zi.
uR(),zi.
v()));
189 params_.triangulation);
201 const Cameras&
cameras,
const double lambda = 0.0,
bool diagonalDamping =
204 size_t numKeys = this->
keys_.size();
207 std::vector<Matrix> Gs(numKeys * (numKeys + 1) / 2);
208 std::vector<Vector> gs(numKeys);
211 throw std::runtime_error(
"SmartStereoProjectionHessianFactor: this->"
212 "measured_.size() inconsistent with input");
216 if (params_.degeneracyMode == ZERO_ON_DEGENERACY && !
result_) {
222 return boost::make_shared<RegularHessianFactor<Base::Dim> >(this->
keys_,
239 return boost::make_shared<RegularHessianFactor<Base::Dim> >(this->
keys_,
275 return boost::make_shared<JacobianFactorSVD<Base::Dim, ZDim> >(this->
keys_);
302 const double lambda = 0.0)
const {
304 switch (params_.linearizationMode) {
314 throw std::runtime_error(
"SmartStereoFactorlinearize: unknown mode");
324 const double lambda = 0.0)
const {
332 const Values& values)
const override {
344 return nonDegenerate;
362 Matrix& E, Vector& b,
366 throw (
"computeJacobiansWithTriangulatedPoint");
381 FBlocks& Fs, Matrix& E, Vector& b,
382 const Values& values)
const {
387 return nonDegenerate;
392 FBlocks& Fs, Matrix& Enull, Vector& b,
393 const Values& values)
const {
398 return nonDegenerate;
418 boost::optional<Point3> externalPoint = boost::none)
const {
428 else if (params_.degeneracyMode == HANDLE_INFINITY) {
429 throw(std::runtime_error(
"Backproject at infinity not implemented for SmartStereo."));
443 if (this->
active(values)) {
456 boost::optional<typename Cameras::FBlocks&> Fs = boost::none,
457 boost::optional<Matrix&> E = boost::none)
const override {
459 for (
size_t i = 0; i <
cameras.size(); i++) {
461 if (std::isnan(z.
uR()))
464 MatrixZD& Fi = Fs->at(i);
465 for (
size_t ii = 0; ii <
Dim; ii++) Fi(1, ii) = 0.0;
468 E->row(
ZDim * i + 1) = Matrix::Zero(1, E->cols());
471 ue(
ZDim * i + 1) = 0.0;
506 template<
class ARCHIVE>
507 void serialize(ARCHIVE & ar,
const unsigned int ) {
508 ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
509 ar & BOOST_SERIALIZATION_NVP(params_.throwCheirality);
510 ar & BOOST_SERIALIZATION_NVP(params_.verboseCheirality);
517 SmartStereoProjectionFactor> {
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 ¶ms)
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 ¶ms=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