26 #include <gtsam/inference/Symbol.h> 43 template<
class CAMERA>
63 mutable std::vector<Pose3, Eigen::aligned_allocator<Pose3> >
89 : Base(sharedNoiseModel),
103 DefaultKeyFormatter)
const override {
104 std::cout << s <<
"SmartProjectionFactor\n";
107 std::cout <<
"triangulationParameters:\n" << params_.triangulation
109 std::cout <<
"result:\n" << result_ << std::endl;
115 const This *e =
dynamic_cast<const This*
>(&p);
134 size_t m = cameras.size();
136 bool retriangulate =
false;
142 retriangulate =
true;
145 if (!retriangulate) {
146 for (
size_t i = 0; i < cameras.size(); i++) {
149 retriangulate =
true;
159 for (
size_t i = 0; i < m; i++)
164 return retriangulate;
175 size_t m = cameras.size();
177 return TriangulationResult::Degenerate();
182 params_.triangulation);
194 return bool(result_);
199 const Cameras&
cameras,
const double lambda = 0.0,
200 bool diagonalDamping =
false)
const {
201 size_t numKeys = this->
keys_.size();
204 std::vector<Matrix> Gs(numKeys * (numKeys + 1) / 2);
205 std::vector<Vector> gs(numKeys);
207 if (this->
measured_.size() != cameras.size())
208 throw std::runtime_error(
209 "SmartProjectionHessianFactor: this->measured_" 210 ".size() inconsistent with input");
217 for (Vector& v : gs) v = Vector::Zero(
Base::Dim);
218 return std::make_shared<RegularHessianFactor<Base::Dim> >(this->
keys_,
223 typename Base::FBlocks Fs;
235 return std::make_shared<RegularHessianFactor<Base::Dim> >(
236 this->
keys_, augmentedHessian);
240 std::shared_ptr<RegularImplicitSchurFactor<CAMERA> > createRegularImplicitSchurFactor(
241 const Cameras&
cameras,
double lambda)
const {
246 return std::shared_ptr<RegularImplicitSchurFactor<CAMERA> >();
251 const Cameras& cameras,
double lambda)
const {
256 return std::make_shared<JacobianFactorQ<Base::Dim, 2> >(this->
keys_);
261 const Values& values,
double lambda)
const {
267 const Cameras& cameras,
double lambda)
const {
272 return std::make_shared<JacobianFactorSVD<Base::Dim, 2> >(this->
keys_);
277 const Values& values,
double lambda = 0.0)
const {
283 const Values& values,
double lambda = 0.0)
const {
284 return createRegularImplicitSchurFactor(this->
cameras(values), lambda);
289 const Values& values,
double lambda = 0.0)
const {
299 const double lambda = 0.0)
const {
305 return createRegularImplicitSchurFactor(cameras, lambda);
311 throw std::runtime_error(
"SmartFactorlinearize: unknown mode");
321 const double lambda = 0.0)
const {
323 Cameras cameras = this->
cameras(values);
329 const Values& values)
const override {
340 cameras.
project2(*result_,
nullptr, &E);
342 return nonDegenerate;
350 Cameras cameras = this->
cameras(values);
358 typename Base::FBlocks& Fs, Matrix& E, Vector& b,
359 const Cameras& cameras)
const {
364 Unit3 backProjected = cameras[0].backprojectPointAtInfinity(
375 typename Base::FBlocks& Fs, Matrix& E, Vector& b,
376 const Values& values)
const {
377 Cameras cameras = this->
cameras(values);
381 return nonDegenerate;
386 typename Base::FBlocks& Fs, Matrix& Enull, Vector& b,
387 const Values& values)
const {
388 Cameras cameras = this->
cameras(values);
392 return nonDegenerate;
397 Cameras cameras = this->
cameras(values);
402 return Vector::Zero(cameras.size() * 2);
412 std::optional<Point3> externalPoint = {})
const {
424 Unit3 backprojected = cameras.front().backprojectPointAtInfinity(
434 if (this->
active(values)) {
448 Cameras cameras = this->
cameras(values);
453 bool isValid()
const {
return result_.valid(); }
469 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 470 friend class boost::serialization::access; 472 template<
class ARCHIVE>
473 void serialize(ARCHIVE & ar,
const unsigned int version) {
474 ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
475 ar & BOOST_SERIALIZATION_NVP(params_);
476 ar & BOOST_SERIALIZATION_NVP(result_);
484 template<
class CAMERA>
486 SmartProjectionFactor<CAMERA> > {
std::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
Definition: SmartProjectionFactor.h:70
virtual Cameras cameras(const Values &values) const
Collect all cameras: important that in key order.
Definition: SmartFactorBase.h:163
void computeJacobians(FBlocks &Fs, Matrix &E, Vector &b, const Cameras &cameras, const POINT &point) const
Definition: SmartFactorBase.h:315
bool triangulateAndComputeE(Matrix &E, const Cameras &cameras) const
Definition: SmartProjectionFactor.h:337
bool triangulateForLinearize(const Cameras &cameras) const
Possibly re-triangulate before calculating Jacobians.
Definition: SmartProjectionFactor.h:192
bool isPointBehindCamera() const
Definition: SmartProjectionFactor.h:459
bool equals(const CameraSet &p, double tol=1e-9) const
equals
Definition: CameraSet.h:91
double totalReprojectionError(const Cameras &cameras, const POINT &point) const
Definition: SmartFactorBase.h:297
SmartProjectionFactor()
Definition: SmartProjectionFactor.h:79
std::shared_ptr< GaussianFactor > linearize(const Values &values) const override
linearize
Definition: SmartProjectionFactor.h:328
Definition: SmartFactorParams.h:42
std::shared_ptr< JacobianFactorQ< Base::Dim, 2 > > createJacobianQFactor(const Cameras &cameras, double lambda) const
Create JacobianFactorQ factor.
Definition: SmartProjectionFactor.h:250
std::string serialize(const T &input)
serializes to a string
Definition: serialization.h:113
void computeJacobiansWithTriangulatedPoint(typename Base::FBlocks &Fs, Matrix &E, Vector &b, const Cameras &cameras) const
Definition: SmartProjectionFactor.h:357
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
equals
Definition: SmartFactorBase.h:188
DegeneracyMode degeneracyMode
How to linearize the factor.
Definition: SmartFactorParams.h:45
std::shared_ptr< JacobianFactorQ< Base::Dim, 2 > > createJacobianQFactor(const Values &values, double lambda) const
Create JacobianFactorQ factor, takes values.
Definition: SmartProjectionFactor.h:260
Definition: SmartProjectionFactor.h:44
Definition: Testable.h:152
virtual std::shared_ptr< JacobianFactorQ< Base::Dim, 2 > > linearizeToJacobian(const Values &values, double lambda=0.0) const
Linearize to a JacobianfactorQ.
Definition: SmartProjectionFactor.h:288
TriangulationResult result_
result from triangulateSafe
Definition: SmartProjectionFactor.h:62
Definition: NonlinearFactor.h:68
KeyVector keys_
The keys involved in this factor.
Definition: Factor.h:87
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Definition: SmartFactorBase.h:175
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:171
virtual std::shared_ptr< RegularHessianFactor< Base::Dim > > linearizeToHessian(const Values &values, double lambda=0.0) const
Linearize to a Hessianfactor.
Definition: SmartProjectionFactor.h:276
Vector reprojectionErrorAfterTriangulation(const Values &values) const
Calculate vector of re-projection errors, before applying noise model.
Definition: SmartProjectionFactor.h:396
std::shared_ptr< GaussianFactor > linearizeDamped(const Cameras &cameras, const double lambda=0.0) const
Definition: SmartProjectionFactor.h:298
bool isOutlier() const
Definition: SmartProjectionFactor.h:462
Definition: SymmetricBlockMatrix.h:53
Base class to create smart factors on poses or cameras.
bool isFarPoint() const
Definition: SmartProjectionFactor.h:465
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:127
ZVector project2(const POINT &point, FBlocks *Fs=nullptr, Matrix *E=nullptr) const
Definition: CameraSet.h:108
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
Base class for smart factors. This base class has no internal point, but it has a measurement...
Definition: SmartFactorBase.h:51
ZVector measured_
Definition: SmartFactorBase.h:80
std::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:386
bool triangulateAndComputeJacobians(typename Base::FBlocks &Fs, Matrix &E, Vector &b, const Values &values) const
Version that takes values, and creates the point.
Definition: SmartProjectionFactor.h:374
void computeJacobiansSVD(FBlocks &Fs, Matrix &Enull, Vector &b, const Cameras &cameras, const POINT &point) const
Definition: SmartFactorBase.h:330
TriangulationResult triangulateSafe(const Cameras &cameras) const
Call gtsam::triangulateSafe iff we need to re-triangulate.
Definition: SmartProjectionFactor.h:173
virtual std::shared_ptr< RegularImplicitSchurFactor< CAMERA > > linearizeToImplicit(const Values &values, double lambda=0.0) const
Linearize to an Implicit Schur factor.
Definition: SmartProjectionFactor.h:282
Functions for triangulation.
double error(const Values &values) const override
Calculate total reprojection error.
Definition: SmartProjectionFactor.h:433
LinearizationMode linearizationMode
How to linearize the factor.
Definition: SmartFactorParams.h:44
TriangulationResult triangulateSafe(const CameraSet< CAMERA > &cameras, const typename CAMERA::MeasurementVector &measured, const TriangulationParameters ¶ms)
triangulateSafe: extensive checking of the outcome
Definition: triangulation.h:687
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
std::shared_ptr< JacobianFactor > createJacobianSVDFactor(const Cameras &cameras, double lambda) const
Different (faster) way to compute a JacobianFactorSVD factor.
Definition: SmartProjectionFactor.h:266
std::shared_ptr< JacobianFactor > createJacobianSVDFactor(const Cameras &cameras, const Point3 &point, double lambda=0.0) const
Definition: SmartFactorBase.h:416
TriangulationResult point(const Values &values) const
Definition: SmartProjectionFactor.h:447
Definition: chartTesting.h:28
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
equals
Definition: SmartProjectionFactor.h:114
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:86
TriangulationResult point() const
Definition: SmartProjectionFactor.h:442
virtual bool active(const Values &) const
Definition: NonlinearFactor.h:141
std::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:399
static const int Dim
Camera dimension.
Definition: SmartFactorBase.h:61
bool isValid() const
Is result valid?
Definition: SmartProjectionFactor.h:453
bool triangulateAndComputeE(Matrix &E, const Values &values) const
Definition: SmartProjectionFactor.h:349
std::shared_ptr< GaussianFactor > linearizeDamped(const Values &values, const double lambda=0.0) const
Definition: SmartProjectionFactor.h:320
CAMERA Camera
shorthand for a set of cameras
Definition: SmartProjectionFactor.h:73
SmartProjectionFactor(const SharedNoiseModel &sharedNoiseModel, const SmartProjectionParams ¶ms=SmartProjectionParams())
Definition: SmartProjectionFactor.h:86
Definition: triangulation.h:627
void whitenJacobians(FBlocks &F, Matrix &E, Vector &b) const
Whiten the Jacobians computed by computeJacobians using noiseModel_.
Definition: SmartFactorBase.h:377
bool triangulateAndComputeJacobiansSVD(typename Base::FBlocks &Fs, Matrix &Enull, Vector &b, const Values &values) const
takes values
Definition: SmartProjectionFactor.h:385
std::vector< Pose3, Eigen::aligned_allocator< Pose3 > > cameraPosesTriangulation_
current triangulation poses
Definition: SmartProjectionFactor.h:64
~SmartProjectionFactor() override
Definition: SmartProjectionFactor.h:94
utility functions for loading datasets
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Definition: SmartProjectionFactor.h:102
bool isDegenerate() const
Definition: SmartProjectionFactor.h:456
std::shared_ptr< RegularHessianFactor< Base::Dim > > createHessianFactor(const Cameras &cameras, const double lambda=0.0, bool diagonalDamping=false) const
Create a Hessianfactor that is an approximation of error(p).
Definition: SmartProjectionFactor.h:198
Collect common parameters for SmartProjection and SmartStereoProjection factors.
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:741
double totalReprojectionError(const Cameras &cameras, std::optional< Point3 > externalPoint={}) const
Definition: SmartProjectionFactor.h:411
Vector unwhitenedError(const Cameras &cameras, const POINT &point, typename Cameras::FBlocks *Fs=nullptr, Matrix *E=nullptr) const
Definition: SmartFactorBase.h:208
double retriangulationThreshold
threshold to decide whether to re-triangulate
Definition: SmartFactorParams.h:50