kopia lustrzana https://github.com/OpenDroneMap/ODM
rodzic
99bbff7ce5
commit
d5b68fc6bc
166
opendm/osfm.py
166
opendm/osfm.py
|
@ -2,7 +2,7 @@
|
|||
OpenSfM related utils
|
||||
"""
|
||||
|
||||
import os
|
||||
import os, shutil, sys
|
||||
from opendm import io
|
||||
from opendm import log
|
||||
from opendm import system
|
||||
|
@ -47,78 +47,136 @@ def reconstruct(opensfm_project_path, rerun=False):
|
|||
raise Exception("Reconstruction could not be generated")
|
||||
|
||||
|
||||
def setup(args, images_path, opensfm_path, photos, gcp_path=None, append_config = []):
|
||||
def setup(args, images_path, opensfm_path, photos, gcp_path=None, append_config = [], rerun=False):
|
||||
"""
|
||||
Setup a OpenSfM project
|
||||
"""
|
||||
if rerun and io.dir_exists(opensfm_path):
|
||||
shutil.rmtree(opensfm_path)
|
||||
|
||||
if not io.dir_exists(opensfm_path):
|
||||
system.mkdir_p(opensfm_path)
|
||||
|
||||
# create file list
|
||||
list_path = io.join_paths(opensfm_path, 'image_list.txt')
|
||||
has_alt = True
|
||||
with open(list_path, 'w') as fout:
|
||||
for photo in photos:
|
||||
if not photo.altitude:
|
||||
has_alt = False
|
||||
fout.write('%s\n' % io.join_paths(images_path, photo.filename))
|
||||
if not io.file_exists(list_path) or rerun:
|
||||
has_alt = True
|
||||
with open(list_path, 'w') as fout:
|
||||
for photo in photos:
|
||||
if not photo.altitude:
|
||||
has_alt = False
|
||||
fout.write('%s\n' % io.join_paths(images_path, photo.filename))
|
||||
|
||||
# TODO: does this need to be a relative path?
|
||||
# TODO: does this need to be a relative path?
|
||||
|
||||
# create config file for OpenSfM
|
||||
config = [
|
||||
"use_exif_size: no",
|
||||
"feature_process_size: %s" % args.resize_to,
|
||||
"feature_min_frames: %s" % args.min_num_features,
|
||||
"processes: %s" % args.max_concurrency,
|
||||
"matching_gps_neighbors: %s" % args.matcher_neighbors,
|
||||
"depthmap_method: %s" % args.opensfm_depthmap_method,
|
||||
"depthmap_resolution: %s" % args.depthmap_resolution,
|
||||
"depthmap_min_patch_sd: %s" % args.opensfm_depthmap_min_patch_sd,
|
||||
"depthmap_min_consistent_views: %s" % args.opensfm_depthmap_min_consistent_views,
|
||||
"optimize_camera_parameters: %s" % ('no' if args.use_fixed_camera_params else 'yes')
|
||||
]
|
||||
# create config file for OpenSfM
|
||||
config = [
|
||||
"use_exif_size: no",
|
||||
"feature_process_size: %s" % args.resize_to,
|
||||
"feature_min_frames: %s" % args.min_num_features,
|
||||
"processes: %s" % args.max_concurrency,
|
||||
"matching_gps_neighbors: %s" % args.matcher_neighbors,
|
||||
"depthmap_method: %s" % args.opensfm_depthmap_method,
|
||||
"depthmap_resolution: %s" % args.depthmap_resolution,
|
||||
"depthmap_min_patch_sd: %s" % args.opensfm_depthmap_min_patch_sd,
|
||||
"depthmap_min_consistent_views: %s" % args.opensfm_depthmap_min_consistent_views,
|
||||
"optimize_camera_parameters: %s" % ('no' if args.use_fixed_camera_params else 'yes')
|
||||
]
|
||||
|
||||
if has_alt:
|
||||
log.ODM_DEBUG("Altitude data detected, enabling it for GPS alignment")
|
||||
config.append("use_altitude_tag: yes")
|
||||
config.append("align_method: naive")
|
||||
if has_alt:
|
||||
log.ODM_DEBUG("Altitude data detected, enabling it for GPS alignment")
|
||||
config.append("use_altitude_tag: yes")
|
||||
config.append("align_method: naive")
|
||||
else:
|
||||
config.append("align_method: orientation_prior")
|
||||
config.append("align_orientation_prior: vertical")
|
||||
|
||||
if args.use_hybrid_bundle_adjustment:
|
||||
log.ODM_DEBUG("Enabling hybrid bundle adjustment")
|
||||
config.append("bundle_interval: 100") # Bundle after adding 'bundle_interval' cameras
|
||||
config.append("bundle_new_points_ratio: 1.2") # Bundle when (new points) / (bundled points) > bundle_new_points_ratio
|
||||
config.append("local_bundle_radius: 1") # Max image graph distance for images to be included in local bundle adjustment
|
||||
|
||||
if args.matcher_distance > 0:
|
||||
config.append("matching_gps_distance: %s" % args.matcher_distance)
|
||||
|
||||
if gcp_path:
|
||||
config.append("bundle_use_gcp: yes")
|
||||
io.copy(gcp_path, opensfm_path)
|
||||
|
||||
config = config + append_config
|
||||
|
||||
# write config file
|
||||
log.ODM_DEBUG(config)
|
||||
config_filename = io.join_paths(opensfm_path, 'config.yaml')
|
||||
with open(config_filename, 'w') as fout:
|
||||
fout.write("\n".join(config))
|
||||
else:
|
||||
config.append("align_method: orientation_prior")
|
||||
config.append("align_orientation_prior: vertical")
|
||||
|
||||
if args.use_hybrid_bundle_adjustment:
|
||||
log.ODM_DEBUG("Enabling hybrid bundle adjustment")
|
||||
config.append("bundle_interval: 100") # Bundle after adding 'bundle_interval' cameras
|
||||
config.append("bundle_new_points_ratio: 1.2") # Bundle when (new points) / (bundled points) > bundle_new_points_ratio
|
||||
config.append("local_bundle_radius: 1") # Max image graph distance for images to be included in local bundle adjustment
|
||||
|
||||
if args.matcher_distance > 0:
|
||||
config.append("matching_gps_distance: %s" % args.matcher_distance)
|
||||
|
||||
if gcp_path:
|
||||
config.append("bundle_use_gcp: yes")
|
||||
io.copy(gcp_path, opensfm_path)
|
||||
|
||||
config = config + append_config
|
||||
|
||||
# write config file
|
||||
log.ODM_DEBUG(config)
|
||||
config_filename = io.join_paths(opensfm_path, 'config.yaml')
|
||||
with open(config_filename, 'w') as fout:
|
||||
fout.write("\n".join(config))
|
||||
log.ODM_WARNING("%s already exists, not rerunning OpenSfM setup" % list_path)
|
||||
|
||||
def feature_matching(opensfm_project_path, rerun=False):
|
||||
matched_done_file = io.join_paths(opensfm_project_path, 'matching_done.txt')
|
||||
if not io.file_exists(matched_done_file) or rerun:
|
||||
if not feature_matching_done(opensfm_project_path) or rerun:
|
||||
run('extract_metadata', opensfm_project_path)
|
||||
|
||||
# TODO: distributed workflow should do these two steps independently
|
||||
run('detect_features', opensfm_project_path)
|
||||
run('match_features', opensfm_project_path)
|
||||
|
||||
with open(matched_done_file, 'w') as fout:
|
||||
fout.write("Matching done!\n")
|
||||
mark_feature_matching_done(opensfm_project_path)
|
||||
else:
|
||||
log.ODM_WARNING('Found a feature matching done progress file in: %s' %
|
||||
matched_done_file)
|
||||
feature_matching_done_file(opensfm_project_path))
|
||||
|
||||
def feature_matching_done_file(opensfm_project_path):
|
||||
return io.join_paths(opensfm_project_path, 'matching_done.txt')
|
||||
|
||||
def mark_feature_matching_done(opensfm_project_path):
|
||||
with open(feature_matching_done_file(opensfm_project_path), 'w') as fout:
|
||||
fout.write("Matching done!\n")
|
||||
|
||||
def feature_matching_done(opensfm_project_path):
|
||||
return io.file_exists(feature_matching_done_file(opensfm_project_path))
|
||||
|
||||
def get_submodel_argv(args, submodels_path, submodel_name):
|
||||
"""
|
||||
:return the same as argv, but removing references to --split,
|
||||
setting/replacing --project-path and name
|
||||
"""
|
||||
argv = sys.argv
|
||||
|
||||
result = [argv[0]]
|
||||
i = 1
|
||||
project_path_found = False
|
||||
project_name_added = False
|
||||
|
||||
while i < len(argv):
|
||||
arg = argv[i]
|
||||
|
||||
# Last?
|
||||
if i == len(argv) - 1:
|
||||
# Project name?
|
||||
if arg == args.name:
|
||||
result.append(submodel_name)
|
||||
project_name_added = True
|
||||
else:
|
||||
result.append(arg)
|
||||
i += 1
|
||||
elif arg == '--project-path':
|
||||
result.append(arg)
|
||||
result.append(submodels_path)
|
||||
project_path_found = True
|
||||
i += 2
|
||||
elif arg == '--split':
|
||||
i += 2
|
||||
else:
|
||||
result.append(arg)
|
||||
i += 1
|
||||
|
||||
if not project_path_found:
|
||||
result.append('--project-path')
|
||||
result.append(submodel_project_path)
|
||||
|
||||
if not project_name_added:
|
||||
result.append(submodel_name)
|
||||
|
||||
return result
|
||||
|
|
3
run.py
3
run.py
|
@ -36,7 +36,8 @@ if __name__ == '__main__':
|
|||
quote(os.path.join(args.project_path, "odm_25dmeshing")),
|
||||
quote(os.path.join(args.project_path, "odm_25dtexturing")),
|
||||
quote(os.path.join(args.project_path, "mve")),
|
||||
]) + "")
|
||||
quote(os.path.join(args.project_path, "submodels")),
|
||||
]))
|
||||
|
||||
app = ODMApp(args)
|
||||
app.execute()
|
||||
|
|
|
@ -30,14 +30,13 @@ class ODMOpenSfMStage(types.ODM_Stage):
|
|||
# check if reconstruction was done before
|
||||
# TODO: more granularity for each step (setup/featurematch/reconstruction/etc.)
|
||||
|
||||
osfm.setup(args, tree.dataset_raw, tree.opensfm, photos, gcp_path=tree.odm_georeferencing_gcp, rerun=self.rerun())
|
||||
|
||||
osfm.feature_matching(tree.opensfm, self.rerun())
|
||||
|
||||
osfm.reconstruct(tree.opensfm, self.rerun())
|
||||
|
||||
if not io.file_exists(output_file) or self.rerun():
|
||||
|
||||
osfm.setup(args, tree.dataset_raw, tree.opensfm, photos, gcp_path=tree.odm_georeferencing_gcp)
|
||||
|
||||
osfm.feature_matching(tree.opensfm, self.rerun())
|
||||
|
||||
osfm.reconstruction(tree.opensfm, self.rerun())
|
||||
|
||||
# Always export VisualSFM's reconstruction and undistort images
|
||||
# as we'll use these for texturing (after GSD estimation and resizing)
|
||||
if not args.ignore_gsd:
|
||||
|
|
|
@ -1,9 +1,11 @@
|
|||
import os
|
||||
import os, sys
|
||||
from opendm import log
|
||||
from opendm import osfm
|
||||
from opendm import types
|
||||
from opendm import io
|
||||
from opendm import system
|
||||
from opensfm.large import metadataset
|
||||
from pipes import quote
|
||||
|
||||
class ODMSplitStage(types.ODM_Stage):
|
||||
def process(self, args, outputs):
|
||||
|
@ -23,7 +25,7 @@ class ODMSplitStage(types.ODM_Stage):
|
|||
"submodel_overlap: %s" % args.split_overlap,
|
||||
]
|
||||
|
||||
osfm.setup(args, tree.dataset_raw, tree.opensfm, photos, gcp_path=tree.odm_georeferencing_gcp, append_config=config)
|
||||
osfm.setup(args, tree.dataset_raw, tree.opensfm, photos, gcp_path=tree.odm_georeferencing_gcp, append_config=config, rerun=self.rerun())
|
||||
|
||||
osfm.feature_matching(tree.opensfm, self.rerun())
|
||||
|
||||
|
@ -50,14 +52,28 @@ class ODMSplitStage(types.ODM_Stage):
|
|||
|
||||
for sp in submodel_paths:
|
||||
log.ODM_INFO("Reconstructing %s" % sp)
|
||||
osfm.reconstruct(sp, self.rerun())
|
||||
#osfm.reconstruct(sp, self.rerun())
|
||||
|
||||
# Align
|
||||
log.ODM_INFO("Aligning submodels...")
|
||||
osfm.run('align_submodels', tree.opensfm)
|
||||
#osfm.run('align_submodels', tree.opensfm)
|
||||
|
||||
# Dense reconstruction for each submodel
|
||||
# TODO
|
||||
for sp in submodel_paths:
|
||||
|
||||
# TODO: network workflow
|
||||
|
||||
# We have already done matching
|
||||
osfm.mark_feature_matching_done(sp)
|
||||
|
||||
submodel_name = os.path.basename(os.path.abspath(os.path.join(sp, "..")))
|
||||
|
||||
log.ODM_INFO("====================")
|
||||
log.ODM_INFO("Processing %s" % submodel_name)
|
||||
log.ODM_INFO("====================")
|
||||
|
||||
argv = osfm.get_submodel_argv(args, tree.submodels_path, submodel_name)
|
||||
system.run(" ".join(map(quote, argv)), env_vars=os.environ.copy())
|
||||
|
||||
exit(1)
|
||||
else:
|
||||
|
|
Ładowanie…
Reference in New Issue