Go to the documentation of this file.
31 #include <gtsam_unstable/dllexport.h>
33 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
34 #include <boost/serialization/optional.hpp>
77 typedef std::shared_ptr<SmartStereoProjectionFactor>
shared_ptr;
110 std::cout <<
s <<
"SmartStereoProjectionFactor\n";
113 std::cout <<
"result:\n" <<
result_ << std::endl;
133 bool retriangulate =
false;
138 retriangulate =
true;
140 if (!retriangulate) {
144 retriangulate =
true;
153 for (
size_t i = 0;
i <
m;
i++)
158 return retriangulate;
175 for(
size_t i = 0;
i <
m;
i++) {
178 const MonoCamera leftCamera_i(leftPose,monoCal);
180 const Pose3 rightPose = leftPose.
compose( left_Pose_right );
181 const MonoCamera rightCamera_i(rightPose,monoCal);
183 monoCameras.push_back(leftCamera_i);
184 monoMeasured.push_back(
Point2(zi.
uL(),zi.
v()));
186 monoCameras.push_back(rightCamera_i);
187 monoMeasured.push_back(
Point2(zi.
uR(),zi.
v()));
207 size_t numKeys = this->
keys_.size();
210 std::vector<Matrix> Gs(numKeys * (numKeys + 1) / 2);
211 std::vector<Vector> gs(numKeys);
213 if (this->
measured_.size() != cameras.size())
214 throw std::runtime_error(
"SmartStereoProjectionHessianFactor: this->"
215 "measured_.size() inconsistent with input");
225 return std::make_shared<RegularHessianFactor<Base::Dim> >(this->
keys_,
242 return std::make_shared<RegularHessianFactor<Base::Dim> >(this->
keys_,
278 return std::make_shared<JacobianFactorSVD<Base::Dim, ZDim> >(this->
keys_);
305 const double lambda = 0.0)
const {
317 throw std::runtime_error(
"SmartStereoFactorlinearize: unknown mode");
327 const double lambda = 0.0)
const {
347 return nonDegenerate;
369 throw (
"computeJacobiansWithTriangulatedPoint");
390 return nonDegenerate;
401 return nonDegenerate;
421 std::optional<Point3> externalPoint = {})
const {
432 throw(std::runtime_error(
"Backproject at infinity not implemented for SmartStereo."));
446 if (this->
active(values)) {
460 Matrix*
E =
nullptr)
const override {
468 for (
size_t ii = 0; ii <
Dim; ii++) Fi(1, ii) = 0.0;
471 E->row(
ZDim *
i + 1) = Matrix::Zero(1,
E->cols());
474 ue(
ZDim *
i + 1) = 0.0;
507 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
508 friend class boost::serialization::access;
510 template<
class ARCHIVE>
511 void serialize(ARCHIVE & ar,
const unsigned int ) {
512 ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(
Base);
522 SmartStereoProjectionFactor> {
bool triangulateAndComputeJacobians(FBlocks &Fs, Matrix &E, Vector &b, const Values &values) const
Version that takes values, and creates the point.
TriangulationParameters triangulation
Base class to create smart factors on poses or cameras.
Vector reprojectionErrorAfterTriangulation(const Values &values) const
Calculate vector of re-projection errors, before applying noise model.
Vector unwhitenedError(const Cameras &cameras, const POINT &point, typename Cameras::FBlocks *Fs=nullptr, Matrix *E=nullptr) const
bool verboseCheirality
If true, prints text for Cheirality exceptions (default: false)
Point2Vector MeasurementVector
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
~SmartStereoProjectionFactor() override
TriangulationResult point(const Values &values) const
Pose3 body_P_sensor() const
std::shared_ptr< GaussianFactor > linearizeDamped(const Values &values, const double lambda=0.0) const
CameraSet< StereoCamera > Cameras
Vector of cameras.
double totalReprojectionError(const Cameras &cameras, std::optional< Point3 > externalPoint={}) const
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Collect common parameters for SmartProjection and SmartStereoProjection factors.
SmartFactorBase< StereoCamera > Base
void correctForMissingMeasurements(const Cameras &cameras, Vector &ue, typename Cameras::FBlocks *Fs=nullptr, Matrix *E=nullptr) const override
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
equals
void computeJacobiansWithTriangulatedPoint(FBlocks &Fs, Matrix &E, Vector &b, const Cameras &cameras) const
Class compose(const Class &g) const
double error(const Values &values) const override
Calculate total reprojection error.
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
ZVector project2(const POINT &point, FBlocks *Fs=nullptr, Matrix *E=nullptr) const
TriangulationResult point() const
static const int Dim
Camera dimension.
static const SmartProjectionParams params
virtual bool active(const Values &) const
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Functions for triangulation.
bool triangulateAndComputeE(Matrix &E, const Cameras &cameras) const
A set of cameras, all with their own calibration.
std::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)
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
DegeneracyMode degeneracyMode
How to linearize the factor.
SmartProjectionParams SmartStereoProjectionParams
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
LinearizationMode linearizationMode
How to linearize the factor.
bool triangulateForLinearize(const Cameras &cameras) const
triangulate
std::shared_ptr< SmartStereoProjectionFactor > shared_ptr
shorthand for a smart pointer to a factor
utility functions for loading datasets
void whitenJacobians(FBlocks &F, Matrix &E, Vector &b) const
Whiten the Jacobians computed by computeJacobians using noiseModel_.
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
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)
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
MonoCamera::MeasurementVector MonoMeasurements
std::vector< Pose3 > cameraPosesTriangulation_
current triangulation poses
A non-linear factor for stereo measurements.
const SmartStereoProjectionParams params_
CameraSet< MonoCamera > MonoCameras
SmartStereoProjectionFactor(const SharedNoiseModel &sharedNoiseModel, const SmartStereoProjectionParams ¶ms=SmartStereoProjectionParams(), const std::optional< Pose3 > body_P_sensor={})
TriangulationResult triangulateSafe(const CameraSet< CAMERA > &cameras, const typename CAMERA::MeasurementVector &measured, const TriangulationParameters ¶ms)
triangulateSafe: extensive checking of the outcome
noiseModel::Base::shared_ptr SharedNoiseModel
std::shared_ptr< JacobianFactor > createJacobianSVDFactor(const Cameras &cameras, const Point3 &point, double lambda=0.0) const
static TriangulationResult Degenerate()
virtual Cameras cameras(const Values &values) const
Collect all cameras: important that in key order.
bool isPointBehindCamera() const
bool decideIfTriangulate(const Cameras &cameras) const
Check if the new linearization point_ is the same as the one used for previous triangulation.
std::vector< MatrixZD, Eigen::aligned_allocator< MatrixZD > > FBlocks
Base class for smart factors. This base class has no internal point, but it has a measurement,...
KeyVector keys_
The keys involved in this factor.
static const int ZDim
Measurement dimension.
bool behindCamera() const
TriangulationResult triangulateSafe(const Cameras &cameras) const
triangulateSafe
Array< int, Dynamic, 1 > v
bool throwCheirality
If true, re-throws Cheirality exceptions (default: false)
double totalReprojectionError(const Cameras &cameras, const POINT &point) const
double retriangulationThreshold
threshold to decide whether to re-triangulate
The most common 5DOF 3D->2D calibration.
std::shared_ptr< GaussianFactor > linearize(const Values &values) const override
linearize
The matrix class, also used for vectors and row-vectors.
bool isDegenerate() const
bool isValid() const
Is result valid?
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
equals
TriangulationResult result_
result from triangulateSafe
bool triangulateAndComputeE(Matrix &E, const Values &values) const
void computeJacobiansSVD(FBlocks &Fs, Matrix &Enull, Vector &b, const Cameras &cameras, const POINT &point) const
std::shared_ptr< JacobianFactor > createJacobianSVDFactor(const Cameras &cameras, double lambda) const
different (faster) way to compute Jacobian factor
bool triangulateAndComputeJacobiansSVD(FBlocks &Fs, Matrix &Enull, Vector &b, const Values &values) const
takes values
std::vector< MatrixZD, Eigen::aligned_allocator< MatrixZD > > FBlocks
A Stereo Camera based on two Simple Cameras.
PinholeCamera< Cal3_S2 > MonoCamera
Vector of monocular cameras (stereo treated as 2 monocular)
std::shared_ptr< GaussianFactor > linearizeDamped(const Cameras &cameras, const double lambda=0.0) const
void computeJacobians(FBlocks &Fs, Matrix &E, Vector &b, const Cameras &cameras, const POINT &point) const
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:04:23