python wrapped SfmData and SfmTrack
							parent
							
								
									ed387e3817
								
							
						
					
					
						commit
						1f09f4aab6
					
				|  | @ -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); | ||||
|     } | ||||
|   } | ||||
| 
 | ||||
|  |  | |||
|  | @ -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(); | ||||
|  |  | |||
|  | @ -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> //
 | ||||
|  |  | |||
|  | @ -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); | ||||
|  |  | |||
|  | @ -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)); | ||||
|   } | ||||
| 
 | ||||
|  |  | |||
		Loading…
	
		Reference in New Issue