Skip to content

Commit 9a7153c

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 8074f9f commit 9a7153c

File tree

8 files changed

+57
-33
lines changed

8 files changed

+57
-33
lines changed

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
@@ -297,7 +297,7 @@ class OpenSfMConfig:
297297
save_partial_reconstructions: bool = False
298298

299299
##################################
300-
# Params for GPS alignment
300+
# Params for GPS/GCP alignment
301301
##################################
302302
# Use or ignore EXIF altitude tag
303303
use_altitude_tag: bool = True
@@ -311,6 +311,8 @@ class OpenSfMConfig:
311311
bundle_use_gcp: bool = True
312312
# Compensate GPS with a per-camera similarity transform
313313
bundle_compensate_gps_bias: bool = False
314+
# Thrershold for the reprojection error of GCPs to be considered outliers
315+
gcp_reprojection_error_threshold: float = 0.05
314316

315317
##################################
316318
# 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
@@ -1424,7 +1424,7 @@ def grow_reconstruction(
14241424
rig_camera_priors = data.load_rig_cameras()
14251425

14261426
paint_reconstruction(data, tracks_manager, reconstruction)
1427-
align_reconstruction(reconstruction, gcp, config)
1427+
align_reconstruction(reconstruction, [], config)
14281428

14291429
bundle(reconstruction, camera_priors, rig_camera_priors, None, config)
14301430
remove_outliers(reconstruction, config)
@@ -1487,7 +1487,7 @@ def grow_reconstruction(
14871487

14881488
if should_retriangulate.should():
14891489
logger.info("Re-triangulating")
1490-
align_reconstruction(reconstruction, gcp, config)
1490+
align_reconstruction(reconstruction, [], config)
14911491
b1rep = bundle(
14921492
reconstruction, camera_priors, rig_camera_priors, None, config
14931493
)
@@ -1502,7 +1502,7 @@ def grow_reconstruction(
15021502
should_retriangulate.done()
15031503
should_bundle.done()
15041504
elif should_bundle.should():
1505-
align_reconstruction(reconstruction, gcp, config)
1505+
align_reconstruction(reconstruction, [], config)
15061506
brep = bundle(
15071507
reconstruction, camera_priors, rig_camera_priors, None, config
15081508
)

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
@@ -64,6 +64,7 @@ class BAHelpers {
6464
static bool TriangulateGCP(
6565
const map::GroundControlPoint& point,
6666
const std::unordered_map<map::ShotId, map::Shot>& shots,
67+
float reproj_threshold,
6768
Vec3d& coordinates);
6869

6970
static void AlignmentConstraints(

opensfm/src/sfm/src/ba_helpers.cc

Lines changed: 27 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -318,8 +318,8 @@ py::tuple BAHelpers::BundleLocal(
318318
bool BAHelpers::TriangulateGCP(
319319
const map::GroundControlPoint& point,
320320
const std::unordered_map<map::ShotId, map::Shot>& shots,
321+
float reproj_threshold,
321322
Vec3d& coordinates) {
322-
constexpr auto reproj_threshold{1.0};
323323
constexpr auto min_ray_angle = 0.1 * M_PI / 180.0;
324324
constexpr auto min_depth = 1e-3; // Assume GCPs 1mm+ away from the camera
325325
MatX3d os, bs;
@@ -361,48 +361,56 @@ size_t BAHelpers::AddGCPToBundle(
361361
ba.GetProjectionsCount() +
362362
ba.GetRelativeMotionsCount();
363363

364-
size_t total_terms = 0;
365-
for (const auto& point : gcp) {
366-
Vec3d coordinates;
367-
if (TriangulateGCP(point, shots, coordinates) || !point.lla_.empty()) {
368-
++total_terms;
369-
}
370-
for (const auto& obs : point.observations_) {
371-
total_terms += (shots.count(obs.shot_id_) > 0);
372-
}
373-
}
374-
375-
double global_weight = config["gcp_global_weight"].cast<double>() *
376-
dominant_terms / std::max<size_t>(1, total_terms);
364+
const float reproj_threshold =
365+
config["gcp_reprojection_error_threshold"].cast<float>();
377366

378367
size_t added_gcp_observations = 0;
379368
for (const auto& point : gcp) {
380369
const auto point_id = "gcp-" + point.id_;
381370
Vec3d coordinates;
382-
if (!TriangulateGCP(point, shots, coordinates)) {
371+
if (!TriangulateGCP(point, shots, reproj_threshold, coordinates)) {
383372
if (!point.lla_.empty()) {
384373
coordinates = reference.ToTopocentric(point.GetLlaVec3d());
385374
} else {
386375
continue;
387376
}
388377
}
378+
379+
double avg_observations = 0.;
380+
int valid_shots = 0;
381+
for (const auto& obs : point.observations_) {
382+
const auto shot_it = shots.find(obs.shot_id_);
383+
if (shot_it != shots.end()) {
384+
const auto& shot = (shot_it->second);
385+
avg_observations += shot.GetLandmarkObservations().size();
386+
++valid_shots;
387+
}
388+
}
389+
390+
if(!valid_shots) {
391+
continue;
392+
}
393+
avg_observations /= valid_shots;
394+
395+
const double prior_weight = config["gcp_global_weight"].cast<double>() * avg_observations;
389396
constexpr auto point_constant{false};
390397
ba.AddPoint(point_id, coordinates, point_constant);
391398
if (!point.lla_.empty()) {
392399
const auto point_std = Vec3d(config["gcp_horizontal_sd"].cast<double>(),
393400
config["gcp_horizontal_sd"].cast<double>(),
394401
config["gcp_vertical_sd"].cast<double>());
395402
ba.AddPointPrior(point_id, reference.ToTopocentric(point.GetLlaVec3d()),
396-
point_std / global_weight, point.has_altitude_);
403+
point_std / prior_weight, point.has_altitude_);
397404
}
398405

399406
// Now iterate through the observations
407+
const double obs_weight = config["gcp_global_weight"].cast<double>() * avg_observations;
400408
for (const auto& obs : point.observations_) {
401409
const auto& shot_id = obs.shot_id_;
402410
if (shots.count(shot_id) > 0) {
403411
constexpr double scale{0.001};
404412
ba.AddPointProjectionObservation(shot_id, point_id, obs.projection_,
405-
scale / global_weight);
413+
scale / obs_weight);
406414
++added_gcp_observations;
407415
}
408416
}
@@ -718,7 +726,7 @@ py::dict BAHelpers::Bundle(
718726
AddGCPToBundle(ba, map, gcp, config);
719727
}
720728

721-
if (config["bundle_compensate_gps_bias"].cast<bool>()) {
729+
if (config["bundle_compensate_gps_bias"].cast<bool>() && !gcp.empty()) {
722730
const auto& biases = map.GetBiases();
723731
for (const auto& camera : map.GetCameras()) {
724732
ba.SetCameraBias(camera.first, biases.at(camera.first));
@@ -861,7 +869,7 @@ void BAHelpers::AlignmentConstraints(
861869
continue;
862870
}
863871
Vec3d coordinates;
864-
if (TriangulateGCP(point, shots, coordinates)) {
872+
if (TriangulateGCP(point, shots, config["gcp_reprojection_error_threshold"].cast<float>(), coordinates)) {
865873
Xp.row(idx) = topocentricConverter.ToTopocentric(point.GetLlaVec3d());
866874
X.row(idx) = coordinates;
867875
++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)