changed Measurements to measurements

release/4.3a0
Sushmita 2020-10-21 23:43:17 -04:00
parent b0cca7eedd
commit 045780a151
14 changed files with 55 additions and 48 deletions

View File

@ -51,7 +51,7 @@ void createExampleBALFile(const string& filename, const vector<Point3>& P,
// Project points in both cameras
for (size_t i = 0; i < 2; i++)
track.Measurements.push_back(make_pair(i, data.cameras[i].project(p)));
track.measurements.push_back(make_pair(i, data.cameras[i].project(p)));
// Add track to data
data.tracks.push_back(track);

View File

@ -77,7 +77,7 @@ int main(int argc, char* argv[]) {
for (const SfmTrack& track : mydata.tracks) {
// Leaf expression for j^th point
Point3_ point_('p', j);
for (const SfmMeasurement& m : track.Measurements) {
for (const SfmMeasurement& m : track.measurements) {
size_t i = m.first;
Point2 uv = m.second;
// Leaf expression for i^th camera

View File

@ -55,7 +55,7 @@ int main (int argc, char* argv[]) {
// Add measurements to the factor graph
size_t j = 0;
for(const SfmTrack& track: mydata.tracks) {
for(const SfmMeasurement& m: track.Measurements) {
for(const SfmMeasurement& m: track.measurements) {
size_t i = m.first;
Point2 uv = m.second;
graph.emplace_shared<MyFactor>(uv, noise, C(i), P(j)); // note use of shorthand symbols C and P

View File

@ -59,7 +59,7 @@ int main(int argc, char* argv[]) {
// Add measurements to the factor graph
size_t j = 0;
for (const SfmTrack& track : mydata.tracks) {
for (const SfmMeasurement& m : track.Measurements) {
for (const SfmMeasurement& m : track.measurements) {
size_t i = m.first;
Point2 uv = m.second;
graph.emplace_shared<MyFactor>(

View File

@ -2759,11 +2759,20 @@ virtual class EssentialMatrixFactor : gtsam::NoiseModelFactor {
};
#include <gtsam/slam/dataset.h>
// Dummy classes, for MATLAB wrappers
class SfmMeasurement{};
class SiftIndex{ };
class SfmMeasurements{};
class SfmCamera{};
class SfmMeasurement{
SfmMeasurement();
size_t i() const;
Point2 j() const;
};
class SiftIndex{
SiftIndex();
size_t i() const;
size_t j() const;
};
class SfmMeasurements{
SfmMeasurements();
};
class SfmTrack {
SfmTrack();
@ -2772,7 +2781,7 @@ class SfmTrack {
void setP(gtsam::Point3& p_);
gtsam::SfmMeasurement measurement(size_t idx) const;
gtsam::SiftIndex siftIndex(size_t idx) const;
void add_measurement(pair<size_t, gtsam::Point2> m);
void add_measurement(const pair<size_t, gtsam::Point2>& m);
SfmMeasurements& measurements();
};
@ -2782,8 +2791,8 @@ class SfmData {
size_t number_tracks() const;
gtsam::PinholeCamera<gtsam::Cal3Bundler> camera(size_t idx) const;
gtsam::SfmTrack track(size_t idx) const;
void add_track(gtsam::SfmTrack t);
void add_camera(gtsam::SfmCamera cam);
void add_track(const gtsam::SfmTrack& t) ;
void add_camera(const gtsam::SfmCamer& cam);
};
gtsam::SfmData readBal(string filename);

View File

@ -144,8 +144,8 @@ protected:
template<class SFM_TRACK>
void add(const SFM_TRACK& trackToAdd) {
for (size_t k = 0; k < trackToAdd.number_measurements(); k++) {
this->measured_.push_back(trackToAdd.Measurements[k].second);
this->keys_.push_back(trackToAdd.Measurements[k].first);
this->measured_.push_back(trackToAdd.measurements[k].second);
this->keys_.push_back(trackToAdd.measurements[k].first);
}
}

View File

@ -1052,13 +1052,13 @@ bool readBundler(const string &filename, SfmData &data) {
size_t nvisible = 0;
is >> nvisible;
track.Measurements.reserve(nvisible);
track.measurements.reserve(nvisible);
track.siftIndices.reserve(nvisible);
for (size_t k = 0; k < nvisible; k++) {
size_t cam_idx = 0, point_idx = 0;
float u, v;
is >> cam_idx >> point_idx >> u >> v;
track.Measurements.emplace_back(cam_idx, Point2(u, -v));
track.measurements.emplace_back(cam_idx, Point2(u, -v));
track.siftIndices.emplace_back(cam_idx, point_idx);
}
@ -1089,7 +1089,7 @@ bool readBAL(const string &filename, SfmData &data) {
size_t i = 0, j = 0;
float u, v;
is >> i >> j >> u >> v;
data.tracks[j].Measurements.emplace_back(i, Point2(u, -v));
data.tracks[j].measurements.emplace_back(i, Point2(u, -v));
}
// Get the information for the camera poses
@ -1163,7 +1163,7 @@ bool writeBAL(const string &filename, SfmData &data) {
for (size_t k = 0; k < track.number_measurements();
k++) { // for each observation of the 3D point j
size_t i = track.Measurements[k].first; // camera id
size_t i = track.measurements[k].first; // camera id
double u0 = data.cameras[i].calibration().u0();
double v0 = data.cameras[i].calibration().v0();
@ -1173,9 +1173,9 @@ bool writeBAL(const string &filename, SfmData &data) {
<< endl;
}
double pixelBALx = track.Measurements[k].second.x() -
double pixelBALx = track.measurements[k].second.x() -
u0; // center of image is the origin
double pixelBALy = -(track.Measurements[k].second.y() -
double pixelBALy = -(track.measurements[k].second.y() -
v0); // center of image is the origin
Point2 pixelMeasurement(pixelBALx, pixelBALy);
os << i /*camera id*/ << " " << j /*point id*/ << " "

View File

@ -220,12 +220,12 @@ struct SfmTrack {
SfmTrack(): p(0,0,0) {}
Point3 p; ///< 3D position of the point
float r, g, b; ///< RGB color of the 3D point
std::vector<SfmMeasurement> Measurements; ///< The 2D image projections (id,(u,v))
std::vector<SfmMeasurement> measurements; ///< The 2D image projections (id,(u,v))
std::vector<SiftIndex> siftIndices;
/// Total number of measurements in this track
size_t number_measurements() const {
return Measurements.size();
return measurements.size();
}
/// Set 3D point
void setP(Point3& p_){
@ -234,7 +234,7 @@ struct SfmTrack {
/// Get the measurement (camera index, Point2) at pose index `idx`
SfmMeasurement measurement(size_t idx) const {
return Measurements[idx];
return measurements[idx];
}
/// Get the SIFT feature index corresponding to the measurement at `idx`
SiftIndex siftIndex(size_t idx) const {
@ -243,12 +243,12 @@ struct SfmTrack {
Point3 point3() const {
return p;
}
void add_measurement(pair<size_t, gtsam::Point2> m) {
Measurements.push_back(m);
void add_measurement(pair<size_t, gtsam::Point2>& m) const{
measurements.push_back(m);
}
SfmMeasurements& measurements() {
return Measurements;
return measurements;
}
};
@ -259,7 +259,7 @@ typedef PinholeCamera<Cal3Bundler> SfmCamera;
/// Define the structure for SfM data
struct SfmData {
std::vector<SfmMeasurement> Measurements;
std::vector<SfmMeasurement> measurements; ///<Set of measurements in a track
std::vector<SfmCamera> cameras; ///< Set of cameras
std::vector<SfmTrack> tracks; ///< Sparse set of points
size_t number_cameras() const {
@ -278,11 +278,11 @@ struct SfmData {
return tracks[idx];
}
void add_track(SfmTrack t) {
void add_track(SfmTrack& t) const {
tracks.push_back(t);
}
void add_camera(SfmCamera cam){
void add_camera(SfmCamera& cam) const{
cameras.push_back(cam);
}
};

View File

@ -166,9 +166,9 @@ TEST( dataSet, Balbianello)
EXPECT_LONGS_EQUAL(3,track0.number_measurements());
// Check projection of a given point
EXPECT_LONGS_EQUAL(0,track0.Measurements[0].first);
EXPECT_LONGS_EQUAL(0,track0.measurements[0].first);
const SfmCamera& camera0 = mydata.cameras[0];
Point2 expected = camera0.project(track0.p), actual = track0.Measurements[0].second;
Point2 expected = camera0.project(track0.p), actual = track0.measurements[0].second;
EXPECT(assert_equal(expected,actual,1));
}
@ -476,9 +476,9 @@ TEST( dataSet, readBAL_Dubrovnik)
EXPECT_LONGS_EQUAL(3,track0.number_measurements());
// Check projection of a given point
EXPECT_LONGS_EQUAL(0,track0.Measurements[0].first);
EXPECT_LONGS_EQUAL(0,track0.measurements[0].first);
const SfmCamera& camera0 = mydata.cameras[0];
Point2 expected = camera0.project(track0.p), actual = track0.Measurements[0].second;
Point2 expected = camera0.project(track0.p), actual = track0.measurements[0].second;
EXPECT(assert_equal(expected,actual,12));
}
@ -557,8 +557,8 @@ TEST( dataSet, writeBAL_Dubrovnik)
// check measurements
for (size_t k = 0; k < actualTrack.number_measurements(); k++){
EXPECT_LONGS_EQUAL(expectedTrack.Measurements[k].first,actualTrack.Measurements[k].first);
EXPECT(assert_equal(expectedTrack.Measurements[k].second,actualTrack.Measurements[k].second));
EXPECT_LONGS_EQUAL(expectedTrack.measurements[k].first,actualTrack.measurements[k].first);
EXPECT(assert_equal(expectedTrack.measurements[k].second,actualTrack.measurements[k].second));
}
}
}
@ -600,9 +600,9 @@ TEST( dataSet, writeBALfromValues_Dubrovnik){
EXPECT_LONGS_EQUAL(3,track0.number_measurements());
// Check projection of a given point
EXPECT_LONGS_EQUAL(0,track0.Measurements[0].first);
EXPECT_LONGS_EQUAL(0,track0.measurements[0].first);
const SfmCamera& camera0 = writtenData.cameras[0];
Point2 expected = camera0.project(track0.p), actual = track0.Measurements[0].second;
Point2 expected = camera0.project(track0.p), actual = track0.measurements[0].second;
EXPECT(assert_equal(expected,actual,12));
Pose3 expectedPose = camera0.pose();

View File

@ -46,10 +46,10 @@ EssentialMatrix trueE(trueRotation, trueDirection);
double baseline = 0.1; // actual baseline of the camera
Point2 pA(size_t i) {
return data.tracks[i].Measurements[0].second;
return data.tracks[i].measurements[0].second;
}
Point2 pB(size_t i) {
return data.tracks[i].Measurements[1].second;
return data.tracks[i].measurements[1].second;
}
Vector vA(size_t i) {
return EssentialMatrix::Homogeneous(pA(i));
@ -367,10 +367,10 @@ EssentialMatrix trueE(aRb, Unit3(aTb));
double baseline = 10; // actual baseline of the camera
Point2 pA(size_t i) {
return data.tracks[i].Measurements[0].second;
return data.tracks[i].measurements[0].second;
}
Point2 pB(size_t i) {
return data.tracks[i].Measurements[1].second;
return data.tracks[i].measurements[1].second;
}
boost::shared_ptr<Cal3Bundler> //

View File

@ -283,14 +283,14 @@ TEST(SmartProjectionFactor, perturbPoseAndOptimizeFromSfM_tracks ) {
SfmTrack track1;
for (size_t i = 0; i < 3; ++i) {
track1.Measurements.emplace_back(i + 1, measurements_cam1.at(i));
track1.measurements.emplace_back(i + 1, measurements_cam1.at(i));
}
SmartFactor::shared_ptr smartFactor1(new SmartFactor(unit2));
smartFactor1->add(track1);
SfmTrack track2;
for (size_t i = 0; i < 3; ++i) {
track2.Measurements.emplace_back(i + 1, measurements_cam2.at(i));
track2.measurements.emplace_back(i + 1, measurements_cam2.at(i));
}
SmartFactor::shared_ptr smartFactor2(new SmartFactor(unit2));
smartFactor2->add(track2);

View File

@ -11,5 +11,4 @@ PYBIND11_MAKE_OPAQUE(std::vector<boost::shared_ptr<gtsam::BetweenFactor<gtsam::P
PYBIND11_MAKE_OPAQUE(std::vector<boost::shared_ptr<gtsam::BetweenFactor<gtsam::Pose2> > >);
PYBIND11_MAKE_OPAQUE(std::vector<gtsam::IndexPair>);
PYBIND11_MAKE_OPAQUE(std::vector<gtsam::SfmMeasurement>);
PYBIND11_MAKE_OPAQUE(std::vector<gtsam::SiftIndex>);
PYBIND11_MAKE_OPAQUE(std::vector<gtsam::SfmCamera>);
PYBIND11_MAKE_OPAQUE(std::vector<gtsam::SiftIndex>);

View File

@ -14,5 +14,4 @@ py::bind_map<gtsam::IndexPairSetMap>(m_, "IndexPairSetMap");
py::bind_vector<gtsam::IndexPairVector>(m_, "IndexPairVector");
py::bind_map<gtsam::KeyPairDoubleMap>(m_, "KeyPairDoubleMap");
py::bind_vector<std::vector<gtsam::SfmMeasurement> >(m_, "Measurement");
py::bind_vector<std::vector<gtsam::SiftIndex> >(m_, "SiftIndexVector");
py::bind_vector<std::vector<gtsam::SfmCamera> >(m_, "cameras");
py::bind_vector<std::vector<gtsam::SiftIndex> >(m_, "SiftIndexVector");

View File

@ -50,7 +50,7 @@ TEST(PinholeCamera, BAL) {
NonlinearFactorGraph graph;
for (size_t j = 0; j < db.number_tracks(); j++) {
for (const SfmMeasurement& m: db.tracks[j].Measurements)
for (const SfmMeasurement& m: db.tracks[j].measurements)
graph.emplace_shared<sfmFactor>(m.second, unit2, m.first, P(j));
}