25 using namespace gtsam;
35 TEST(dataSet, Balbianello) {
38 SfmData sfmData = SfmData::FromBundlerFile(filename);
50 actual = track0.measurements[0].second;
54 auto model = noiseModel::Isotropic::Sigma(2, 1.0);
66 TEST(dataSet, readBAL_Dubrovnik) {
69 SfmData sfmData = SfmData::FromBalFile(filename);
81 actual = track0.measurements[0].second;
95 Rot3 cRw(r1.x(),
r2.x(),
r3.x(), -r1.y(), -
r2.y(), -
r3.y(), -r1.z(), -
r2.z(),
116 TEST(dataSet, writeBAL_Dubrovnik) {
118 SfmData readData = SfmData::FromBalFile(filenameToRead);
125 SfmData writtenData = SfmData::FromBalFile(filenameToWrite);
141 Point3 expectedPoint = expectedTrack.
p;
142 Point3 actualPoint = actualTrack.
p;
147 Point3(expectedTrack.
r, expectedTrack.
g, expectedTrack.
b);
148 Point3 actualRGB =
Point3(actualTrack.
r, actualTrack.
g, actualTrack.
b);
162 TEST(dataSet, writeBALfromValues_Dubrovnik) {
164 SfmData readData = SfmData::FromBalFile(filenameToRead);
184 SfmData writtenData = SfmData::FromBalFile(filenameToWrite);
197 actual = track0.measurements[0].second;
204 Point3 expectedPoint = track0.p;
Point3 r1() const
first column
SfmData stores a bunch of SfmTracks.
static int runAllTests(TestResult &result)
Factor Graph consisting of non-linear factors.
noiseModel::Diagonal::shared_ptr model
const ValueType at(Key j) const
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Rot2 R(Rot2::fromAngle(0.1))
Pose2_ Expmap(const Vector3_ &xi)
Values initialCamerasAndPointsEstimate(const SfmData &db)
This function creates initial values for cameras and points from db.
Pose3 openGL2gtsam(const Rot3 &R, double tx, double ty, double tz)
This function converts an openGL camera pose to an GTSAM camera pose.
NonlinearFactorGraph graph
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Point3 r2() const
second column
std::vector< SfmTrack > tracks
Sparse set of points.
const Pose3 & pose() const
return pose
Rot3 inverse() const
inverse of a rotation
Point2 project(const Point3 &pw, OptionalJacobian< 2, 6 > Dpose={}, OptionalJacobian< 2, 3 > Dpoint={}, OptionalJacobian< 2, DimK > Dcal={}) const
project a 3D point from world coordinates into the image
bool writeBALfromValues(const std::string &filename, const SfmData &data, const Values &values)
This function writes a "Bundle Adjustment in the Large" (BAL) file from a SfmData structure and a val...
size_t numberMeasurements() const
Total number of measurements in this track.
#define EXPECT(condition)
Data structure for dealing with Structure from Motion data.
Point3 transformFrom(const Point3 &point, OptionalJacobian< 3, 6 > Hself={}, OptionalJacobian< 3, 3 > Hpoint={}) const
takes point in Pose coordinates and transforms it to world coordinates
std::vector< SfmMeasurement > measurements
The 2D image projections (id,(u,v))
size_t numberCameras() const
The number of cameras.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Class compose(const Class &g) const
TEST(dataSet, Balbianello)
GTSAM_EXPORT std::string findExampleDataFile(const std::string &name)
std::vector< SfmCamera > cameras
Set of cameras.
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
#define EXPECT_LONGS_EQUAL(expected, actual)
Point3 p
3D position of the point
float b
RGB color of the 3D point.
void insert(Key j, const Value &val)
Annotation for function names.
size_t numberTracks() const
The number of reconstructed 3D points.
Pose3 gtsam2openGL(const Rot3 &R, double tx, double ty, double tz)
This function converts a GTSAM camera pose to an openGL camera pose.
NonlinearFactorGraph sfmFactorGraph(const SharedNoiseModel &model=noiseModel::Isotropic::Sigma(2, 1.0), std::optional< size_t > fixedCamera=0, std::optional< size_t > fixedPoint=0) const
Create factor graph with projection factors and gauge fix.
GTSAM_EXPORT std::string createRewrittenFileName(const std::string &name)
bool writeBAL(const std::string &filename, const SfmData &data)
This function writes a "Bundle Adjustment in the Large" (BAL) file from a SfmData structure...
Point3 r3() const
third column