25 using namespace gtsam;
34 return Unit3(Tb - Ta);
46 SfmData db = SfmData::FromBalFile(filename);
57 poses, {{0, 1}, {0, 2}, {1, 2}});
60 for (
auto& unitTranslation : relativeTranslations) {
62 unitTranslation.measured()));
70 const double scale = 2.0;
71 const auto result = algorithm.
run(relativeTranslations, scale);
101 auto relativeTranslations =
105 for (
auto& unitTranslation : relativeTranslations) {
107 unitTranslation.measured()));
115 const auto result = algorithm.
run(relativeTranslations, 3.0);
140 poses, {{0, 1}, {1, 3}, {3, 0}});
143 for (
auto& unitTranslation : relativeTranslations) {
145 unitTranslation.measured()));
152 const auto result = algorithm.
run(relativeTranslations, 3.0);
174 auto relativeTranslations =
178 for (
auto& unitTranslation : relativeTranslations) {
180 unitTranslation.measured()));
185 const auto result = algorithm.
run(relativeTranslations, 3.0);
213 poses, {{0, 1}, {1, 2}, {1, 3}, {3, 0}});
216 for (
auto& unitTranslation : relativeTranslations) {
218 unitTranslation.measured()));
224 const auto result = algorithm.
run(relativeTranslations, 4.0);
240 poses, {{0, 1}, {1, 2}, {2, 0}});
243 for (
auto& unitTranslation : relativeTranslations) {
245 unitTranslation.measured()));
251 const auto result = algorithm.
run(relativeTranslations, 4.0);
277 poses, {{0, 1}, {0, 3}, {1, 3}});
279 std::vector<BinaryMeasurement<Point3>> betweenTranslations;
280 betweenTranslations.emplace_back(0, 3,
Point3(1, -1, 0),
281 noiseModel::Isotropic::Sigma(3, 1
e-2));
285 algorithm.
run(relativeTranslations, 0.0, betweenTranslations);
311 poses, {{0, 1}, {0, 3}, {1, 3}});
313 std::vector<BinaryMeasurement<Point3>> betweenTranslations;
314 betweenTranslations.emplace_back(0, 1,
Point3(2, 0, 0),
315 noiseModel::Constrained::All(3, 1e2));
319 algorithm.
run(relativeTranslations, 0.0, betweenTranslations);
337 poses, {{0, 1}, {0, 3}, {1, 3}});
339 std::vector<BinaryMeasurement<Point3>> betweenTranslations;
340 betweenTranslations.emplace_back(0, 1,
Point3(2, 0, 0),
341 noiseModel::Constrained::All(3, 1e2));
343 betweenTranslations.emplace_back(0, 4,
Point3(1, 2, 1));
347 algorithm.
run(relativeTranslations, 0.0, betweenTranslations);
Point3 translation(const Pose3 &pose, OptionalJacobian< 3, 6 > H)
const Point3 & translation(OptionalJacobian< 3, 6 > Hself={}) const
get translation
SfmData stores a bunch of SfmTracks.
static int runAllTests(TestResult &result)
const ValueType at(Key j) const
Values run(const TranslationEdges &relativeTranslations, const double scale=1.0, const std::vector< BinaryMeasurement< Point3 >> &betweenTranslations={}, const Values &initialValues=Values()) const
Build and optimize factor graph.
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
NonlinearFactorGraph graph
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
TEST(TranslationRecovery, BAL)
Unit3 GetDirectionFromPoses(const Values &poses, const BinaryMeasurement< Unit3 > &unitTranslation)
Represents a 3D point on a unit sphere.
const Pose3 & pose() const
return pose, constant version
#define EXPECT(condition)
Data structure for dealing with Structure from Motion data.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
NonlinearFactorGraph buildGraph(const std::vector< BinaryMeasurement< Unit3 >> &relativeTranslations) const
Build the factor graph to do the optimization.
GTSAM_EXPORT std::string findExampleDataFile(const std::string &name)
std::vector< SfmCamera > cameras
Set of cameras.
#define EXPECT_LONGS_EQUAL(expected, actual)
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
void insert(Key j, const Value &val)
Recovering translations in an epipolar graph when rotations are given.
static const CalibratedCamera camera(kDefaultPose)
utility functions for loading datasets