Skip to content

Commit 8db2970

Browse files
committed
d
1 parent ccc7d29 commit 8db2970

File tree

2 files changed

+46
-48
lines changed

2 files changed

+46
-48
lines changed

glomap/controllers/global_mapper_test.cc

Lines changed: 17 additions & 18 deletions
Original file line numberDiff line numberDiff line change
@@ -53,7 +53,7 @@ GlobalMapperOptions CreateTestOptions() {
5353
TEST(GlobalMapper, WithoutNoise) {
5454
const std::string database_path = colmap::CreateTestDir() + "/database.db";
5555

56-
colmap::Database database(database_path);
56+
auto database = colmap::Database::Open(database_path);
5757
colmap::Reconstruction gt_reconstruction;
5858
colmap::SyntheticDatasetOptions synthetic_dataset_options;
5959
synthetic_dataset_options.num_rigs = 2;
@@ -62,7 +62,7 @@ TEST(GlobalMapper, WithoutNoise) {
6262
synthetic_dataset_options.num_points3D = 50;
6363
synthetic_dataset_options.point2D_stddev = 0;
6464
colmap::SynthesizeDataset(
65-
synthetic_dataset_options, &gt_reconstruction, &database);
65+
synthetic_dataset_options, &gt_reconstruction, database.get());
6666

6767
ViewGraph view_graph;
6868
std::unordered_map<rig_t, Rig> rigs;
@@ -71,11 +71,11 @@ TEST(GlobalMapper, WithoutNoise) {
7171
std::unordered_map<image_t, Image> images;
7272
std::unordered_map<track_t, Track> tracks;
7373

74-
ConvertDatabaseToGlomap(database, view_graph, rigs, cameras, frames, images);
74+
ConvertDatabaseToGlomap(*database, view_graph, rigs, cameras, frames, images);
7575

7676
GlobalMapper global_mapper(CreateTestOptions());
7777
global_mapper.Solve(
78-
database, view_graph, rigs, cameras, frames, images, tracks);
78+
*database, view_graph, rigs, cameras, frames, images, tracks);
7979

8080
colmap::Reconstruction reconstruction;
8181
ConvertGlomapToColmap(rigs, cameras, frames, images, tracks, reconstruction);
@@ -90,7 +90,7 @@ TEST(GlobalMapper, WithoutNoise) {
9090
TEST(GlobalMapper, WithoutNoiseWithNonTrivialKnownRig) {
9191
const std::string database_path = colmap::CreateTestDir() + "/database.db";
9292

93-
colmap::Database database(database_path);
93+
auto database = colmap::Database::Open(database_path);
9494
colmap::Reconstruction gt_reconstruction;
9595
colmap::SyntheticDatasetOptions synthetic_dataset_options;
9696
synthetic_dataset_options.num_rigs = 2;
@@ -102,7 +102,7 @@ TEST(GlobalMapper, WithoutNoiseWithNonTrivialKnownRig) {
102102
0.1; // No noise
103103
synthetic_dataset_options.sensor_from_rig_rotation_stddev = 5.; // No noise
104104
colmap::SynthesizeDataset(
105-
synthetic_dataset_options, &gt_reconstruction, &database);
105+
synthetic_dataset_options, &gt_reconstruction, database.get());
106106

107107
ViewGraph view_graph;
108108
std::unordered_map<rig_t, Rig> rigs;
@@ -111,11 +111,11 @@ TEST(GlobalMapper, WithoutNoiseWithNonTrivialKnownRig) {
111111
std::unordered_map<image_t, Image> images;
112112
std::unordered_map<track_t, Track> tracks;
113113

114-
ConvertDatabaseToGlomap(database, view_graph, rigs, cameras, frames, images);
114+
ConvertDatabaseToGlomap(*database, view_graph, rigs, cameras, frames, images);
115115

116116
GlobalMapper global_mapper(CreateTestOptions());
117117
global_mapper.Solve(
118-
database, view_graph, rigs, cameras, frames, images, tracks);
118+
*database, view_graph, rigs, cameras, frames, images, tracks);
119119

120120
colmap::Reconstruction reconstruction;
121121
ConvertGlomapToColmap(rigs, cameras, frames, images, tracks, reconstruction);
@@ -130,7 +130,7 @@ TEST(GlobalMapper, WithoutNoiseWithNonTrivialKnownRig) {
130130
TEST(GlobalMapper, WithoutNoiseWithNonTrivialUnknownRig) {
131131
const std::string database_path = colmap::CreateTestDir() + "/database.db";
132132

133-
colmap::Database database(database_path);
133+
auto database = colmap::Database::Open(database_path);
134134
colmap::Reconstruction gt_reconstruction;
135135
colmap::SyntheticDatasetOptions synthetic_dataset_options;
136136
synthetic_dataset_options.num_rigs = 2;
@@ -143,7 +143,7 @@ TEST(GlobalMapper, WithoutNoiseWithNonTrivialUnknownRig) {
143143
synthetic_dataset_options.sensor_from_rig_rotation_stddev = 5.; // No noise
144144

145145
colmap::SynthesizeDataset(
146-
synthetic_dataset_options, &gt_reconstruction, &database);
146+
synthetic_dataset_options, &gt_reconstruction, database.get());
147147

148148
ViewGraph view_graph;
149149
std::unordered_map<rig_t, Rig> rigs;
@@ -152,12 +152,11 @@ TEST(GlobalMapper, WithoutNoiseWithNonTrivialUnknownRig) {
152152
std::unordered_map<image_t, Image> images;
153153
std::unordered_map<track_t, Track> tracks;
154154

155-
ConvertDatabaseToGlomap(database, view_graph, rigs, cameras, frames, images);
155+
ConvertDatabaseToGlomap(*database, view_graph, rigs, cameras, frames, images);
156156

157157
// Set the rig sensors to be unknown
158158
for (auto& [rig_id, rig] : rigs) {
159-
for (auto& [sensor_id, sensor] : rig.Sensors()) {
160-
if (rig.IsRefSensor(sensor_id)) continue; // Skip reference sensor
159+
for (auto& [sensor_id, sensor] : rig.NonRefSensors()) {
161160
if (sensor.has_value()) {
162161
rig.ResetSensorFromRig(sensor_id);
163162
}
@@ -166,7 +165,7 @@ TEST(GlobalMapper, WithoutNoiseWithNonTrivialUnknownRig) {
166165

167166
GlobalMapper global_mapper(CreateTestOptions());
168167
global_mapper.Solve(
169-
database, view_graph, rigs, cameras, frames, images, tracks);
168+
*database, view_graph, rigs, cameras, frames, images, tracks);
170169

171170
colmap::Reconstruction reconstruction;
172171
ConvertGlomapToColmap(rigs, cameras, frames, images, tracks, reconstruction);
@@ -181,7 +180,7 @@ TEST(GlobalMapper, WithoutNoiseWithNonTrivialUnknownRig) {
181180
TEST(GlobalMapper, WithNoiseAndOutliers) {
182181
const std::string database_path = colmap::CreateTestDir() + "/database.db";
183182

184-
colmap::Database database(database_path);
183+
auto database = colmap::Database::Open(database_path);
185184
colmap::Reconstruction gt_reconstruction;
186185
colmap::SyntheticDatasetOptions synthetic_dataset_options;
187186
synthetic_dataset_options.num_rigs = 2;
@@ -191,7 +190,7 @@ TEST(GlobalMapper, WithNoiseAndOutliers) {
191190
synthetic_dataset_options.point2D_stddev = 0.5;
192191
synthetic_dataset_options.inlier_match_ratio = 0.6;
193192
colmap::SynthesizeDataset(
194-
synthetic_dataset_options, &gt_reconstruction, &database);
193+
synthetic_dataset_options, &gt_reconstruction, database.get());
195194

196195
ViewGraph view_graph;
197196
std::unordered_map<camera_t, Camera> cameras;
@@ -200,11 +199,11 @@ TEST(GlobalMapper, WithNoiseAndOutliers) {
200199
std::unordered_map<frame_t, Frame> frames;
201200
std::unordered_map<track_t, Track> tracks;
202201

203-
ConvertDatabaseToGlomap(database, view_graph, rigs, cameras, frames, images);
202+
ConvertDatabaseToGlomap(*database, view_graph, rigs, cameras, frames, images);
204203

205204
GlobalMapper global_mapper(CreateTestOptions());
206205
global_mapper.Solve(
207-
database, view_graph, rigs, cameras, frames, images, tracks);
206+
*database, view_graph, rigs, cameras, frames, images, tracks);
208207

209208
colmap::Reconstruction reconstruction;
210209
ConvertGlomapToColmap(rigs, cameras, frames, images, tracks, reconstruction);

glomap/controllers/rotation_averager_test.cc

Lines changed: 29 additions & 30 deletions
Original file line numberDiff line numberDiff line change
@@ -125,7 +125,7 @@ void ExpectEqualGravity(
125125
TEST(RotationEstimator, WithoutNoise) {
126126
const std::string database_path = colmap::CreateTestDir() + "/database.db";
127127

128-
colmap::Database database(database_path);
128+
auto database = colmap::Database::Open(database_path);
129129
colmap::Reconstruction gt_reconstruction;
130130
colmap::SyntheticDatasetOptions synthetic_dataset_options;
131131
synthetic_dataset_options.num_rigs = 1;
@@ -135,7 +135,7 @@ TEST(RotationEstimator, WithoutNoise) {
135135
synthetic_dataset_options.point2D_stddev = 0;
136136
synthetic_dataset_options.sensor_from_rig_rotation_stddev = 20.;
137137
colmap::SynthesizeDataset(
138-
synthetic_dataset_options, &gt_reconstruction, &database);
138+
synthetic_dataset_options, &gt_reconstruction, database.get());
139139

140140
ViewGraph view_graph;
141141
std::unordered_map<rig_t, Rig> rigs;
@@ -144,13 +144,13 @@ TEST(RotationEstimator, WithoutNoise) {
144144
std::unordered_map<image_t, Image> images;
145145
std::unordered_map<track_t, Track> tracks;
146146

147-
ConvertDatabaseToGlomap(database, view_graph, rigs, cameras, frames, images);
147+
ConvertDatabaseToGlomap(*database, view_graph, rigs, cameras, frames, images);
148148

149149
PrepareGravity(gt_reconstruction, frames);
150150

151151
GlobalMapper global_mapper(CreateMapperTestOptions());
152152
global_mapper.Solve(
153-
database, view_graph, rigs, cameras, frames, images, tracks);
153+
*database, view_graph, rigs, cameras, frames, images, tracks);
154154

155155
// Version with Gravity
156156
for (bool use_gravity : {true}) {
@@ -168,7 +168,7 @@ TEST(RotationEstimator, WithoutNoise) {
168168
TEST(RotationEstimator, WithoutNoiseWithNoneTrivialKnownRig) {
169169
const std::string database_path = colmap::CreateTestDir() + "/database.db";
170170

171-
colmap::Database database(database_path);
171+
auto database = colmap::Database::Open(database_path);
172172
colmap::Reconstruction gt_reconstruction;
173173
colmap::SyntheticDatasetOptions synthetic_dataset_options;
174174
synthetic_dataset_options.num_rigs = 1;
@@ -178,7 +178,7 @@ TEST(RotationEstimator, WithoutNoiseWithNoneTrivialKnownRig) {
178178
synthetic_dataset_options.point2D_stddev = 0;
179179
synthetic_dataset_options.sensor_from_rig_rotation_stddev = 20.;
180180
colmap::SynthesizeDataset(
181-
synthetic_dataset_options, &gt_reconstruction, &database);
181+
synthetic_dataset_options, &gt_reconstruction, database.get());
182182

183183
ViewGraph view_graph;
184184
std::unordered_map<rig_t, Rig> rigs;
@@ -187,13 +187,13 @@ TEST(RotationEstimator, WithoutNoiseWithNoneTrivialKnownRig) {
187187
std::unordered_map<image_t, Image> images;
188188
std::unordered_map<track_t, Track> tracks;
189189

190-
ConvertDatabaseToGlomap(database, view_graph, rigs, cameras, frames, images);
190+
ConvertDatabaseToGlomap(*database, view_graph, rigs, cameras, frames, images);
191191

192192
PrepareGravity(gt_reconstruction, frames);
193193

194194
GlobalMapper global_mapper(CreateMapperTestOptions());
195195
global_mapper.Solve(
196-
database, view_graph, rigs, cameras, frames, images, tracks);
196+
*database, view_graph, rigs, cameras, frames, images, tracks);
197197

198198
// Version with Gravity
199199
for (bool use_gravity : {true, false}) {
@@ -211,7 +211,7 @@ TEST(RotationEstimator, WithoutNoiseWithNoneTrivialKnownRig) {
211211
TEST(RotationEstimator, WithoutNoiseWithNoneTrivialUnknownRig) {
212212
const std::string database_path = colmap::CreateTestDir() + "/database.db";
213213

214-
colmap::Database database(database_path);
214+
auto database = colmap::Database::Open(database_path);
215215
colmap::Reconstruction gt_reconstruction;
216216
colmap::SyntheticDatasetOptions synthetic_dataset_options;
217217
synthetic_dataset_options.num_rigs = 1;
@@ -221,7 +221,7 @@ TEST(RotationEstimator, WithoutNoiseWithNoneTrivialUnknownRig) {
221221
synthetic_dataset_options.point2D_stddev = 0;
222222
synthetic_dataset_options.sensor_from_rig_rotation_stddev = 20.;
223223
colmap::SynthesizeDataset(
224-
synthetic_dataset_options, &gt_reconstruction, &database);
224+
synthetic_dataset_options, &gt_reconstruction, database.get());
225225

226226
ViewGraph view_graph;
227227
std::unordered_map<rig_t, Rig> rigs;
@@ -230,11 +230,10 @@ TEST(RotationEstimator, WithoutNoiseWithNoneTrivialUnknownRig) {
230230
std::unordered_map<image_t, Image> images;
231231
std::unordered_map<track_t, Track> tracks;
232232

233-
ConvertDatabaseToGlomap(database, view_graph, rigs, cameras, frames, images);
233+
ConvertDatabaseToGlomap(*database, view_graph, rigs, cameras, frames, images);
234234

235235
for (auto& [rig_id, rig] : rigs) {
236-
for (auto& [sensor_id, sensor] : rig.Sensors()) {
237-
if (rig.IsRefSensor(sensor_id)) continue; // Skip reference sensor
236+
for (auto& [sensor_id, sensor] : rig.NonRefSensors()) {
238237
if (sensor.has_value()) {
239238
rig.ResetSensorFromRig(sensor_id);
240239
}
@@ -244,7 +243,7 @@ TEST(RotationEstimator, WithoutNoiseWithNoneTrivialUnknownRig) {
244243

245244
GlobalMapper global_mapper(CreateMapperTestOptions());
246245
global_mapper.Solve(
247-
database, view_graph, rigs, cameras, frames, images, tracks);
246+
*database, view_graph, rigs, cameras, frames, images, tracks);
248247

249248
// For unknown rigs, it is not supported to use gravity
250249
for (bool use_gravity : {false}) {
@@ -262,7 +261,7 @@ TEST(RotationEstimator, WithoutNoiseWithNoneTrivialUnknownRig) {
262261
TEST(RotationEstimator, WithNoiseAndOutliers) {
263262
const std::string database_path = colmap::CreateTestDir() + "/database.db";
264263

265-
colmap::Database database(database_path);
264+
auto database = colmap::Database::Open(database_path);
266265
colmap::Reconstruction gt_reconstruction;
267266
colmap::SyntheticDatasetOptions synthetic_dataset_options;
268267
synthetic_dataset_options.num_rigs = 2;
@@ -272,7 +271,7 @@ TEST(RotationEstimator, WithNoiseAndOutliers) {
272271
synthetic_dataset_options.point2D_stddev = 1;
273272
synthetic_dataset_options.inlier_match_ratio = 0.6;
274273
colmap::SynthesizeDataset(
275-
synthetic_dataset_options, &gt_reconstruction, &database);
274+
synthetic_dataset_options, &gt_reconstruction, database.get());
276275

277276
ViewGraph view_graph;
278277
std::unordered_map<rig_t, Rig> rigs;
@@ -281,13 +280,13 @@ TEST(RotationEstimator, WithNoiseAndOutliers) {
281280
std::unordered_map<frame_t, Frame> frames;
282281
std::unordered_map<track_t, Track> tracks;
283282

284-
ConvertDatabaseToGlomap(database, view_graph, rigs, cameras, frames, images);
283+
ConvertDatabaseToGlomap(*database, view_graph, rigs, cameras, frames, images);
285284

286285
PrepareGravity(gt_reconstruction, frames, /*stddev_gravity=*/3e-1);
287286

288287
GlobalMapper global_mapper(CreateMapperTestOptions());
289288
global_mapper.Solve(
290-
database, view_graph, rigs, cameras, frames, images, tracks);
289+
*database, view_graph, rigs, cameras, frames, images, tracks);
291290

292291
for (bool use_gravity : {true, false}) {
293292
SolveRotationAveraging(
@@ -308,7 +307,7 @@ TEST(RotationEstimator, WithNoiseAndOutliers) {
308307
TEST(RotationEstimator, WithNoiseAndOutliersWithNonTrivialKnownRigs) {
309308
const std::string database_path = colmap::CreateTestDir() + "/database.db";
310309

311-
colmap::Database database(database_path);
310+
auto database = colmap::Database::Open(database_path);
312311
colmap::Reconstruction gt_reconstruction;
313312
colmap::SyntheticDatasetOptions synthetic_dataset_options;
314313
synthetic_dataset_options.num_rigs = 2;
@@ -318,7 +317,7 @@ TEST(RotationEstimator, WithNoiseAndOutliersWithNonTrivialKnownRigs) {
318317
synthetic_dataset_options.point2D_stddev = 1;
319318
synthetic_dataset_options.inlier_match_ratio = 0.6;
320319
colmap::SynthesizeDataset(
321-
synthetic_dataset_options, &gt_reconstruction, &database);
320+
synthetic_dataset_options, &gt_reconstruction, database.get());
322321

323322
ViewGraph view_graph;
324323
std::unordered_map<rig_t, Rig> rigs;
@@ -327,12 +326,12 @@ TEST(RotationEstimator, WithNoiseAndOutliersWithNonTrivialKnownRigs) {
327326
std::unordered_map<frame_t, Frame> frames;
328327
std::unordered_map<track_t, Track> tracks;
329328

330-
ConvertDatabaseToGlomap(database, view_graph, rigs, cameras, frames, images);
329+
ConvertDatabaseToGlomap(*database, view_graph, rigs, cameras, frames, images);
331330
PrepareGravity(gt_reconstruction, frames, /*stddev_gravity=*/3e-1);
332331

333332
GlobalMapper global_mapper(CreateMapperTestOptions());
334333
global_mapper.Solve(
335-
database, view_graph, rigs, cameras, frames, images, tracks);
334+
*database, view_graph, rigs, cameras, frames, images, tracks);
336335

337336
for (bool use_gravity : {true, false}) {
338337
SolveRotationAveraging(
@@ -353,7 +352,7 @@ TEST(RotationEstimator, WithNoiseAndOutliersWithNonTrivialKnownRigs) {
353352
TEST(RotationEstimator, RefineGravity) {
354353
const std::string database_path = colmap::CreateTestDir() + "/database.db";
355354

356-
colmap::Database database(database_path);
355+
auto database = colmap::Database::Open(database_path);
357356
colmap::Reconstruction gt_reconstruction;
358357
colmap::SyntheticDatasetOptions synthetic_dataset_options;
359358
synthetic_dataset_options.num_rigs = 2;
@@ -362,7 +361,7 @@ TEST(RotationEstimator, RefineGravity) {
362361
synthetic_dataset_options.num_points3D = 100;
363362
synthetic_dataset_options.point2D_stddev = 0;
364363
colmap::SynthesizeDataset(
365-
synthetic_dataset_options, &gt_reconstruction, &database);
364+
synthetic_dataset_options, &gt_reconstruction, database.get());
366365

367366
ViewGraph view_graph;
368367
std::unordered_map<rig_t, Rig> rigs;
@@ -371,7 +370,7 @@ TEST(RotationEstimator, RefineGravity) {
371370
std::unordered_map<image_t, Image> images;
372371
std::unordered_map<track_t, Track> tracks;
373372

374-
ConvertDatabaseToGlomap(database, view_graph, rigs, cameras, frames, images);
373+
ConvertDatabaseToGlomap(*database, view_graph, rigs, cameras, frames, images);
375374

376375
PrepareGravity(gt_reconstruction,
377376
frames,
@@ -380,7 +379,7 @@ TEST(RotationEstimator, RefineGravity) {
380379

381380
GlobalMapper global_mapper(CreateMapperTestOptions());
382381
global_mapper.Solve(
383-
database, view_graph, rigs, cameras, frames, images, tracks);
382+
*database, view_graph, rigs, cameras, frames, images, tracks);
384383

385384
GravityRefinerOptions opt_grav_refine;
386385
GravityRefiner grav_refiner(opt_grav_refine);
@@ -395,7 +394,7 @@ TEST(RotationEstimator, RefineGravity) {
395394
TEST(RotationEstimator, RefineGravityWithNontrivialRigs) {
396395
const std::string database_path = colmap::CreateTestDir() + "/database.db";
397396

398-
colmap::Database database(database_path);
397+
auto database = colmap::Database::Open(database_path);
399398
colmap::Reconstruction gt_reconstruction;
400399
colmap::SyntheticDatasetOptions synthetic_dataset_options;
401400
synthetic_dataset_options.num_rigs = 2;
@@ -404,7 +403,7 @@ TEST(RotationEstimator, RefineGravityWithNontrivialRigs) {
404403
synthetic_dataset_options.num_points3D = 100;
405404
synthetic_dataset_options.point2D_stddev = 0;
406405
colmap::SynthesizeDataset(
407-
synthetic_dataset_options, &gt_reconstruction, &database);
406+
synthetic_dataset_options, &gt_reconstruction, database.get());
408407

409408
ViewGraph view_graph;
410409
std::unordered_map<rig_t, Rig> rigs;
@@ -413,7 +412,7 @@ TEST(RotationEstimator, RefineGravityWithNontrivialRigs) {
413412
std::unordered_map<image_t, Image> images;
414413
std::unordered_map<track_t, Track> tracks;
415414

416-
ConvertDatabaseToGlomap(database, view_graph, rigs, cameras, frames, images);
415+
ConvertDatabaseToGlomap(*database, view_graph, rigs, cameras, frames, images);
417416

418417
PrepareGravity(gt_reconstruction,
419418
frames,
@@ -422,7 +421,7 @@ TEST(RotationEstimator, RefineGravityWithNontrivialRigs) {
422421

423422
GlobalMapper global_mapper(CreateMapperTestOptions());
424423
global_mapper.Solve(
425-
database, view_graph, rigs, cameras, frames, images, tracks);
424+
*database, view_graph, rigs, cameras, frames, images, tracks);
426425

427426
GravityRefinerOptions opt_grav_refine;
428427
GravityRefiner grav_refiner(opt_grav_refine);

0 commit comments

Comments
 (0)