Skip to content

Commit 2a2a18c

Browse files
author
Yann N.
committed
Better and unified GCP thresholds handling :
- Use a single threshold from triangulation to stats - Only use GCPs for linear alignment at the end since GPS and GCP have no garantee of consistency (bias) TOSORT
1 parent 59fd7cd commit 2a2a18c

8 files changed

Lines changed: 57 additions & 33 deletions

File tree

opensfm/align.py

Lines changed: 8 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -127,11 +127,13 @@ def alignment_constraints(
127127
X, Xp = [], []
128128
# Get Ground Control Point correspondences
129129
if gcp and config["bundle_use_gcp"]:
130-
triangulated, measured = triangulate_all_gcp(reconstruction, gcp)
130+
triangulated, measured = triangulate_all_gcp(
131+
reconstruction, gcp, config["gcp_reprojection_error_threshold"]
132+
)
131133
X.extend(triangulated)
132134
Xp.extend(measured)
133135
# Get camera center correspondences
134-
if use_gps and config["bundle_use_gps"]:
136+
elif use_gps and config["bundle_use_gps"]:
135137
for rig_instance in reconstruction.rig_instances.values():
136138
gpses = [
137139
shot.metadata.gps_position.value
@@ -437,14 +439,17 @@ def get_horizontal_and_vertical_directions(
437439

438440

439441
def triangulate_all_gcp(
440-
reconstruction: types.Reconstruction, gcp: List[pymap.GroundControlPoint]
442+
reconstruction: types.Reconstruction,
443+
gcp: List[pymap.GroundControlPoint],
444+
threshold: float,
441445
) -> Tuple[List[NDArray], List[NDArray]]:
442446
"""Group and triangulate Ground Control Points seen in 2+ images."""
443447
triangulated, measured = [], []
444448
for point in gcp:
445449
x = multiview.triangulate_gcp(
446450
point,
447451
reconstruction.shots,
452+
threshold,
448453
)
449454
if x is not None and len(point.lla):
450455
point_enu = np.array(

opensfm/config.py

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -260,7 +260,7 @@ class OpenSfMConfig:
260260
# The default vertical standard deviation of the GCPs (in meters)
261261
gcp_vertical_sd: float = 0.1
262262
# Global weight for GCPs, expressed a ratio of the sum of (# projections) + (# shots) + (# relative motions)
263-
gcp_global_weight: float = 0.01
263+
gcp_global_weight: float = 0.02
264264
# The standard deviation of the rig translation
265265
rig_translation_sd: float = 0.1
266266
# The standard deviation of the rig rotation
@@ -303,7 +303,7 @@ class OpenSfMConfig:
303303
save_partial_reconstructions: bool = False
304304

305305
##################################
306-
# Params for GPS alignment
306+
# Params for GPS/GCP alignment
307307
##################################
308308
# Use or ignore EXIF altitude tag
309309
use_altitude_tag: bool = True
@@ -317,6 +317,8 @@ class OpenSfMConfig:
317317
bundle_use_gcp: bool = True
318318
# Compensate GPS with a per-camera similarity transform
319319
bundle_compensate_gps_bias: bool = False
320+
# Thrershold for the reprojection error of GCPs to be considered outliers
321+
gcp_reprojection_error_threshold: float = 0.05
320322

321323
##################################
322324
# Params for rigs

opensfm/multiview.py

Lines changed: 7 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -533,6 +533,7 @@ def triangulate_gcp(
533533
reproj_threshold: float = 0.02,
534534
min_ray_angle_degrees: float = 1.0,
535535
min_depth: float = 0.001,
536+
iterations: int = 10,
536537
) -> Optional[NDArray]:
537538
"""Compute the reconstructed position of a GCP from observations."""
538539

@@ -550,13 +551,17 @@ def triangulate_gcp(
550551

551552
if len(os) >= 2:
552553
thresholds = len(os) * [reproj_threshold]
554+
os = np.asarray(os)
555+
bs = np.asarray(bs)
553556
valid_triangulation, X = pygeometry.triangulate_bearings_midpoint(
554-
np.asarray(os),
555-
np.asarray(bs),
557+
os,
558+
bs,
556559
thresholds,
557560
np.radians(min_ray_angle_degrees),
558561
min_depth,
559562
)
563+
560564
if valid_triangulation:
565+
X = pygeometry.point_refinement(os, bs, X, iterations)
561566
return X
562567
return None

opensfm/reconstruction.py

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1512,7 +1512,7 @@ def grow_reconstruction(
15121512
rig_camera_priors = data.load_rig_cameras()
15131513

15141514
paint_reconstruction(data, tracks_manager, reconstruction)
1515-
align_reconstruction(reconstruction, gcp, config)
1515+
align_reconstruction(reconstruction, [], config)
15161516

15171517
bundle(reconstruction, camera_priors, rig_camera_priors, None, -1, config)
15181518
remove_outliers(reconstruction, config)
@@ -1598,7 +1598,7 @@ def grow_reconstruction(
15981598

15991599
if should_retriangulate.should():
16001600
logger.info("Re-triangulating")
1601-
align_reconstruction(reconstruction, gcp, config)
1601+
align_reconstruction(reconstruction, [], config)
16021602
b1rep = bundle(
16031603
reconstruction, camera_priors, rig_camera_priors, None, local_ba_grid, config
16041604
)
@@ -1614,7 +1614,7 @@ def grow_reconstruction(
16141614
should_retriangulate.done()
16151615
should_bundle.done()
16161616
elif should_bundle.should():
1617-
align_reconstruction(reconstruction, gcp, config)
1617+
align_reconstruction(reconstruction, [], config)
16181618
brep = bundle(
16191619
reconstruction, camera_priors, rig_camera_priors, None, local_ba_grid, config
16201620
)

opensfm/src/bundle/src/bundle_adjuster.cc

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -809,8 +809,7 @@ void BundleAdjuster::Run() {
809809
projection_type, use_analytic_, observation, projection_loss, &problem);
810810

811811
// Add relative depth error blocks
812-
geometry::Dispatch<AddRelativeDepthError>(projection_type, observation,
813-
projection_loss, &problem);
812+
geometry::Dispatch<AddRelativeDepthError>(projection_type, observation, projection_loss, &problem);
814813
}
815814

816815
// Add relative motion errors

opensfm/src/sfm/ba_helpers.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -72,6 +72,7 @@ class BAHelpers {
7272
static bool TriangulateGCP(
7373
const map::GroundControlPoint& point,
7474
const std::unordered_map<map::ShotId, map::Shot>& shots,
75+
float reproj_threshold,
7576
Vec3d& coordinates);
7677

7778
static void AlignmentConstraints(

opensfm/src/sfm/src/ba_helpers.cc

Lines changed: 27 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -351,8 +351,8 @@ py::tuple BAHelpers::BundleLocal(
351351
bool BAHelpers::TriangulateGCP(
352352
const map::GroundControlPoint& point,
353353
const std::unordered_map<map::ShotId, map::Shot>& shots,
354+
float reproj_threshold,
354355
Vec3d& coordinates) {
355-
constexpr auto reproj_threshold{1.0};
356356
constexpr auto min_ray_angle = 0.1 * M_PI / 180.0;
357357
constexpr auto min_depth = 1e-3; // Assume GCPs 1mm+ away from the camera
358358
MatX3d os, bs;
@@ -394,48 +394,56 @@ size_t BAHelpers::AddGCPToBundle(
394394
ba.GetProjectionsCount() +
395395
ba.GetRelativeMotionsCount();
396396

397-
size_t total_terms = 0;
398-
for (const auto& point : gcp) {
399-
Vec3d coordinates;
400-
if (TriangulateGCP(point, shots, coordinates) || !point.lla_.empty()) {
401-
++total_terms;
402-
}
403-
for (const auto& obs : point.observations_) {
404-
total_terms += (shots.count(obs.shot_id_) > 0);
405-
}
406-
}
407-
408-
double global_weight = config["gcp_global_weight"].cast<double>() *
409-
dominant_terms / std::max<size_t>(1, total_terms);
397+
const float reproj_threshold =
398+
config["gcp_reprojection_error_threshold"].cast<float>();
410399

411400
size_t added_gcp_observations = 0;
412401
for (const auto& point : gcp) {
413402
const auto point_id = "gcp-" + point.id_;
414403
Vec3d coordinates;
415-
if (!TriangulateGCP(point, shots, coordinates)) {
404+
if (!TriangulateGCP(point, shots, reproj_threshold, coordinates)) {
416405
if (!point.lla_.empty()) {
417406
coordinates = reference.ToTopocentric(point.GetLlaVec3d());
418407
} else {
419408
continue;
420409
}
421410
}
411+
412+
double avg_observations = 0.;
413+
int valid_shots = 0;
414+
for (const auto& obs : point.observations_) {
415+
const auto shot_it = shots.find(obs.shot_id_);
416+
if (shot_it != shots.end()) {
417+
const auto& shot = (shot_it->second);
418+
avg_observations += shot.GetLandmarkObservations().size();
419+
++valid_shots;
420+
}
421+
}
422+
423+
if(!valid_shots) {
424+
continue;
425+
}
426+
avg_observations /= valid_shots;
427+
428+
const double prior_weight = config["gcp_global_weight"].cast<double>() * avg_observations;
422429
constexpr auto point_constant{false};
423430
ba.AddPoint(point_id, coordinates, point_constant);
424431
if (!point.lla_.empty()) {
425432
const auto point_std = Vec3d(config["gcp_horizontal_sd"].cast<double>(),
426433
config["gcp_horizontal_sd"].cast<double>(),
427434
config["gcp_vertical_sd"].cast<double>());
428435
ba.AddPointPrior(point_id, reference.ToTopocentric(point.GetLlaVec3d()),
429-
point_std / global_weight, point.has_altitude_);
436+
point_std / prior_weight, point.has_altitude_);
430437
}
431438

432439
// Now iterate through the observations
440+
const double obs_weight = config["gcp_global_weight"].cast<double>() * avg_observations;
433441
for (const auto& obs : point.observations_) {
434442
const auto& shot_id = obs.shot_id_;
435443
if (shots.count(shot_id) > 0) {
436444
constexpr double scale{0.001};
437445
ba.AddPointProjectionObservation(shot_id, point_id, obs.projection_,
438-
scale / global_weight);
446+
scale / obs_weight);
439447
++added_gcp_observations;
440448
}
441449
}
@@ -829,7 +837,7 @@ py::dict BAHelpers::Bundle(
829837
AddGCPToBundle(ba, map, gcp, config);
830838
}
831839

832-
if (config["bundle_compensate_gps_bias"].cast<bool>()) {
840+
if (config["bundle_compensate_gps_bias"].cast<bool>() && !gcp.empty()) {
833841
const auto& biases = map.GetBiases();
834842
for (const auto& camera : map.GetCameras()) {
835843
ba.SetCameraBias(camera.first, biases.at(camera.first));
@@ -989,7 +997,7 @@ void BAHelpers::AlignmentConstraints(
989997
continue;
990998
}
991999
Vec3d coordinates;
992-
if (TriangulateGCP(point, shots, coordinates)) {
1000+
if (TriangulateGCP(point, shots, config["gcp_reprojection_error_threshold"].cast<float>(), coordinates)) {
9931001
Xp.row(idx) = topocentricConverter.ToTopocentric(point.GetLlaVec3d());
9941002
X.row(idx) = coordinates;
9951003
++idx;

opensfm/stats.py

Lines changed: 6 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -94,7 +94,9 @@ def gcp_errors(
9494

9595
triangulated = None
9696
for rec in reconstructions:
97-
triangulated = multiview.triangulate_gcp(gcp, rec.shots, 1.0, 0.1)
97+
triangulated = multiview.triangulate_gcp(
98+
gcp, rec.shots, data.config["gcp_reprojection_error_threshold"]
99+
)
98100
if triangulated is None:
99101
continue
100102
else:
@@ -583,7 +585,9 @@ def save_residual_histogram(
583585
n,
584586
_,
585587
p_angular,
586-
) = axs[2].hist(b_angular[:-1], b_angular, weights=h_angular)
588+
) = axs[
589+
2
590+
].hist(b_angular[:-1], b_angular, weights=h_angular)
587591
n = n.astype("int")
588592
for i in range(len(p_angular)):
589593
p_angular[i].set_facecolor(plt.cm.viridis(n[i] / max(n)))

0 commit comments

Comments
 (0)