testSmartFactorBase.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
20 #include <gtsam/geometry/Pose3.h>
23 
24 using namespace std;
25 using namespace gtsam;
26 
27 static SharedNoiseModel unit2(noiseModel::Unit::Create(2));
28 static SharedNoiseModel unit3(noiseModel::Unit::Create(3));
29 
30 /* ************************************************************************* */
33 
34 namespace gtsam {
35 
36 class PinholeFactor: public SmartFactorBase<PinholeCamera<Cal3Bundler> > {
37 public:
40  PinholeFactor(const SharedNoiseModel& sharedNoiseModel,
41  boost::optional<Pose3> body_P_sensor = boost::none,
42  size_t expectedNumberCameras = 10)
43  : Base(sharedNoiseModel, body_P_sensor, expectedNumberCameras) {}
44  double error(const Values& values) const override { return 0.0; }
45  boost::shared_ptr<GaussianFactor> linearize(
46  const Values& values) const override {
47  return boost::shared_ptr<GaussianFactor>(new JacobianFactor());
48  }
49 };
50 
52 template<>
53 struct traits<PinholeFactor> : public Testable<PinholeFactor> {};
54 }
55 
56 TEST(SmartFactorBase, Pinhole) {
58  f.add(Point2(0,0), 1);
59  f.add(Point2(0,0), 2);
60  EXPECT_LONGS_EQUAL(2 * 2, f.dim());
61 }
62 
63 TEST(SmartFactorBase, PinholeWithSensor) {
64  Pose3 body_P_sensor(Rot3(), Point3(1, 0, 0));
65  PinholeFactor f = PinholeFactor(unit2, body_P_sensor);
66  EXPECT(assert_equal<Pose3>(f.body_P_sensor(), body_P_sensor));
67 
68  PinholeFactor::Cameras cameras;
69  // Assume body at origin.
70  Pose3 world_P_body = Pose3();
71  // Camera coordinates in world frame.
72  Pose3 wTc = world_P_body * body_P_sensor;
73  cameras.push_back(PinholeCamera<Cal3Bundler>(wTc));
74 
75  // Simple point to project slightly off image center
76  Point3 p(0, 0, 10);
77  Point2 measurement = cameras[0].project(p);
78  f.add(measurement, 1);
79 
81  Matrix E;
82  Vector error = f.unwhitenedError<Point3>(cameras, p, Fs, E);
83 
84  Vector expectedError = Vector::Zero(2);
85  Matrix29 expectedFs;
86  expectedFs << -0.001, -1.00001, 0, -0.1, 0, -0.01, 0, 0, 0, 1, 0, 0, 0, -0.1, 0, 0, 0, 0;
87  Matrix23 expectedE;
88  expectedE << 0.1, 0, 0.01, 0, 0.1, 0;
89 
90  EXPECT(assert_equal(error, expectedError));
91  // We only have the jacobian for the 1 camera
92  // Use of a lower tolerance value due to compiler precision mismatch.
93  EXPECT(assert_equal(expectedFs, Fs[0], 1e-3));
94  EXPECT(assert_equal(expectedE, E));
95 }
96 
97 /* ************************************************************************* */
99 
100 namespace gtsam {
101 
102 class StereoFactor: public SmartFactorBase<StereoCamera> {
103 public:
106  StereoFactor(const SharedNoiseModel& sharedNoiseModel): Base(sharedNoiseModel) {
107  }
108  double error(const Values& values) const override {
109  return 0.0;
110  }
111  boost::shared_ptr<GaussianFactor> linearize(
112  const Values& values) const override {
113  return boost::shared_ptr<GaussianFactor>(new JacobianFactor());
114  }
115 };
116 
118 template<>
119 struct traits<StereoFactor> : public Testable<StereoFactor> {};
120 }
121 
124  f.add(StereoPoint2(), 1);
125  f.add(StereoPoint2(), 2);
126  EXPECT_LONGS_EQUAL(2 * 3, f.dim());
127 }
128 
129 /* ************************************************************************* */
130 BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Constrained, "gtsam_noiseModel_Constrained");
131 BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Diagonal, "gtsam_noiseModel_Diagonal");
132 BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Gaussian, "gtsam_noiseModel_Gaussian");
133 BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Unit, "gtsam_noiseModel_Unit");
134 BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Isotropic, "gtsam_noiseModel_Isotropic");
135 BOOST_CLASS_EXPORT_GUID(gtsam::SharedNoiseModel, "gtsam_SharedNoiseModel");
136 BOOST_CLASS_EXPORT_GUID(gtsam::SharedDiagonal, "gtsam_SharedDiagonal");
137 
139  using namespace gtsam::serializationTestHelpers;
140  PinholeFactor factor(unit2);
141 
142  EXPECT(equalsObj(factor));
143  EXPECT(equalsXML(factor));
144  EXPECT(equalsBinary(factor));
145 }
146 
147 /* ************************************************************************* */
148 int main() {
149  TestResult tr;
150  return TestRegistry::runAllTests(tr);
151 }
152 /* ************************************************************************* */
153 
SmartFactorBase< PinholeCamera< Cal3Bundler > > Base
PinholeFactor(const SharedNoiseModel &sharedNoiseModel, boost::optional< Pose3 > body_P_sensor=boost::none, size_t expectedNumberCameras=10)
Key E(std::uint64_t j)
std::vector< MatrixZD, Eigen::aligned_allocator< MatrixZD > > FBlocks
Definition: CameraSet.h:74
void serialize(Archive &ar, Eigen::Matrix< Scalar_, Rows_, Cols_, Ops_, MaxRows_, MaxCols_ > &m, const unsigned int version)
Definition: base/Matrix.h:591
static int runAllTests(TestResult &result)
static SharedNoiseModel unit3(noiseModel::Unit::Create(3))
Vector2 Point2
Definition: Point2.h:27
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
leaf::MyValues values
double measurement(10.0)
Definition: Half.h:150
int main()
Base class to create smart factors on poses or cameras.
Base class for all pinhole cameras.
Base class for smart factors This base class has no internal point, but it has a measurement, noise model and an optional sensor pose. This class mainly computes the derivatives and returns them as a variety of factors. The methods take a Cameras argument, which should behave like PinholeCamera, and the value of a point, which is kept in the base class.
Eigen::VectorXd Vector
Definition: Vector.h:38
TEST(SmartFactorBase, Pinhole)
double error(const Values &values) const override
#define EXPECT(condition)
Definition: Test.h:151
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
boost::shared_ptr< GaussianFactor > linearize(const Values &values) const override
static SharedNoiseModel unit2(noiseModel::Unit::Create(2))
StereoFactor(const SharedNoiseModel &sharedNoiseModel)
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:736
traits
Definition: chartTesting.h:28
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Constrained,"gtsam_noiseModel_Constrained")
SmartFactorBase< StereoCamera > Base
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
Pose3 body_P_sensor() const
A Stereo Camera based on two Simple Cameras.
#define EXPECT_LONGS_EQUAL(expected, actual)
Definition: Test.h:155
size_t dim() const override
get the dimension (number of rows!) of the factor
void add(const Z &measured, const Key &key)
float * p
static double error
Definition: testRot3.cpp:39
double error(const Values &values) const override
Vector3 Point3
Definition: Point3.h:35
Vector unwhitenedError(const Cameras &cameras, const POINT &point, boost::optional< typename Cameras::FBlocks & > Fs=boost::none, boost::optional< Matrix & > E=boost::none) const
3D Pose
Calibration used by Bundler.
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:734
boost::shared_ptr< GaussianFactor > linearize(const Values &values) const override


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:49:36