From 3d51989f2ee6ab300dfa0786707d7ebd957588b9 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Mon, 31 Jan 2022 08:32:44 -0500 Subject: [PATCH] Deprecated incorrectly named methods --- examples/SFMExampleExpressions_bal.cpp | 2 +- examples/SFMExample_bal.cpp | 2 +- examples/SFMExample_bal_COLAMD_METIS.cpp | 4 +-- gtsam/slam/SmartFactorBase.h | 2 +- gtsam/slam/slam.i | 12 +++---- gtsam/slam/tests/testDataset.cpp | 32 +++++++++---------- .../slam/tests/testEssentialMatrixFactor.cpp | 6 ++-- python/gtsam/examples/SFMExample_bal.py | 16 +++++----- python/gtsam/tests/test_SfmData.py | 18 +++++------ python/gtsam/tests/test_pickle.py | 4 +-- tests/testGeneralSFMFactorB.cpp | 2 +- timing/timeSFMBAL.cpp | 2 +- timing/timeSFMBAL.h | 4 +-- timing/timeSFMBALautodiff.cpp | 2 +- timing/timeSFMBALcamTnav.cpp | 2 +- timing/timeSFMBALnavTcam.cpp | 2 +- timing/timeSFMBALsmart.cpp | 2 +- 17 files changed, 57 insertions(+), 57 deletions(-) diff --git a/examples/SFMExampleExpressions_bal.cpp b/examples/SFMExampleExpressions_bal.cpp index 3768ee2a3..4cc6b1185 100644 --- a/examples/SFMExampleExpressions_bal.cpp +++ b/examples/SFMExampleExpressions_bal.cpp @@ -49,7 +49,7 @@ int main(int argc, char* argv[]) { SfmData mydata; readBAL(filename, mydata); cout << boost::format("read %1% tracks on %2% cameras\n") % - mydata.number_tracks() % mydata.number_cameras(); + mydata.nrTracks() % mydata.nrCameras(); // Create a factor graph ExpressionFactorGraph graph; diff --git a/examples/SFMExample_bal.cpp b/examples/SFMExample_bal.cpp index ffb5b195b..a93e43850 100644 --- a/examples/SFMExample_bal.cpp +++ b/examples/SFMExample_bal.cpp @@ -43,7 +43,7 @@ int main (int argc, char* argv[]) { // Load the SfM data from file SfmData mydata; readBAL(filename, mydata); - cout << boost::format("read %1% tracks on %2% cameras\n") % mydata.number_tracks() % mydata.number_cameras(); + cout << boost::format("read %1% tracks on %2% cameras\n") % mydata.nrTracks() % mydata.nrCameras(); // Create a factor graph NonlinearFactorGraph graph; diff --git a/examples/SFMExample_bal_COLAMD_METIS.cpp b/examples/SFMExample_bal_COLAMD_METIS.cpp index b79a9fa28..90b397b06 100644 --- a/examples/SFMExample_bal_COLAMD_METIS.cpp +++ b/examples/SFMExample_bal_COLAMD_METIS.cpp @@ -48,7 +48,7 @@ int main(int argc, char* argv[]) { SfmData mydata; readBAL(filename, mydata); cout << boost::format("read %1% tracks on %2% cameras\n") % - mydata.number_tracks() % mydata.number_cameras(); + mydata.nrTracks() % mydata.nrCameras(); // Create a factor graph NonlinearFactorGraph graph; @@ -131,7 +131,7 @@ int main(int argc, char* argv[]) { cout << "Time comparison by solving " << filename << " results:" << endl; cout << boost::format("%1% point tracks and %2% cameras\n") % - mydata.number_tracks() % mydata.number_cameras() + mydata.nrTracks() % mydata.nrCameras() << endl; tictoc_print_(); diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 209c1196d..42a950848 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -146,7 +146,7 @@ protected: */ template void add(const SFM_TRACK& trackToAdd) { - for (size_t k = 0; k < trackToAdd.number_measurements(); k++) { + for (size_t k = 0; k < trackToAdd.nrMeasurements(); k++) { this->measured_.push_back(trackToAdd.measurements[k].second); this->keys_.push_back(trackToAdd.measurements[k].first); } diff --git a/gtsam/slam/slam.i b/gtsam/slam/slam.i index 2b25a4369..51a590405 100644 --- a/gtsam/slam/slam.i +++ b/gtsam/slam/slam.i @@ -220,10 +220,10 @@ class SfmTrack { std::vector> measurements; - size_t number_measurements() const; + size_t nrMeasurements() const; pair measurement(size_t idx) const; pair siftIndex(size_t idx) const; - void add_measurement(size_t idx, const gtsam::Point2& m); + void addMeasurement(size_t idx, const gtsam::Point2& m); // enabling serialization functionality void serialize() const; @@ -234,12 +234,12 @@ class SfmTrack { class SfmData { SfmData(); - size_t number_cameras() const; - size_t number_tracks() const; + size_t nrCameras() const; + size_t nrTracks() const; gtsam::PinholeCamera camera(size_t idx) const; gtsam::SfmTrack track(size_t idx) const; - void add_track(const gtsam::SfmTrack& t); - void add_camera(const gtsam::SfmCamera& cam); + void addTrack(const gtsam::SfmTrack& t); + void addCamera(const gtsam::SfmCamera& cam); // enabling serialization functionality void serialize() const; diff --git a/gtsam/slam/tests/testDataset.cpp b/gtsam/slam/tests/testDataset.cpp index aad9124c5..b88832ff2 100644 --- a/gtsam/slam/tests/testDataset.cpp +++ b/gtsam/slam/tests/testDataset.cpp @@ -160,10 +160,10 @@ TEST( dataSet, Balbianello) CHECK(readBundler(filename, mydata)); // Check number of things - EXPECT_LONGS_EQUAL(5,mydata.number_cameras()); - EXPECT_LONGS_EQUAL(544,mydata.number_tracks()); + EXPECT_LONGS_EQUAL(5,mydata.nrCameras()); + EXPECT_LONGS_EQUAL(544,mydata.nrTracks()); const SfmTrack& track0 = mydata.tracks[0]; - EXPECT_LONGS_EQUAL(3,track0.number_measurements()); + EXPECT_LONGS_EQUAL(3,track0.nrMeasurements()); // Check projection of a given point EXPECT_LONGS_EQUAL(0,track0.measurements[0].first); @@ -470,10 +470,10 @@ TEST( dataSet, readBAL_Dubrovnik) CHECK(readBAL(filename, mydata)); // Check number of things - EXPECT_LONGS_EQUAL(3,mydata.number_cameras()); - EXPECT_LONGS_EQUAL(7,mydata.number_tracks()); + EXPECT_LONGS_EQUAL(3,mydata.nrCameras()); + EXPECT_LONGS_EQUAL(7,mydata.nrTracks()); const SfmTrack& track0 = mydata.tracks[0]; - EXPECT_LONGS_EQUAL(3,track0.number_measurements()); + EXPECT_LONGS_EQUAL(3,track0.nrMeasurements()); // Check projection of a given point EXPECT_LONGS_EQUAL(0,track0.measurements[0].first); @@ -533,16 +533,16 @@ TEST( dataSet, writeBAL_Dubrovnik) CHECK(readBAL(filenameToWrite, writtenData)); // Check that what we read is the same as what we wrote - EXPECT_LONGS_EQUAL(readData.number_cameras(),writtenData.number_cameras()); - EXPECT_LONGS_EQUAL(readData.number_tracks(),writtenData.number_tracks()); + EXPECT_LONGS_EQUAL(readData.nrCameras(),writtenData.nrCameras()); + EXPECT_LONGS_EQUAL(readData.nrTracks(),writtenData.nrTracks()); - for (size_t i = 0; i < readData.number_cameras(); i++){ + for (size_t i = 0; i < readData.nrCameras(); i++){ PinholeCamera expectedCamera = writtenData.cameras[i]; PinholeCamera actualCamera = readData.cameras[i]; EXPECT(assert_equal(expectedCamera,actualCamera)); } - for (size_t j = 0; j < readData.number_tracks(); j++){ + for (size_t j = 0; j < readData.nrTracks(); j++){ // check point SfmTrack expectedTrack = writtenData.tracks[j]; SfmTrack actualTrack = readData.tracks[j]; @@ -556,7 +556,7 @@ TEST( dataSet, writeBAL_Dubrovnik) EXPECT(assert_equal(expectedRGB,actualRGB)); // check measurements - for (size_t k = 0; k < actualTrack.number_measurements(); k++){ + for (size_t k = 0; k < actualTrack.nrMeasurements(); k++){ EXPECT_LONGS_EQUAL(expectedTrack.measurements[k].first,actualTrack.measurements[k].first); EXPECT(assert_equal(expectedTrack.measurements[k].second,actualTrack.measurements[k].second)); } @@ -575,11 +575,11 @@ TEST( dataSet, writeBALfromValues_Dubrovnik){ Pose3 poseChange = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.3,0.1,0.3)); Values value; - for(size_t i=0; i < readData.number_cameras(); i++){ // for each camera + for(size_t i=0; i < readData.nrCameras(); i++){ // for each camera Pose3 pose = poseChange.compose(readData.cameras[i].pose()); value.insert(X(i), pose); } - for(size_t j=0; j < readData.number_tracks(); j++){ // for each point + for(size_t j=0; j < readData.nrTracks(); j++){ // for each point Point3 point = poseChange.transformFrom( readData.tracks[j].p ); value.insert(P(j), point); } @@ -594,10 +594,10 @@ TEST( dataSet, writeBALfromValues_Dubrovnik){ // Check that the reprojection errors are the same and the poses are correct // Check number of things - EXPECT_LONGS_EQUAL(3,writtenData.number_cameras()); - EXPECT_LONGS_EQUAL(7,writtenData.number_tracks()); + EXPECT_LONGS_EQUAL(3,writtenData.nrCameras()); + EXPECT_LONGS_EQUAL(7,writtenData.nrTracks()); const SfmTrack& track0 = writtenData.tracks[0]; - EXPECT_LONGS_EQUAL(3,track0.number_measurements()); + EXPECT_LONGS_EQUAL(3,track0.nrMeasurements()); // Check projection of a given point EXPECT_LONGS_EQUAL(0,track0.measurements[0].first); diff --git a/gtsam/slam/tests/testEssentialMatrixFactor.cpp b/gtsam/slam/tests/testEssentialMatrixFactor.cpp index 03775a70f..6df59ba48 100644 --- a/gtsam/slam/tests/testEssentialMatrixFactor.cpp +++ b/gtsam/slam/tests/testEssentialMatrixFactor.cpp @@ -632,14 +632,14 @@ TEST(EssentialMatrixFactor2, extraMinimization) { // We start with a factor graph and add constraints to it // Noise sigma is 1, assuming pixel measurements NonlinearFactorGraph graph; - for (size_t i = 0; i < data.number_tracks(); i++) + for (size_t i = 0; i < data.nrTracks(); i++) graph.emplace_shared(100, i, pA(i), pB(i), model2, K); // Check error at ground truth Values truth; truth.insert(100, trueE); - for (size_t i = 0; i < data.number_tracks(); i++) { + for (size_t i = 0; i < data.nrTracks(); i++) { Point3 P1 = data.tracks[i].p; truth.insert(i, double(baseline / P1.z())); } @@ -654,7 +654,7 @@ TEST(EssentialMatrixFactor2, extraMinimization) { // Check result EssentialMatrix actual = result.at(100); EXPECT(assert_equal(trueE, actual, 1e-1)); - for (size_t i = 0; i < data.number_tracks(); i++) + for (size_t i = 0; i < data.nrTracks(); i++) EXPECT_DOUBLES_EQUAL(truth.at(i), result.at(i), 1e-1); // Check error at result diff --git a/python/gtsam/examples/SFMExample_bal.py b/python/gtsam/examples/SFMExample_bal.py index f3e48c3c3..1c4d76c83 100644 --- a/python/gtsam/examples/SFMExample_bal.py +++ b/python/gtsam/examples/SFMExample_bal.py @@ -29,10 +29,10 @@ DEFAULT_BAL_DATASET = "dubrovnik-3-7-pre" def plot_scene(scene_data: gtsam.SfmData, result: gtsam.Values) -> None: """Plot the SFM results.""" plot_vals = gtsam.Values() - for cam_idx in range(scene_data.number_cameras()): + for cam_idx in range(scene_data.nrCameras()): plot_vals.insert(C(cam_idx), result.atPinholeCameraCal3Bundler(C(cam_idx)).pose()) - for j in range(scene_data.number_tracks()): + for j in range(scene_data.nrTracks()): plot_vals.insert(P(j), result.atPoint3(P(j))) plot.plot_3d_points(0, plot_vals, linespec="g.") @@ -47,8 +47,8 @@ def run(args: argparse.Namespace) -> None: # Load the SfM data from file scene_data = gtsam.readBal(input_file) - logging.info("read %d tracks on %d cameras\n", scene_data.number_tracks(), - scene_data.number_cameras()) + logging.info("read %d tracks on %d cameras\n", scene_data.nrTracks(), + scene_data.nrCameras()) # Create a factor graph graph = gtsam.NonlinearFactorGraph() @@ -57,10 +57,10 @@ def run(args: argparse.Namespace) -> None: noise = gtsam.noiseModel.Isotropic.Sigma(2, 1.0) # one pixel in u and v # Add measurements to the factor graph - for j in range(scene_data.number_tracks()): + for j in range(scene_data.nrTracks()): track = scene_data.track(j) # SfmTrack # retrieve the SfmMeasurement objects - for m_idx in range(track.number_measurements()): + for m_idx in range(track.nrMeasurements()): # i represents the camera index, and uv is the 2d measurement i, uv = track.measurement(m_idx) # note use of shorthand symbols C and P @@ -82,13 +82,13 @@ def run(args: argparse.Namespace) -> None: i = 0 # add each PinholeCameraCal3Bundler - for cam_idx in range(scene_data.number_cameras()): + for cam_idx in range(scene_data.nrCameras()): camera = scene_data.camera(cam_idx) initial.insert(C(i), camera) i += 1 # add each SfmTrack - for j in range(scene_data.number_tracks()): + for j in range(scene_data.nrTracks()): track = scene_data.track(j) initial.insert(P(j), track.point3()) diff --git a/python/gtsam/tests/test_SfmData.py b/python/gtsam/tests/test_SfmData.py index 9c965ddc5..79004f03c 100644 --- a/python/gtsam/tests/test_SfmData.py +++ b/python/gtsam/tests/test_SfmData.py @@ -39,10 +39,10 @@ class TestSfmData(GtsamTestCase): # translating point uv_i1 along X-axis uv_i2 = gtsam.Point2(24.88, 82) # add measurements to the track - self.tracks.add_measurement(i1, uv_i1) - self.tracks.add_measurement(i2, uv_i2) + self.tracks.addMeasurement(i1, uv_i1) + self.tracks.addMeasurement(i2, uv_i2) # Number of measurements in the track is 2 - self.assertEqual(self.tracks.number_measurements(), 2) + self.assertEqual(self.tracks.nrMeasurements(), 2) # camera_idx in the first measurement of the track corresponds to i1 cam_idx, img_measurement = self.tracks.measurement(0) self.assertEqual(cam_idx, i1) @@ -64,13 +64,13 @@ class TestSfmData(GtsamTestCase): measurements = [(i1, uv_i1), (i2, uv_i2), (i3, uv_i3)] pt = gtsam.Point3(1.0, 6.0, 2.0) track2 = gtsam.SfmTrack(pt) - track2.add_measurement(i1, uv_i1) - track2.add_measurement(i2, uv_i2) - track2.add_measurement(i3, uv_i3) - self.data.add_track(self.tracks) - self.data.add_track(track2) + track2.addMeasurement(i1, uv_i1) + track2.addMeasurement(i2, uv_i2) + track2.addMeasurement(i3, uv_i3) + self.data.addTrack(self.tracks) + self.data.addTrack(track2) # Number of tracks in SfmData is 2 - self.assertEqual(self.data.number_tracks(), 2) + self.assertEqual(self.data.nrTracks(), 2) # camera idx of first measurement of second track corresponds to i1 cam_idx, img_measurement = self.data.track(1).measurement(0) self.assertEqual(cam_idx, i1) diff --git a/python/gtsam/tests/test_pickle.py b/python/gtsam/tests/test_pickle.py index 0acbf6765..a6a5745bc 100644 --- a/python/gtsam/tests/test_pickle.py +++ b/python/gtsam/tests/test_pickle.py @@ -37,8 +37,8 @@ class TestPickle(GtsamTestCase): def test_sfmTrack_roundtrip(self): obj = SfmTrack(Point3(1, 1, 0)) - obj.add_measurement(0, Point2(-1, 5)) - obj.add_measurement(1, Point2(6, 2)) + obj.addMeasurement(0, Point2(-1, 5)) + obj.addMeasurement(1, Point2(6, 2)) self.assertEqualityOnPickleRoundtrip(obj) def test_unit3_roundtrip(self): diff --git a/tests/testGeneralSFMFactorB.cpp b/tests/testGeneralSFMFactorB.cpp index 05b4c7f66..895c8484b 100644 --- a/tests/testGeneralSFMFactorB.cpp +++ b/tests/testGeneralSFMFactorB.cpp @@ -49,7 +49,7 @@ TEST(PinholeCamera, BAL) { SharedNoiseModel unit2 = noiseModel::Unit::Create(2); NonlinearFactorGraph graph; - for (size_t j = 0; j < db.number_tracks(); j++) { + for (size_t j = 0; j < db.nrTracks(); j++) { for (const SfmMeasurement& m: db.tracks[j].measurements) graph.emplace_shared(m.second, unit2, m.first, P(j)); } diff --git a/timing/timeSFMBAL.cpp b/timing/timeSFMBAL.cpp index 4a58a57a6..06b963757 100644 --- a/timing/timeSFMBAL.cpp +++ b/timing/timeSFMBAL.cpp @@ -36,7 +36,7 @@ int main(int argc, char* argv[]) { // Build graph using conventional GeneralSFMFactor NonlinearFactorGraph graph; - for (size_t j = 0; j < db.number_tracks(); j++) { + for (size_t j = 0; j < db.nrTracks(); j++) { for (const SfmMeasurement& m: db.tracks[j].measurements) { size_t i = m.first; Point2 z = m.second; diff --git a/timing/timeSFMBAL.h b/timing/timeSFMBAL.h index 548c4de70..3108624ce 100644 --- a/timing/timeSFMBAL.h +++ b/timing/timeSFMBAL.h @@ -73,8 +73,8 @@ int optimize(const SfmData& db, const NonlinearFactorGraph& graph, if (gUseSchur) { // Create Schur-complement ordering Ordering ordering; - for (size_t j = 0; j < db.number_tracks(); j++) ordering.push_back(P(j)); - for (size_t i = 0; i < db.number_cameras(); i++) { + for (size_t j = 0; j < db.nrTracks(); j++) ordering.push_back(P(j)); + for (size_t i = 0; i < db.nrCameras(); i++) { ordering.push_back(C(i)); if (separateCalibration) ordering.push_back(K(i)); } diff --git a/timing/timeSFMBALautodiff.cpp b/timing/timeSFMBALautodiff.cpp index 2d0f4a1fe..63e193145 100644 --- a/timing/timeSFMBALautodiff.cpp +++ b/timing/timeSFMBALautodiff.cpp @@ -44,7 +44,7 @@ int main(int argc, char* argv[]) { // Build graph NonlinearFactorGraph graph; - for (size_t j = 0; j < db.number_tracks(); j++) { + for (size_t j = 0; j < db.nrTracks(); j++) { for (const SfmMeasurement& m: db.tracks[j].measurements) { size_t i = m.first; Point2 z = m.second; diff --git a/timing/timeSFMBALcamTnav.cpp b/timing/timeSFMBALcamTnav.cpp index 355defed9..cc2671040 100644 --- a/timing/timeSFMBALcamTnav.cpp +++ b/timing/timeSFMBALcamTnav.cpp @@ -33,7 +33,7 @@ int main(int argc, char* argv[]) { // Build graph using conventional GeneralSFMFactor NonlinearFactorGraph graph; - for (size_t j = 0; j < db.number_tracks(); j++) { + for (size_t j = 0; j < db.nrTracks(); j++) { for (const SfmMeasurement& m: db.tracks[j].measurements) { size_t i = m.first; Point2 z = m.second; diff --git a/timing/timeSFMBALnavTcam.cpp b/timing/timeSFMBALnavTcam.cpp index e602ef241..4c3bc0621 100644 --- a/timing/timeSFMBALnavTcam.cpp +++ b/timing/timeSFMBALnavTcam.cpp @@ -33,7 +33,7 @@ int main(int argc, char* argv[]) { // Build graph using conventional GeneralSFMFactor NonlinearFactorGraph graph; - for (size_t j = 0; j < db.number_tracks(); j++) { + for (size_t j = 0; j < db.nrTracks(); j++) { Point3_ nav_point_(P(j)); for (const SfmMeasurement& m: db.tracks[j].measurements) { size_t i = m.first; diff --git a/timing/timeSFMBALsmart.cpp b/timing/timeSFMBALsmart.cpp index a69d895a5..f37f35a39 100644 --- a/timing/timeSFMBALsmart.cpp +++ b/timing/timeSFMBALsmart.cpp @@ -35,7 +35,7 @@ int main(int argc, char* argv[]) { // Add smart factors to graph NonlinearFactorGraph graph; - for (size_t j = 0; j < db.number_tracks(); j++) { + for (size_t j = 0; j < db.nrTracks(); j++) { auto smartFactor = boost::make_shared(gNoiseModel); for (const SfmMeasurement& m : db.tracks[j].measurements) { size_t i = m.first;