55 #include <boost/archive/xml_iarchive.hpp> 56 #include <boost/serialization/export.hpp> 59 using namespace gtsam;
217 TEST (testSerializationSLAM, smallExample_linear) {
233 EXPECT(equalsBinary(cbn));
237 TEST (testSerializationSLAM, gaussianISAM) {
245 EXPECT(equalsBinary(isam));
255 TEST (testSerializationSLAM, smallExample_nonlinear) {
261 EXPECT(equalsBinary(nfg));
275 Rot3 rot3(Rot3::RzRyRx(1.0, 2.0, 3.0));
278 Cal3_S2 cal3_s2(1.0, 2.0, 3.0, 4.0, 5.0);
279 Cal3DS2 cal3ds2(1.0, 2.0, 3.0, 4.0, 5.0,6.0, 7.0, 8.0, 9.0);
283 StereoCamera stereoCamera(pose3, std::make_shared<Cal3_S2Stereo>(cal3_s2stereo));
286 Symbol a01(
'a',1), a02(
'a',2), a03(
'a',3), a04(
'a',4), a05(
'a',5),
287 a06(
'a',6), a07(
'a',7), a08(
'a',8), a09(
'a',9), a10(
'a',10),
288 a11(
'a',11), a12(
'a',12), a13(
'a',13), a14(
'a',14), a15(
'a',15);
289 Symbol b01(
'b',1), b02(
'b',2), b03(
'b',3), b04(
'b',4), b05(
'b',5),
290 b06(
'b',6), b07(
'b',7), b08(
'b',8), b09(
'b',9), b10(
'b',10),
291 b11(
'b',11), b12(
'b',12), b13(
'b',13), b14(
'b',14), b15(
'b',15);
294 values.
insert(a03, point2);
295 values.
insert(a04, stereoPoint2);
296 values.
insert(a05, point3);
299 values.
insert(a08, pose2);
300 values.
insert(a09, pose3);
301 values.
insert(a10, cal3_s2);
302 values.
insert(a11, cal3ds2);
303 values.
insert(a12, calibratedCamera);
304 values.
insert(a13, simpleCamera);
305 values.
insert(a14, stereoCamera);
319 noiseModel::Unit::Create(2));
321 EXPECT(equalsDereferenced(robust1));
322 EXPECT(equalsDereferencedXML(robust1));
323 EXPECT(equalsDereferencedBinary(robust1));
374 GenericStereoFactor3D genericStereoFactor3D(stereoPoint2, model3, a09, a05, std::make_shared<Cal3_S2Stereo>(cal3_s2stereo));
378 graph += priorFactorPoint2;
379 graph += priorFactorStereoPoint2;
380 graph += priorFactorPoint3;
381 graph += priorFactorRot2;
382 graph += priorFactorRot3;
383 graph += priorFactorPose2;
384 graph += priorFactorPose3;
385 graph += priorFactorCal3_S2;
386 graph += priorFactorCal3DS2;
387 graph += priorFactorCalibratedCamera;
388 graph += priorFactorStereoCamera;
390 graph += betweenFactorPoint2;
391 graph += betweenFactorPoint3;
392 graph += betweenFactorRot2;
393 graph += betweenFactorRot3;
394 graph += betweenFactorPose2;
395 graph += betweenFactorPose3;
397 graph += nonlinearEqualityPoint2;
398 graph += nonlinearEqualityStereoPoint2;
399 graph += nonlinearEqualityPoint3;
400 graph += nonlinearEqualityRot2;
401 graph += nonlinearEqualityRot3;
402 graph += nonlinearEqualityPose2;
403 graph += nonlinearEqualityPose3;
404 graph += nonlinearEqualityCal3_S2;
405 graph += nonlinearEqualityCal3DS2;
406 graph += nonlinearEqualityCalibratedCamera;
407 graph += nonlinearEqualityStereoCamera;
409 graph += rangeFactor2D;
410 graph += rangeFactor3D;
411 graph += rangeFactorPose2;
412 graph += rangeFactorPose3;
413 graph += rangeFactorCalibratedCameraPoint;
414 graph += rangeFactorPinholeCameraCal3_S2Point;
415 graph += rangeFactorCalibratedCamera;
416 graph += rangeFactorPinholeCameraCal3_S2;
418 graph += bearingRangeFactor2D;
420 graph += genericProjectionFactorCal3_S2;
421 graph += genericProjectionFactorCal3DS2;
423 graph += generalSFMFactorCal3_S2;
425 graph += generalSFMFactor2Cal3_S2;
427 graph += genericStereoFactor3D;
431 EXPECT(equalsObj<Symbol>(a01));
432 EXPECT(equalsObj<Symbol>(b02));
433 EXPECT(equalsObj<Values>(values));
434 EXPECT(equalsObj<NonlinearFactorGraph>(graph));
436 EXPECT(equalsObj<PriorFactorPoint2>(priorFactorPoint2));
437 EXPECT(equalsObj<PriorFactorStereoPoint2>(priorFactorStereoPoint2));
438 EXPECT(equalsObj<PriorFactorPoint3>(priorFactorPoint3));
439 EXPECT(equalsObj<PriorFactorRot2>(priorFactorRot2));
440 EXPECT(equalsObj<PriorFactorRot3>(priorFactorRot3));
441 EXPECT(equalsObj<PriorFactorPose2>(priorFactorPose2));
442 EXPECT(equalsObj<PriorFactorPose3>(priorFactorPose3));
443 EXPECT(equalsObj<PriorFactorCal3_S2>(priorFactorCal3_S2));
444 EXPECT(equalsObj<PriorFactorCal3DS2>(priorFactorCal3DS2));
445 EXPECT(equalsObj<PriorFactorCalibratedCamera>(priorFactorCalibratedCamera));
446 EXPECT(equalsObj<PriorFactorStereoCamera>(priorFactorStereoCamera));
448 EXPECT(equalsObj<BetweenFactorPoint2>(betweenFactorPoint2));
449 EXPECT(equalsObj<BetweenFactorPoint3>(betweenFactorPoint3));
450 EXPECT(equalsObj<BetweenFactorRot2>(betweenFactorRot2));
451 EXPECT(equalsObj<BetweenFactorRot3>(betweenFactorRot3));
452 EXPECT(equalsObj<BetweenFactorPose2>(betweenFactorPose2));
453 EXPECT(equalsObj<BetweenFactorPose3>(betweenFactorPose3));
455 EXPECT(equalsObj<NonlinearEqualityPoint2>(nonlinearEqualityPoint2));
456 EXPECT(equalsObj<NonlinearEqualityStereoPoint2>(nonlinearEqualityStereoPoint2));
457 EXPECT(equalsObj<NonlinearEqualityPoint3>(nonlinearEqualityPoint3));
458 EXPECT(equalsObj<NonlinearEqualityRot2>(nonlinearEqualityRot2));
459 EXPECT(equalsObj<NonlinearEqualityRot3>(nonlinearEqualityRot3));
460 EXPECT(equalsObj<NonlinearEqualityPose2>(nonlinearEqualityPose2));
461 EXPECT(equalsObj<NonlinearEqualityPose3>(nonlinearEqualityPose3));
462 EXPECT(equalsObj<NonlinearEqualityCal3_S2>(nonlinearEqualityCal3_S2));
463 EXPECT(equalsObj<NonlinearEqualityCal3DS2>(nonlinearEqualityCal3DS2));
464 EXPECT(equalsObj<NonlinearEqualityCalibratedCamera>(nonlinearEqualityCalibratedCamera));
465 EXPECT(equalsObj<NonlinearEqualityStereoCamera>(nonlinearEqualityStereoCamera));
467 EXPECT(equalsObj<RangeFactor2D>(rangeFactor2D));
468 EXPECT(equalsObj<RangeFactor3D>(rangeFactor3D));
469 EXPECT(equalsObj<RangeFactorPose2>(rangeFactorPose2));
470 EXPECT(equalsObj<RangeFactorPose3>(rangeFactorPose3));
471 EXPECT(equalsObj<RangeFactorCalibratedCameraPoint>(rangeFactorCalibratedCameraPoint));
472 EXPECT(equalsObj<RangeFactorPinholeCameraCal3_S2Point>(rangeFactorPinholeCameraCal3_S2Point));
473 EXPECT(equalsObj<RangeFactorCalibratedCamera>(rangeFactorCalibratedCamera));
474 EXPECT(equalsObj<RangeFactorPinholeCameraCal3_S2>(rangeFactorPinholeCameraCal3_S2));
476 EXPECT(equalsObj<BearingRangeFactor2D>(bearingRangeFactor2D));
478 EXPECT(equalsObj<GenericProjectionFactorCal3_S2>(genericProjectionFactorCal3_S2));
479 EXPECT(equalsObj<GenericProjectionFactorCal3DS2>(genericProjectionFactorCal3DS2));
481 EXPECT(equalsObj<GeneralSFMFactorCal3_S2>(generalSFMFactorCal3_S2));
483 EXPECT(equalsObj<GeneralSFMFactor2Cal3_S2>(generalSFMFactor2Cal3_S2));
485 EXPECT(equalsObj<GenericStereoFactor3D>(genericStereoFactor3D));
489 EXPECT(equalsXML<Symbol>(a01));
490 EXPECT(equalsXML<Symbol>(b02));
491 EXPECT(equalsXML<Values>(values));
492 EXPECT(equalsXML<NonlinearFactorGraph>(graph));
494 EXPECT(equalsXML<PriorFactorPoint2>(priorFactorPoint2));
495 EXPECT(equalsXML<PriorFactorStereoPoint2>(priorFactorStereoPoint2));
496 EXPECT(equalsXML<PriorFactorPoint3>(priorFactorPoint3));
497 EXPECT(equalsXML<PriorFactorRot2>(priorFactorRot2));
498 EXPECT(equalsXML<PriorFactorRot3>(priorFactorRot3));
499 EXPECT(equalsXML<PriorFactorPose2>(priorFactorPose2));
500 EXPECT(equalsXML<PriorFactorPose3>(priorFactorPose3));
501 EXPECT(equalsXML<PriorFactorCal3_S2>(priorFactorCal3_S2));
502 EXPECT(equalsXML<PriorFactorCal3DS2>(priorFactorCal3DS2));
503 EXPECT(equalsXML<PriorFactorCalibratedCamera>(priorFactorCalibratedCamera));
504 EXPECT(equalsXML<PriorFactorStereoCamera>(priorFactorStereoCamera));
506 EXPECT(equalsXML<BetweenFactorPoint2>(betweenFactorPoint2));
507 EXPECT(equalsXML<BetweenFactorPoint3>(betweenFactorPoint3));
508 EXPECT(equalsXML<BetweenFactorRot2>(betweenFactorRot2));
509 EXPECT(equalsXML<BetweenFactorRot3>(betweenFactorRot3));
510 EXPECT(equalsXML<BetweenFactorPose2>(betweenFactorPose2));
511 EXPECT(equalsXML<BetweenFactorPose3>(betweenFactorPose3));
513 EXPECT(equalsXML<NonlinearEqualityPoint2>(nonlinearEqualityPoint2));
514 EXPECT(equalsXML<NonlinearEqualityStereoPoint2>(nonlinearEqualityStereoPoint2));
515 EXPECT(equalsXML<NonlinearEqualityPoint3>(nonlinearEqualityPoint3));
516 EXPECT(equalsXML<NonlinearEqualityRot2>(nonlinearEqualityRot2));
517 EXPECT(equalsXML<NonlinearEqualityRot3>(nonlinearEqualityRot3));
518 EXPECT(equalsXML<NonlinearEqualityPose2>(nonlinearEqualityPose2));
519 EXPECT(equalsXML<NonlinearEqualityPose3>(nonlinearEqualityPose3));
520 EXPECT(equalsXML<NonlinearEqualityCal3_S2>(nonlinearEqualityCal3_S2));
521 EXPECT(equalsXML<NonlinearEqualityCal3DS2>(nonlinearEqualityCal3DS2));
522 EXPECT(equalsXML<NonlinearEqualityCalibratedCamera>(nonlinearEqualityCalibratedCamera));
523 EXPECT(equalsXML<NonlinearEqualityStereoCamera>(nonlinearEqualityStereoCamera));
525 EXPECT(equalsXML<RangeFactor2D>(rangeFactor2D));
526 EXPECT(equalsXML<RangeFactor3D>(rangeFactor3D));
527 EXPECT(equalsXML<RangeFactorPose2>(rangeFactorPose2));
528 EXPECT(equalsXML<RangeFactorPose3>(rangeFactorPose3));
529 EXPECT(equalsXML<RangeFactorCalibratedCameraPoint>(rangeFactorCalibratedCameraPoint));
530 EXPECT(equalsXML<RangeFactorPinholeCameraCal3_S2Point>(rangeFactorPinholeCameraCal3_S2Point));
531 EXPECT(equalsXML<RangeFactorCalibratedCamera>(rangeFactorCalibratedCamera));
532 EXPECT(equalsXML<RangeFactorPinholeCameraCal3_S2>(rangeFactorPinholeCameraCal3_S2));
534 EXPECT(equalsXML<BearingRangeFactor2D>(bearingRangeFactor2D));
536 EXPECT(equalsXML<GenericProjectionFactorCal3_S2>(genericProjectionFactorCal3_S2));
537 EXPECT(equalsXML<GenericProjectionFactorCal3DS2>(genericProjectionFactorCal3DS2));
539 EXPECT(equalsXML<GeneralSFMFactorCal3_S2>(generalSFMFactorCal3_S2));
541 EXPECT(equalsXML<GeneralSFMFactor2Cal3_S2>(generalSFMFactor2Cal3_S2));
543 EXPECT(equalsXML<GenericStereoFactor3D>(genericStereoFactor3D));
547 EXPECT(equalsBinary<Symbol>(a01));
548 EXPECT(equalsBinary<Symbol>(b02));
549 EXPECT(equalsBinary<Values>(values));
550 EXPECT(equalsBinary<NonlinearFactorGraph>(graph));
552 EXPECT(equalsBinary<PriorFactorPoint2>(priorFactorPoint2));
553 EXPECT(equalsBinary<PriorFactorStereoPoint2>(priorFactorStereoPoint2));
554 EXPECT(equalsBinary<PriorFactorPoint3>(priorFactorPoint3));
555 EXPECT(equalsBinary<PriorFactorRot2>(priorFactorRot2));
556 EXPECT(equalsBinary<PriorFactorRot3>(priorFactorRot3));
557 EXPECT(equalsBinary<PriorFactorPose2>(priorFactorPose2));
558 EXPECT(equalsBinary<PriorFactorPose3>(priorFactorPose3));
559 EXPECT(equalsBinary<PriorFactorCal3_S2>(priorFactorCal3_S2));
560 EXPECT(equalsBinary<PriorFactorCal3DS2>(priorFactorCal3DS2));
561 EXPECT(equalsBinary<PriorFactorCalibratedCamera>(priorFactorCalibratedCamera));
562 EXPECT(equalsBinary<PriorFactorStereoCamera>(priorFactorStereoCamera));
564 EXPECT(equalsBinary<BetweenFactorPoint2>(betweenFactorPoint2));
565 EXPECT(equalsBinary<BetweenFactorPoint3>(betweenFactorPoint3));
566 EXPECT(equalsBinary<BetweenFactorRot2>(betweenFactorRot2));
567 EXPECT(equalsBinary<BetweenFactorRot3>(betweenFactorRot3));
568 EXPECT(equalsBinary<BetweenFactorPose2>(betweenFactorPose2));
569 EXPECT(equalsBinary<BetweenFactorPose3>(betweenFactorPose3));
571 EXPECT(equalsBinary<NonlinearEqualityPoint2>(nonlinearEqualityPoint2));
572 EXPECT(equalsBinary<NonlinearEqualityStereoPoint2>(nonlinearEqualityStereoPoint2));
573 EXPECT(equalsBinary<NonlinearEqualityPoint3>(nonlinearEqualityPoint3));
574 EXPECT(equalsBinary<NonlinearEqualityRot2>(nonlinearEqualityRot2));
575 EXPECT(equalsBinary<NonlinearEqualityRot3>(nonlinearEqualityRot3));
576 EXPECT(equalsBinary<NonlinearEqualityPose2>(nonlinearEqualityPose2));
577 EXPECT(equalsBinary<NonlinearEqualityPose3>(nonlinearEqualityPose3));
578 EXPECT(equalsBinary<NonlinearEqualityCal3_S2>(nonlinearEqualityCal3_S2));
579 EXPECT(equalsBinary<NonlinearEqualityCal3DS2>(nonlinearEqualityCal3DS2));
580 EXPECT(equalsBinary<NonlinearEqualityCalibratedCamera>(nonlinearEqualityCalibratedCamera));
581 EXPECT(equalsBinary<NonlinearEqualityStereoCamera>(nonlinearEqualityStereoCamera));
583 EXPECT(equalsBinary<RangeFactor2D>(rangeFactor2D));
584 EXPECT(equalsBinary<RangeFactor3D>(rangeFactor3D));
585 EXPECT(equalsBinary<RangeFactorPose2>(rangeFactorPose2));
586 EXPECT(equalsBinary<RangeFactorPose3>(rangeFactorPose3));
587 EXPECT(equalsBinary<RangeFactorCalibratedCameraPoint>(rangeFactorCalibratedCameraPoint));
588 EXPECT(equalsBinary<RangeFactorPinholeCameraCal3_S2Point>(rangeFactorPinholeCameraCal3_S2Point));
589 EXPECT(equalsBinary<RangeFactorCalibratedCamera>(rangeFactorCalibratedCamera));
590 EXPECT(equalsBinary<RangeFactorPinholeCameraCal3_S2>(rangeFactorPinholeCameraCal3_S2));
592 EXPECT(equalsBinary<BearingRangeFactor2D>(bearingRangeFactor2D));
594 EXPECT(equalsBinary<GenericProjectionFactorCal3_S2>(genericProjectionFactorCal3_S2));
595 EXPECT(equalsBinary<GenericProjectionFactorCal3DS2>(genericProjectionFactorCal3DS2));
597 EXPECT(equalsBinary<GeneralSFMFactorCal3_S2>(generalSFMFactorCal3_S2));
599 EXPECT(equalsBinary<GeneralSFMFactor2Cal3_S2>(generalSFMFactor2Cal3_S2));
601 EXPECT(equalsBinary<GenericStereoFactor3D>(genericStereoFactor3D));
610 if (!is.is_open())
throw runtime_error(
"Cannot find file " +
inputFile);
611 boost::archive::xml_iarchive in_archive(is);
613 in_archive >> boost::serialization::make_nvp(
"graph", Ab);
628 const auto Ab2 =
read(
"toy3D");
629 const auto Ab3 =
read(
"randomGrid3D");
632 for (
const auto&
Ab : {Ab1, Ab2, Ab3}) {
635 std::map<Key, Vector>
lambda;
636 system.
build(
Ab, keyInfo, lambda);
640 auto values_y = VectorValues::Zero(xbar);
641 auto it = values_y.begin();
642 it->second.setConstant(100);
644 it->second.setConstant(-100);
654 auto ord_y = values_y.vector(ord);
655 auto vector_x = R1.inverse() * ord_y;
662 auto vector_y = values_y.vector(
ordering);
663 const size_t N = R1.cols();
664 Vector solve_x = Vector::Zero(N);
665 system.
solve(vector_y, solve_x);
671 Vector solveT_x = Vector::Zero(N);
gtsam::GenericStereoFactor< gtsam::Pose3, gtsam::Point3 > GenericStereoFactor3D
void build(const GaussianFactorGraph &gfg, const KeyInfo &info, const std::map< Key, Vector > &lambda) override
build/factorize the preconditioner
NonlinearEquality< Pose3 > NonlinearEqualityPose3
PriorFactor< Pose2 > PriorFactorPose2
PriorFactor< Point3 > PriorFactorPoint3
static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE ::Eigen::internal::enable_if< PacketLoad, PacketType >::type read(const TensorMapper &tensorMapper, const StorageIndex &NCIndex, const StorageIndex &CIndex, const StorageIndex &ld)
read, a template function used for loading the data from global memory. This function is used to guar...
PriorFactor< StereoPoint2 > PriorFactorStereoPoint2
PriorFactor< Rot2 > PriorFactorRot2
BetweenFactor< Point3 > BetweenFactorPoint3
GaussianFactorGraph createSmoother(int T)
static int runAllTests(TestResult &result)
NonlinearEquality< Cal3DS2 > NonlinearEqualityCal3DS2
This is the base class for all measurement types.
GaussianFactorGraph createGaussianFactorGraph()
BetweenFactor< Pose2 > BetweenFactorPose2
NonlinearEquality< Rot2 > NonlinearEqualityRot2
gtsam::GeneralSFMFactor< gtsam::PinholeCameraCal3_S2, gtsam::Point3 > GeneralSFMFactorCal3_S2
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
RangeFactor< Pose2, Point2 > RangeFactor2D
BetweenFactor< Point2 > BetweenFactorPoint2
PriorFactor< Cal3_S2 > PriorFactorCal3_S2
const GaussianFactorGraph factors
gtsam::GeneralSFMFactor2< gtsam::Cal3_S2 > GeneralSFMFactor2Cal3_S2
TEST(testSerializationSLAM, smallExample_linear)
BearingRangeFactor< Pose3, Point3 > BearingRangeFactor3D
Calibration of a camera with radial distortion, calculations in base class Cal3DS2_Base.
BetweenFactor< Pose3 > BetweenFactorPose3
NonlinearEquality< CalibratedCamera > NonlinearEqualityCalibratedCamera
PriorFactor< CalibratedCamera > PriorFactorCalibratedCamera
PriorFactor< Pose3 > PriorFactorPose3
RangeFactor< PinholeCameraCal3_S2, Point3 > RangeFactorPinholeCameraCal3_S2Point
PriorFactor< Point2 > PriorFactorPoint2
BetweenFactor< Rot2 > BetweenFactorRot2
NonlinearFactorGraph graph
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
static enum @1107 ordering
noiseModel::Isotropic::shared_ptr model1
PriorFactor< StereoCamera > PriorFactorStereoCamera
const GaussianBayesNet & Rc1() const
PriorFactor< PinholeCameraCal3_S2 > PriorFactorPinholeCameraCal3_S2
Base class for all pinhole cameras.
VectorValues optimize() const
RangeFactor< Pose3, Point3 > RangeFactor3D
PriorFactor< Cal3DS2 > PriorFactorCal3DS2
RangeFactor< CalibratedCamera, Point3 > RangeFactorCalibratedCameraPoint
NonlinearEquality< StereoPoint2 > NonlinearEqualityStereoPoint2
GaussianBayesNet createSmallGaussianBayesNet()
NonlinearEquality< Point2 > NonlinearEqualityPoint2
The most common 5DOF 3D->2D calibration, stereo version.
#define EXPECT(condition)
static Pose3 pose3(rt3, pt3)
NonlinearEquality< Pose2 > NonlinearEqualityPose2
NonlinearEquality< StereoCamera > NonlinearEqualityStereoCamera
VectorValues backSubstituteTranspose(const VectorValues &gx) const
const SharedNoiseModel model3
NonlinearISAM isam(relinearizeInterval)
static const Point3 point3(0.08, 0.08, 0.0)
NonlinearFactorGraph createNonlinearFactorGraph(const SharedNoiseModel &noiseModel1=impl::kSigma0_1, const SharedNoiseModel &noiseModel2=impl::kSigma0_2)
const Ordering & ordering() const
Return the ordering.
NonlinearEquality< Point3 > NonlinearEqualityPoint3
RangeFactor< Pose2, Pose2 > RangeFactorPose2
The most common 5DOF 3D->2D calibration.
static const Point3 point2(-0.08, 0.08, 0.0)
BetweenFactor< Rot3 > BetweenFactorRot3
void transposeSolve(const Vector &y, Vector &x) const override
implement x = R^{-T} y
Calibration of a camera with radial distortion that also supports Lie-group behaviors for optimizatio...
Reprojection of a LANDMARK to a 2D point.
A non-linear factor for stereo measurements.
#define GTSAM_VALUE_EXPORT(Type)
use this macro instead of BOOST_CLASS_EXPORT for GenericValues
cout<< "The eigenvalues of A are:"<< endl<< ces.eigenvalues()<< endl;cout<< "The matrix of eigenvectors, V, is:"<< endl<< ces.eigenvectors()<< endl<< endl;complex< float > lambda
Calibrated camera for which only pose is unknown.
noiseModel::Diagonal::shared_ptr SharedDiagonal
gtsam::GeneralSFMFactor< gtsam::PinholeCameraCal3DS2, gtsam::Point3 > GeneralSFMFactorCal3DS2
RangeFactor< PinholeCameraCal3_S2, PinholeCameraCal3_S2 > RangeFactorPinholeCameraCal3_S2
std::pair< Matrix, Vector > matrix(const Ordering &ordering) const
std::pair< GaussianFactorGraph, VectorValues > planarGraph(size_t N)
GTSAM_EXPORT std::string findExampleDataFile(const std::string &name)
The most common 5DOF 3D->2D calibration + Stereo baseline.
NonlinearEquality< Rot3 > NonlinearEqualityRot3
A simple camera class with a Cal3_S2 calibration.
A Stereo Camera based on two Simple Cameras.
RangeFactor< Pose3, Pose3 > RangeFactorPose3
GenericProjectionFactor< Pose3, Point3, Cal3DS2 > GenericProjectionFactorCal3DS2
GenericProjectionFactor< Pose3, Point3, Cal3_S2 > GenericProjectionFactorCal3_S2
NonlinearEquality< PinholeCameraCal3_S2 > NonlinearEqualityPinholeCameraCal3_S2
NonlinearEquality< Cal3_S2 > NonlinearEqualityCal3_S2
std::shared_ptr< BayesTreeType > eliminateMultifrontal(OptionalOrderingType orderingType={}, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const
A 2D stereo point (uL,uR,v)
A Gaussian factor using the canonical parameters (information form)
Create small example with two poses and one landmark.
static noiseModel::Diagonal::shared_ptr Diagonal(const Matrix &covariance)
void insert(Key j, const Value &val)
Ordering ordering() const
BearingRangeFactor< Pose2, Point2 > BearingRangeFactor2D
Annotation for function names.
BOOST_CLASS_EXPORT_GUID(DecisionTreeFactor, "gtsam_DecisionTreeFactor")
VectorValues backSubstitute(const VectorValues &gx) const
a general SFM factor with an unknown calibration
void solve(const Vector &y, Vector &x) const override
implement x = R^{-1} y
utility functions for loading datasets
PriorFactor< Rot3 > PriorFactorRot3
RangeFactor< CalibratedCamera, CalibratedCamera > RangeFactorCalibratedCamera
noiseModel::Base::shared_ptr SharedNoiseModel
The most common 5DOF 3D->2D calibration.
3D rotation represented as a rotation matrix or quaternion