24 #include <gtsam/slam/SmartFactorParams.h> 29 #include <gtsam/slam/StereoFactor.h> 30 #include <gtsam/inference/Symbol.h> 33 #include <boost/optional.hpp> 34 #include <boost/make_shared.hpp> 42 typedef SmartProjectionParams SmartStereoProjectionParams;
73 typedef boost::shared_ptr<SmartStereoProjectionFactor>
shared_ptr;
81 typedef MonoCamera::MeasurementVector MonoMeasurements;
89 const boost::optional<Pose3> body_P_sensor = boost::none) :
90 Base(sharedNoiseModel, body_P_sensor),
105 DefaultKeyFormatter)
const {
106 std::cout << s <<
"SmartStereoProjectionFactor\n";
108 std::cout <<
"triangulationParameters:\n" << params_.triangulation << std::endl;
109 std::cout <<
"result:\n" <<
result_ << std::endl;
116 dynamic_cast<const SmartStereoProjectionFactor*>(&p);
129 bool retriangulate =
false;
134 retriangulate =
true;
136 if (!retriangulate) {
137 for (
size_t i = 0; i <
cameras.size(); i++) {
140 retriangulate =
true;
149 for (
size_t i = 0; i < m; i++)
154 return retriangulate;
170 MonoMeasurements monoMeasured;
171 for(
size_t i = 0; i < m; i++) {
174 const MonoCamera leftCamera_i(leftPose,monoCal);
176 const Pose3 rightPose = leftPose.compose( left_Pose_right );
177 const MonoCamera rightCamera_i(rightPose,monoCal);
179 monoCameras.push_back(leftCamera_i);
180 monoMeasured.push_back(
Point2(zi.
uL(),zi.
v()));
181 if(!std::isnan(zi.
uR())){
182 monoCameras.push_back(rightCamera_i);
183 monoMeasured.push_back(
Point2(zi.
uR(),zi.
v()));
188 params_.triangulation);
200 const Cameras&
cameras,
const double lambda = 0.0,
bool diagonalDamping =
203 size_t numKeys = this->
keys_.size();
206 std::vector<Matrix> Gs(numKeys * (numKeys + 1) / 2);
207 std::vector<Vector> gs(numKeys);
209 if (this->
measured_.size() != cameras.size())
210 throw std::runtime_error(
"SmartStereoProjectionHessianFactor: this->" 211 "measured_.size() inconsistent with input");
221 return boost::make_shared<RegularHessianFactor<Base::Dim> >(this->
keys_,
238 return boost::make_shared<RegularHessianFactor<Base::Dim> >(this->
keys_,
274 return boost::make_shared<JacobianFactorSVD<Base::Dim, ZDim> >(this->
keys_);
301 const double lambda = 0.0)
const {
313 throw std::runtime_error(
"SmartStereoFactorlinearize: unknown mode");
323 const double lambda = 0.0)
const {
331 const Values& values)
const {
343 return nonDegenerate;
361 Matrix& E, Vector& b,
365 throw (
"computeJacobiansWithTriangulatedPoint");
380 FBlocks& Fs, Matrix& E, Vector& b,
381 const Values& values)
const {
386 return nonDegenerate;
391 FBlocks& Fs, Matrix& Enull, Vector& b,
392 const Values& values)
const {
397 return nonDegenerate;
417 boost::optional<Point3> externalPoint = boost::none)
const {
428 throw(std::runtime_error(
"Backproject at infinity not implemented for SmartStereo."));
442 if (this->
active(values)) {
453 boost::optional<typename Cameras::FBlocks&> Fs = boost::none,
454 boost::optional<Matrix&> E = boost::none)
const 457 for(
size_t i=0; i <
cameras.size(); i++){
459 if(std::isnan(z.
uR()))
462 MatrixZD& Fi = Fs->at(i);
463 for(
size_t ii=0; ii<
Dim; ii++)
467 E->row(
ZDim * i + 1) = Matrix::Zero(1, E->cols());
470 ue(
ZDim * i + 1) = 0.0;
505 template<
class ARCHIVE>
506 void serialize(ARCHIVE & ar,
const unsigned int ) {
507 ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(
Base);
516 SmartStereoProjectionFactor> {
SmartStereoProjectionFactor: triangulates point and keeps an estimate of it around.
Definition: SmartStereoProjectionFactor.h:52
bool triangulateAndComputeE(Matrix &E, const Values &values) const
Triangulate and compute derivative of error with respect to point.
Definition: SmartStereoProjectionFactor.h:350
double totalReprojectionError(const Cameras &cameras, boost::optional< Point3 > externalPoint=boost::none) const
Calculate the error of the factor.
Definition: SmartStereoProjectionFactor.h:416
This is the base class for all factor types.
Definition: Factor.h:54
Functions for triangulation.
A non-templated config holding any types of Manifold-group elements.
Definition: Values.h:70
A Stereo Camera based on two Simple Cameras.
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
Definition: PinholeCamera.h:33
DegeneracyMode degeneracyMode
How to linearize the factor.
Definition: SmartFactorParams.h:45
A set of cameras, all with their own calibration.
Definition: CameraSet.h:35
boost::shared_ptr< GaussianFactor > linearizeDamped(const Values &values, const double lambda=0.0) const
Linearize to Gaussian Factor.
Definition: SmartStereoProjectionFactor.h:322
PinholeCamera< Cal3_S2 > MonoCamera
Vector of monocular cameras (stereo treated as 2 monocular)
Definition: SmartStereoProjectionFactor.h:79
bool verboseCheirality
If true, prints text for Cheirality exceptions (default: false)
Definition: SmartFactorParams.h:56
TriangulationResult result_
result from triangulateSafe
Definition: SmartStereoProjectionFactor.h:66
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:122
bool isOutlier() const
return the outlier state
Definition: SmartStereoProjectionFactor.h:496
std::vector< Pose3 > cameraPosesTriangulation_
current triangulation poses
Definition: SmartStereoProjectionFactor.h:67
virtual double error(const Values &values) const
Calculate total reprojection error.
Definition: SmartStereoProjectionFactor.h:441
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
double uL() const
get uL
Definition: StereoPoint2.h:106
virtual Cameras cameras(const Values &values) const
Collect all cameras: important that in key order.
Definition: SmartFactorBase.h:164
SmartStereoProjectionFactor(const SharedNoiseModel &sharedNoiseModel, const SmartStereoProjectionParams ¶ms=SmartStereoProjectionParams(), const boost::optional< Pose3 > body_P_sensor=boost::none)
Constructor.
Definition: SmartStereoProjectionFactor.h:87
virtual ~SmartStereoProjectionFactor()
Virtual destructor.
Definition: SmartStereoProjectionFactor.h:96
virtual bool equals(const NonlinearFactor &p, double tol=1e-9) const
equals
Definition: SmartStereoProjectionFactor.h:114
TriangulationResult point(const Values &values) const
COMPUTE the landmark.
Definition: SmartStereoProjectionFactor.h:481
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
boost::shared_ptr< SmartStereoProjectionFactor > shared_ptr
shorthand for a smart pointer to a factor
Definition: SmartStereoProjectionFactor.h:73
bool isValid() const
Is result valid?
Definition: SmartStereoProjectionFactor.h:487
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
print
Definition: SmartStereoProjectionFactor.h:104
TriangulationResult triangulateSafe(const Cameras &cameras) const
triangulateSafe
Definition: SmartStereoProjectionFactor.h:163
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
Definition: StereoPoint2.h:32
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
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 and error vector for the case in which the right pixel in the monocular c...
Definition: SmartStereoProjectionFactor.h:452
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
bool isPointBehindCamera() const
return the cheirality status flag
Definition: SmartStereoProjectionFactor.h:493
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:359
bool isDegenerate() const
return the degenerate state
Definition: SmartStereoProjectionFactor.h:490
TriangulationResult triangulateSafe(const CameraSet< CAMERA > &cameras, const typename CAMERA::MeasurementVector &measured, const TriangulationParameters ¶ms)
triangulateSafe: extensive checking of the outcome
Definition: triangulation.h:460
static const int ZDim
Measurement dimension.
Definition: SmartFactorBase.h:58
Definition: SmartFactorParams.h:42
TriangulationResult point() const
return the landmark
Definition: SmartStereoProjectionFactor.h:476
bool isFarPoint() const
return the farPoint state
Definition: SmartStereoProjectionFactor.h:499
bool triangulateAndComputeJacobiansSVD(FBlocks &Fs, Matrix &Enull, Vector &b, const Values &values) const
takes values
Definition: SmartStereoProjectionFactor.h:390
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:56
CameraSet< StereoCamera > Cameras
Vector of cameras.
Definition: SmartStereoProjectionFactor.h:76
A manifold defines a space in which there is a notion of a linear tangent space that can be centered ...
Definition: concepts.h:30
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
Base class for smart factors This base class has no internal point, but it has a measurement,...
Definition: SmartFactorBase.h:47
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
virtual boost::shared_ptr< GaussianFactor > linearize(const Values &values) const
linearize
Definition: SmartStereoProjectionFactor.h:330
friend class boost::serialization::access
Serialization function.
Definition: SmartStereoProjectionFactor.h:504
Definition: SymmetricBlockMatrix.h:51
bool triangulateAndComputeJacobians(FBlocks &Fs, Matrix &E, Vector &b, const Values &values) const
Version that takes values, and creates the point.
Definition: SmartStereoProjectionFactor.h:379
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
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
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:199
boost::shared_ptr< GaussianFactor > linearizeDamped(const Cameras &cameras, const double lambda=0.0) const
Linearize to Gaussian Factor.
Definition: SmartStereoProjectionFactor.h:300
double v() const
get v
Definition: StereoPoint2.h:112
static const int Dim
Camera dimension.
Definition: SmartFactorBase.h:57
bool throwCheirality
If true, re-throws Cheirality exceptions (default: false)
Definition: SmartFactorParams.h:55
bool triangulateForLinearize(const Cameras &cameras) const
triangulate
Definition: SmartStereoProjectionFactor.h:193
void whitenJacobians(FBlocks &F, Matrix &E, Vector &b) const
Whiten the Jacobians computed by computeJacobians using noiseModel_.
Definition: SmartFactorBase.h:321
double uR() const
get uR
Definition: StereoPoint2.h:109
boost::shared_ptr< JacobianFactor > createJacobianSVDFactor(const Cameras &cameras, double lambda) const
different (faster) way to compute Jacobian factor
Definition: SmartStereoProjectionFactor.h:269
bool triangulateAndComputeE(Matrix &E, const Cameras &cameras) const
Triangulate and compute derivative of error with respect to point.
Definition: SmartStereoProjectionFactor.h:339
Vector reprojectionErrorAfterTriangulation(const Values &values) const
Calculate vector of re-projection errors, before applying noise model.
Definition: SmartStereoProjectionFactor.h:401
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