testTranslationRecovery.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010-2020, 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 
21 #include <gtsam/slam/dataset.h>
22 
23 using namespace std;
24 using namespace gtsam;
25 
26 // Returns the Unit3 direction as measured in the binary measurement, but
27 // computed from the input poses. Helper function used in the unit tests.
29  const BinaryMeasurement<Unit3>& unitTranslation) {
30  const Pose3 wTa = poses.at<Pose3>(unitTranslation.key1()),
31  wTb = poses.at<Pose3>(unitTranslation.key2());
32  const Point3 Ta = wTa.translation(), Tb = wTb.translation();
33  return Unit3(Tb - Ta);
34 }
35 
36 /* ************************************************************************* */
37 // We read the BAL file, which has 3 cameras in it, with poses. We then assume
38 // the rotations are correct, but translations have to be estimated from
39 // translation directions only. Since we have 3 cameras, A, B, and C, we can at
40 // most create three relative measurements, let's call them w_aZb, w_aZc, and
41 // bZc. These will be of type Unit3. We then call `recoverTranslations` which
42 // sets up an optimization problem for the three unknown translations.
44  const string filename = findExampleDataFile("dubrovnik-3-7-pre");
45  SfmData db;
46  bool success = readBAL(filename, db);
47  if (!success) throw runtime_error("Could not access file!");
48 
49  // Get camera poses, as Values
50  size_t j = 0;
51  Values poses;
52  for (auto camera : db.cameras) {
53  poses.insert(j++, camera.pose());
54  }
55 
56  // Simulate measurements
57  const auto relativeTranslations = TranslationRecovery::SimulateMeasurements(
58  poses, {{0, 1}, {0, 2}, {1, 2}});
59 
60  // Check simulated measurements.
61  for (auto& unitTranslation : relativeTranslations) {
62  EXPECT(assert_equal(GetDirectionFromPoses(poses, unitTranslation),
63  unitTranslation.measured()));
64  }
65 
66  TranslationRecovery algorithm(relativeTranslations);
67  const auto graph = algorithm.buildGraph();
69 
70  // Run translation recovery
71  const double scale = 2.0;
72  const auto result = algorithm.run(scale);
73 
74  // Check result for first two translations, determined by prior
75  EXPECT(assert_equal(Point3(0, 0, 0), result.at<Point3>(0)));
77  Point3(2 * GetDirectionFromPoses(poses, relativeTranslations[0])),
78  result.at<Point3>(1)));
79 
80  // Check that the third translations is correct
81  Point3 Ta = poses.at<Pose3>(0).translation();
82  Point3 Tb = poses.at<Pose3>(1).translation();
83  Point3 Tc = poses.at<Pose3>(2).translation();
84  Point3 expected = (Tc - Ta) * (scale / (Tb - Ta).norm());
85  EXPECT(assert_equal(expected, result.at<Point3>(2), 1e-4));
86 
87  // TODO(frank): how to get stats back?
88  // EXPECT_DOUBLES_EQUAL(0.0199833, actualError, 1e-5);
89 }
90 
91 TEST(TranslationRecovery, TwoPoseTest) {
92  // Create a dataset with 2 poses.
93  // __ __
94  // \/ \/
95  // 0 _____ 1
96  //
97  // 0 and 1 face in the same direction but have a translation offset.
98  Values poses;
99  poses.insert<Pose3>(0, Pose3(Rot3(), Point3(0, 0, 0)));
100  poses.insert<Pose3>(1, Pose3(Rot3(), Point3(2, 0, 0)));
101 
102  auto relativeTranslations =
104 
105  // Check simulated measurements.
106  for (auto& unitTranslation : relativeTranslations) {
107  EXPECT(assert_equal(GetDirectionFromPoses(poses, unitTranslation),
108  unitTranslation.measured()));
109  }
110 
111  TranslationRecovery algorithm(relativeTranslations);
112  const auto graph = algorithm.buildGraph();
114 
115  // Run translation recovery
116  const auto result = algorithm.run(/*scale=*/3.0);
117 
118  // Check result for first two translations, determined by prior
119  EXPECT(assert_equal(Point3(0, 0, 0), result.at<Point3>(0)));
120  EXPECT(assert_equal(Point3(3, 0, 0), result.at<Point3>(1)));
121 }
122 
123 TEST(TranslationRecovery, ThreePoseTest) {
124  // Create a dataset with 3 poses.
125  // __ __
126  // \/ \/
127  // 0 _____ 1
128  // \ __ /
129  // \\//
130  // 3
131  //
132  // 0 and 1 face in the same direction but have a translation offset. 3 is in
133  // the same direction as 0 and 1, in between 0 and 1, with some Y axis offset.
134 
135  Values poses;
136  poses.insert<Pose3>(0, Pose3(Rot3(), Point3(0, 0, 0)));
137  poses.insert<Pose3>(1, Pose3(Rot3(), Point3(2, 0, 0)));
138  poses.insert<Pose3>(3, Pose3(Rot3(), Point3(1, -1, 0)));
139 
140  auto relativeTranslations = TranslationRecovery::SimulateMeasurements(
141  poses, {{0, 1}, {1, 3}, {3, 0}});
142 
143  // Check simulated measurements.
144  for (auto& unitTranslation : relativeTranslations) {
145  EXPECT(assert_equal(GetDirectionFromPoses(poses, unitTranslation),
146  unitTranslation.measured()));
147  }
148 
149  TranslationRecovery algorithm(relativeTranslations);
150  const auto graph = algorithm.buildGraph();
152 
153  const auto result = algorithm.run(/*scale=*/3.0);
154 
155  // Check result
156  EXPECT(assert_equal(Point3(0, 0, 0), result.at<Point3>(0)));
157  EXPECT(assert_equal(Point3(3, 0, 0), result.at<Point3>(1)));
158  EXPECT(assert_equal(Point3(1.5, -1.5, 0), result.at<Point3>(3)));
159 }
160 
161 TEST(TranslationRecovery, ThreePosesIncludingZeroTranslation) {
162  // Create a dataset with 3 poses.
163  // __ __
164  // \/ \/
165  // 0 _____ 1
166  // 2 <|
167  //
168  // 0 and 1 face in the same direction but have a translation offset. 2 is at
169  // the same point as 1 but is rotated, with little FOV overlap.
170  Values poses;
171  poses.insert<Pose3>(0, Pose3(Rot3(), Point3(0, 0, 0)));
172  poses.insert<Pose3>(1, Pose3(Rot3(), Point3(2, 0, 0)));
173  poses.insert<Pose3>(2, Pose3(Rot3::RzRyRx(-M_PI / 2, 0, 0), Point3(2, 0, 0)));
174 
175  auto relativeTranslations =
176  TranslationRecovery::SimulateMeasurements(poses, {{0, 1}, {1, 2}});
177 
178  // Check simulated measurements.
179  for (auto& unitTranslation : relativeTranslations) {
180  EXPECT(assert_equal(GetDirectionFromPoses(poses, unitTranslation),
181  unitTranslation.measured()));
182  }
183 
184  TranslationRecovery algorithm(relativeTranslations);
185  const auto graph = algorithm.buildGraph();
186  // There is only 1 non-zero translation edge.
188 
189  // Run translation recovery
190  const auto result = algorithm.run(/*scale=*/3.0);
191 
192  // Check result
193  EXPECT(assert_equal(Point3(0, 0, 0), result.at<Point3>(0)));
194  EXPECT(assert_equal(Point3(3, 0, 0), result.at<Point3>(1)));
195  EXPECT(assert_equal(Point3(3, 0, 0), result.at<Point3>(2)));
196 }
197 
198 TEST(TranslationRecovery, FourPosesIncludingZeroTranslation) {
199  // Create a dataset with 4 poses.
200  // __ __
201  // \/ \/
202  // 0 _____ 1
203  // \ __ 2 <|
204  // \\//
205  // 3
206  //
207  // 0 and 1 face in the same direction but have a translation offset. 2 is at
208  // the same point as 1 but is rotated, with very little FOV overlap. 3 is in
209  // the same direction as 0 and 1, in between 0 and 1, with some Y axis offset.
210 
211  Values poses;
212  poses.insert<Pose3>(0, Pose3(Rot3(), Point3(0, 0, 0)));
213  poses.insert<Pose3>(1, Pose3(Rot3(), Point3(2, 0, 0)));
214  poses.insert<Pose3>(2, Pose3(Rot3::RzRyRx(-M_PI / 2, 0, 0), Point3(2, 0, 0)));
215  poses.insert<Pose3>(3, Pose3(Rot3(), Point3(1, -1, 0)));
216 
217  auto relativeTranslations = TranslationRecovery::SimulateMeasurements(
218  poses, {{0, 1}, {1, 2}, {1, 3}, {3, 0}});
219 
220  // Check simulated measurements.
221  for (auto& unitTranslation : relativeTranslations) {
222  EXPECT(assert_equal(GetDirectionFromPoses(poses, unitTranslation),
223  unitTranslation.measured()));
224  }
225 
226  TranslationRecovery algorithm(relativeTranslations);
227  const auto graph = algorithm.buildGraph();
229 
230  // Run translation recovery
231  const auto result = algorithm.run(/*scale=*/4.0);
232 
233  // Check result
234  EXPECT(assert_equal(Point3(0, 0, 0), result.at<Point3>(0)));
235  EXPECT(assert_equal(Point3(4, 0, 0), result.at<Point3>(1)));
236  EXPECT(assert_equal(Point3(4, 0, 0), result.at<Point3>(2)));
237  EXPECT(assert_equal(Point3(2, -2, 0), result.at<Point3>(3)));
238 }
239 
240 TEST(TranslationRecovery, ThreePosesWithZeroTranslation) {
241  Values poses;
242  poses.insert<Pose3>(0, Pose3(Rot3::RzRyRx(-M_PI / 6, 0, 0), Point3(0, 0, 0)));
243  poses.insert<Pose3>(1, Pose3(Rot3(), Point3(0, 0, 0)));
244  poses.insert<Pose3>(2, Pose3(Rot3::RzRyRx(M_PI / 6, 0, 0), Point3(0, 0, 0)));
245 
246  auto relativeTranslations = TranslationRecovery::SimulateMeasurements(
247  poses, {{0, 1}, {1, 2}, {2, 0}});
248 
249  // Check simulated measurements.
250  for (auto& unitTranslation : relativeTranslations) {
251  EXPECT(assert_equal(GetDirectionFromPoses(poses, unitTranslation),
252  unitTranslation.measured()));
253  }
254 
255  TranslationRecovery algorithm(relativeTranslations);
256  const auto graph = algorithm.buildGraph();
257  // Graph size will be zero as there no 'non-zero distance' edges.
259 
260  // Run translation recovery
261  const auto result = algorithm.run(/*scale=*/4.0);
262 
263  // Check result
264  EXPECT(assert_equal(Point3(0, 0, 0), result.at<Point3>(0)));
265  EXPECT(assert_equal(Point3(0, 0, 0), result.at<Point3>(1)));
266  EXPECT(assert_equal(Point3(0, 0, 0), result.at<Point3>(2)));
267 }
268 
269 /* ************************************************************************* */
270 int main() {
271  TestResult tr;
272  return TestRegistry::runAllTests(tr);
273 }
274 /* ************************************************************************* */
size_t size() const
Definition: FactorGraph.h:306
Define the structure for SfM data.
Definition: dataset.h:326
static int runAllTests(TestResult &result)
void insert(Key j, const Value &val)
Definition: Values.cpp:140
Matrix expected
Definition: testMatrix.cpp:974
#define M_PI
Definition: main.h:78
Definition: Half.h:150
const Point3 & translation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get translation
Definition: Pose3.cpp:259
NonlinearFactorGraph graph
Values run(const double scale=1.0) const
Build and optimize factor graph.
const Pose3 & pose() const
return pose, constant version
TEST(TranslationRecovery, BAL)
string findExampleDataFile(const string &name)
Definition: dataset.cpp:65
Unit3 GetDirectionFromPoses(const Values &poses, const BinaryMeasurement< Unit3 > &unitTranslation)
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
Values result
const ValueType at(Key j) const
Definition: Values-inl.h:342
#define EXPECT(condition)
Definition: Test.h:151
Array< double, 1, 3 > e(1./3., 0.5, 2.)
traits
Definition: chartTesting.h:28
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
std::vector< SfmCamera > cameras
Set of cameras.
Definition: dataset.h:327
NonlinearFactorGraph buildGraph() const
Build the factor graph to do the optimization.
#define EXPECT_LONGS_EQUAL(expected, actual)
Definition: Test.h:155
def SimulateMeasurements(gt_poses, graph_edges)
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics scale
Recovering translations in an epipolar graph when rotations are given.
Vector3 Point3
Definition: Point3.h:35
static const CalibratedCamera camera(kDefaultPose)
utility functions for loading datasets
std::ptrdiff_t j
bool readBAL(const string &filename, SfmData &data)
This function parses a "Bundle Adjustment in the Large" (BAL) file and stores the data into a SfmData...
Definition: dataset.cpp:1073


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:50:06