kopia lustrzana https://github.com/OpenDroneMap/ODM
rodzic
47d5ed9b51
commit
bb27902f9d
|
@ -7,7 +7,7 @@ from appsettings import SettingsParser
|
|||
import sys
|
||||
|
||||
# parse arguments
|
||||
processopts = ['dataset', 'opensfm', 'slam', 'mve',
|
||||
processopts = ['dataset', 'opensfm', 'slam', 'mve', 'odm_filterpoints',
|
||||
'odm_meshing', 'odm_25dmeshing', 'mvs_texturing', 'odm_georeferencing',
|
||||
'odm_dem', 'odm_orthophoto']
|
||||
|
||||
|
|
|
@ -24,10 +24,8 @@ orb_slam2_path = os.path.join(superbuild_path, "src/orb_slam2")
|
|||
|
||||
# define mve join_paths
|
||||
makescene_path = os.path.join(superbuild_path, 'src', 'elibs', 'mve', 'apps', 'makescene', 'makescene') #TODO: don't install in source
|
||||
mve_path = os.path.join(superbuild_path, 'src', 'elibs', 'mve', 'apps', 'dmrecon', 'dmrecon')
|
||||
mve_path_pc = os.path.join(superbuild_path, 'src', 'elibs', 'mve', 'apps', 'scene2pset', 'scene2pset')
|
||||
|
||||
pdal_path_pc = os.path.join(superbuild_path, 'install/bin/pdal')
|
||||
dmrecon_path = os.path.join(superbuild_path, 'src', 'elibs', 'mve', 'apps', 'dmrecon', 'dmrecon')
|
||||
scene2pset_path = os.path.join(superbuild_path, 'src', 'elibs', 'mve', 'apps', 'scene2pset', 'scene2pset')
|
||||
|
||||
poisson_recon_path = os.path.join(superbuild_path, 'src', 'PoissonRecon', 'Bin', 'Linux', 'PoissonRecon')
|
||||
dem2mesh_path = os.path.join(superbuild_path, 'src', 'dem2mesh', 'dem2mesh')
|
||||
|
|
|
@ -1,11 +1,11 @@
|
|||
import os, sys
|
||||
import os, sys, shutil
|
||||
from opendm import system
|
||||
from opendm import log
|
||||
from opendm import context
|
||||
|
||||
def filter(pointCloudPath, standard_deviation=2.5, meank=16, verbose=False):
|
||||
def filter(inputPointCloud, outputPointCloud, standard_deviation=2.5, meank=16, verbose=False):
|
||||
"""
|
||||
Filters a point cloud in place (it will replace the input file with the filtered result).
|
||||
Filters a point cloud
|
||||
"""
|
||||
if standard_deviation <= 0 or meank <= 0:
|
||||
log.ODM_INFO("Skipping point cloud filtering")
|
||||
|
@ -13,29 +13,20 @@ def filter(pointCloudPath, standard_deviation=2.5, meank=16, verbose=False):
|
|||
|
||||
log.ODM_INFO("Filtering point cloud (statistical, meanK {}, standard deviation {})".format(meank, standard_deviation))
|
||||
|
||||
if not os.path.exists(pointCloudPath):
|
||||
log.ODM_ERROR("{} does not exist, cannot filter point cloud. The program will now exit.".format(pointCloudPath))
|
||||
if not os.path.exists(inputPointCloud):
|
||||
log.ODM_ERROR("{} does not exist, cannot filter point cloud. The program will now exit.".format(inputPointCloud))
|
||||
sys.exit(1)
|
||||
|
||||
filter_program = os.path.join(context.odm_modules_path, 'odm_filterpoints')
|
||||
if not os.path.exists(filter_program):
|
||||
log.ODM_WARNING("{} program not found. Will skip filtering, but this installation should be fixed.")
|
||||
shutil.copy(inputPointCloud, outputPointCloud)
|
||||
return
|
||||
|
||||
pc_path, pc_filename = os.path.split(pointCloudPath)
|
||||
# pc_path = path/to
|
||||
# pc_filename = pointcloud.ply
|
||||
|
||||
basename, ext = os.path.splitext(pc_filename)
|
||||
# basename = pointcloud
|
||||
# ext = .ply
|
||||
|
||||
tmpPointCloud = os.path.join(pc_path, "{}.tmp{}".format(basename, ext))
|
||||
|
||||
filterArgs = {
|
||||
'bin': filter_program,
|
||||
'inputFile': pointCloudPath,
|
||||
'outputFile': tmpPointCloud,
|
||||
'inputFile': inputPointCloud,
|
||||
'outputFile': outputPointCloud,
|
||||
'sd': standard_deviation,
|
||||
'meank': meank,
|
||||
'verbose': '--verbose' if verbose else '',
|
||||
|
@ -47,8 +38,5 @@ def filter(pointCloudPath, standard_deviation=2.5, meank=16, verbose=False):
|
|||
'-meank {meank} {verbose} '.format(**filterArgs))
|
||||
|
||||
# Remove input file, swap temp file
|
||||
if os.path.exists(tmpPointCloud):
|
||||
os.remove(pointCloudPath)
|
||||
os.rename(tmpPointCloud, pointCloudPath)
|
||||
else:
|
||||
log.ODM_WARNING("{} not found, filtering has failed.".format(tmpPointCloud))
|
||||
if not os.path.exists(outputPointCloud):
|
||||
log.ODM_WARNING("{} not found, filtering has failed.".format(outputPointCloud))
|
||||
|
|
|
@ -252,8 +252,8 @@ class ODM_Tree(object):
|
|||
self.odm_25dtexturing = io.join_paths(self.root_path, 'odm_texturing_25d')
|
||||
self.odm_georeferencing = io.join_paths(self.root_path, 'odm_georeferencing')
|
||||
self.odm_25dgeoreferencing = io.join_paths(self.root_path, 'odm_25dgeoreferencing')
|
||||
self.odm_filterpoints = io.join_paths(self.root_path, 'odm_filterpoints')
|
||||
self.odm_orthophoto = io.join_paths(self.root_path, 'odm_orthophoto')
|
||||
self.odm_pdal = io.join_paths(self.root_path, 'pdal')
|
||||
|
||||
# important files paths
|
||||
|
||||
|
@ -278,6 +278,9 @@ class ODM_Tree(object):
|
|||
self.mve_bundle = io.join_paths(self.mve_path, 'bundle/bundle.out')
|
||||
self.mve_views = io.join_paths(self.mve, 'views')
|
||||
|
||||
# filter points
|
||||
self.filtered_point_cloud = io.join_paths(self.odm_filterpoints, "point_cloud.ply")
|
||||
|
||||
# odm_meshing
|
||||
self.odm_mesh = io.join_paths(self.odm_meshing, 'odm_mesh.ply')
|
||||
self.odm_meshing_log = io.join_paths(self.odm_meshing, 'odm_meshing_log.txt')
|
||||
|
|
|
@ -7,12 +7,6 @@ from opendm import context
|
|||
from opendm import point_cloud
|
||||
|
||||
class ODMMveCell(ecto.Cell):
|
||||
|
||||
def declare_params(self, params):
|
||||
params.declare("mve_output_scale", "scale of optimization", 2)
|
||||
params.declare("max_concurrency", "max number of threads", 3)
|
||||
# params.declare("mve_filter_range", "min confidence value", 0.5)
|
||||
|
||||
def declare_io(self, params, inputs, outputs):
|
||||
inputs.declare("tree", "Struct with paths", [])
|
||||
inputs.declare("args", "The application arguments.", {})
|
||||
|
@ -20,7 +14,6 @@ class ODMMveCell(ecto.Cell):
|
|||
outputs.declare("reconstruction", "list of ODMReconstructions", [])
|
||||
|
||||
def process(self, inputs, outputs):
|
||||
|
||||
# Benchmarking
|
||||
start_time = system.now_raw()
|
||||
|
||||
|
@ -66,32 +59,27 @@ class ODMMveCell(ecto.Cell):
|
|||
if not io.dir_exists(tree.mve_views):
|
||||
system.run('%s %s %s' % (context.makescene_path, tree.mve_path, tree.mve))
|
||||
|
||||
|
||||
|
||||
#dmrecon config
|
||||
config = [
|
||||
dmrecon_config = [
|
||||
"-s%s" % args.mve_output_scale,
|
||||
#"-s%s" % args.max_concurrency,
|
||||
"--progress=silent"
|
||||
|
||||
"--progress=silent"
|
||||
]
|
||||
|
||||
#run dmrecon
|
||||
system.run('%s %s %s' % (context.mve_path, ' '.join(config), tree.mve))
|
||||
# Run MVE's dmrecon
|
||||
system.run('%s %s %s' % (context.dmrecon_path, ' '.join(dmrecon_config), tree.mve))
|
||||
|
||||
|
||||
#scene2pset config
|
||||
config = [
|
||||
"-F1",
|
||||
"--with-conf"
|
||||
]
|
||||
scene2pset_config = [
|
||||
"-F1",
|
||||
"--with-conf"
|
||||
]
|
||||
|
||||
# run scene2pset
|
||||
system.run('%s %s %s %s' % (context.mve_path_pc, ' '.join(config), tree.mve, tree.mve_model))
|
||||
system.run('%s %s "%s" "%s"' % (context.scene2pset_path, ' '.join(scene2pset_config), tree.mve, tree.mve_model))
|
||||
|
||||
# run pdal
|
||||
system.run('%s %s %s %s %s %s' % (context.pdal_path_pc, ' translate -i ', tree.mve_model, '-o ', tree.mve_model_output, ' -f range --filters.range.limits="confidence[0.25:1]"'))
|
||||
|
||||
# run pdal
|
||||
system.run('pdal translate -i {} '
|
||||
' -o {} '
|
||||
' -f range --filters.range.limits="confidence[0.25:1]'.format(tree.mve_model, tree.mve_model_output))
|
||||
|
||||
# find and rename the output file for simplicity
|
||||
mve_files = glob.glob(os.path.join(tree.mve, 'mve-*'))
|
||||
mve_files.sort(key=os.path.getmtime) # sort by last modified date
|
||||
|
@ -99,9 +87,6 @@ class ODMMveCell(ecto.Cell):
|
|||
old_file = mve_files[-1]
|
||||
if not (io.rename_file(old_file, tree.mve_model)):
|
||||
log.ODM_WARNING("File %s does not exist, cannot be renamed. " % old_file)
|
||||
|
||||
# Filter
|
||||
point_cloud.filter(tree.mve_model_output, standard_deviation=args.pc_filter, verbose=args.verbose)
|
||||
else:
|
||||
log.ODM_WARNING("Cannot find a valid point cloud (mve-XX.ply) in %s. Check the console output for errors." % tree.mve)
|
||||
else:
|
||||
|
|
|
@ -15,6 +15,7 @@ from mvstex import ODMMvsTexCell
|
|||
from odm_georeferencing import ODMGeoreferencingCell
|
||||
from odm_orthophoto import ODMOrthoPhotoCell
|
||||
from odm_dem import ODMDEMCell
|
||||
from odm_filterpoints import ODMFilterPoints
|
||||
|
||||
|
||||
class ODMApp(ecto.BlackBox):
|
||||
|
@ -48,8 +49,9 @@ class ODMApp(ecto.BlackBox):
|
|||
hybrid_bundle_adjustment=p.args.use_hybrid_bundle_adjustment),
|
||||
'slam': ODMSlamCell(),
|
||||
|
||||
'mve': ODMMveCell(mve_output_scale=p.args.mve_output_scale,
|
||||
max_concurrency=p.args.max_concurrency),
|
||||
'mve': ODMMveCell(),
|
||||
|
||||
'filterpoints': ODMFilterPoints(),
|
||||
|
||||
'meshing': ODMeshingCell(max_vertex=p.args.mesh_size,
|
||||
oct_tree=p.args.mesh_octree_depth,
|
||||
|
@ -96,13 +98,6 @@ class ODMApp(ecto.BlackBox):
|
|||
if p.args.video:
|
||||
return self.slam_connections(p)
|
||||
|
||||
# define initial task
|
||||
# TODO: What is this?
|
||||
# initial_task = p.args['start_with']
|
||||
# initial_task_id = config.processopts.index(initial_task)
|
||||
|
||||
# define the connections like you would for the plasm
|
||||
|
||||
# load the dataset
|
||||
connections = [self.tree[:] >> self.dataset['tree'],
|
||||
self.args[:] >> self.dataset['args']]
|
||||
|
@ -113,21 +108,25 @@ class ODMApp(ecto.BlackBox):
|
|||
self.dataset['reconstruction'] >> self.opensfm['reconstruction']]
|
||||
|
||||
if p.args.use_opensfm_dense or p.args.fast_orthophoto:
|
||||
# create odm mesh from opensfm point cloud
|
||||
connections += [self.tree[:] >> self.meshing['tree'],
|
||||
self.args[:] >> self.meshing['args'],
|
||||
self.opensfm['reconstruction'] >> self.meshing['reconstruction']]
|
||||
# filter points from opensfm point cloud
|
||||
connections += [self.tree[:] >> self.filterpoints['tree'],
|
||||
self.args[:] >> self.filterpoints['args'],
|
||||
self.opensfm['reconstruction'] >> self.filterpoints['reconstruction']]
|
||||
else:
|
||||
# run mve
|
||||
|
||||
connections += [self.tree[:] >> self.mve['tree'],
|
||||
self.args[:] >> self.mve['args'],
|
||||
self.opensfm['reconstruction'] >> self.mve['reconstruction']]
|
||||
|
||||
# create odm mesh from mve point cloud
|
||||
connections += [self.tree[:] >> self.meshing['tree'],
|
||||
self.args[:] >> self.meshing['args'],
|
||||
self.mve['reconstruction'] >> self.meshing['reconstruction']]
|
||||
# filter points from mve point cloud
|
||||
connections += [self.tree[:] >> self.filterpoints['tree'],
|
||||
self.args[:] >> self.filterpoints['args'],
|
||||
self.mve['reconstruction'] >> self.filterpoints['reconstruction']]
|
||||
|
||||
# create mesh
|
||||
connections += [self.tree[:] >> self.meshing['tree'],
|
||||
self.args[:] >> self.meshing['args'],
|
||||
self.filterpoints['reconstruction'] >> self.meshing['reconstruction']]
|
||||
|
||||
# create odm texture
|
||||
connections += [self.tree[:] >> self.texturing['tree'],
|
||||
|
|
|
@ -0,0 +1,56 @@
|
|||
import ecto, os
|
||||
|
||||
from opendm import log
|
||||
from opendm import io
|
||||
from opendm import system
|
||||
from opendm import context
|
||||
from opendm import point_cloud
|
||||
|
||||
class ODMFilterPoints(ecto.Cell):
|
||||
def declare_io(self, params, inputs, outputs):
|
||||
inputs.declare("tree", "Struct with paths", [])
|
||||
inputs.declare("args", "The application arguments.", {})
|
||||
inputs.declare("reconstruction", "ODMReconstruction", [])
|
||||
outputs.declare("reconstruction", "list of ODMReconstructions", [])
|
||||
|
||||
def process(self, inputs, outputs):
|
||||
# Benchmarking
|
||||
start_time = system.now_raw()
|
||||
|
||||
log.ODM_INFO('Running ODM FilterPoints Cell')
|
||||
|
||||
# get inputs
|
||||
tree = inputs.tree
|
||||
args = inputs.args
|
||||
reconstruction = inputs.reconstruction
|
||||
|
||||
# check if we rerun cell or not
|
||||
rerun_cell = (args.rerun is not None and
|
||||
args.rerun == 'odm_filterpoints') or \
|
||||
(args.rerun_all) or \
|
||||
(args.rerun_from is not None and
|
||||
'odm_filterpoints' in args.rerun_from)
|
||||
if not os.path.exists(tree.odm_filterpoints): system.mkdir_p(tree.odm_filterpoints)
|
||||
|
||||
# check if reconstruction was done before
|
||||
if not io.file_exists(tree.filtered_point_cloud) or rerun_cell:
|
||||
if args.fast_orthophoto:
|
||||
inputPointCloud = os.path.join(tree.opensfm, 'reconstruction.ply')
|
||||
elif args.use_opensfm_dense:
|
||||
inputPointCloud = tree.opensfm_model
|
||||
else:
|
||||
inputPointCloud = tree.mve_model
|
||||
|
||||
# TODO add MVE filter
|
||||
point_cloud.filter(inputPointCloud, tree.filtered_point_cloud, standard_deviation=args.pc_filter, verbose=args.verbose)
|
||||
else:
|
||||
log.ODM_WARNING('Found a valid point cloud file in: %s' %
|
||||
tree.filtered_point_cloud)
|
||||
|
||||
outputs.reconstruction = reconstruction
|
||||
|
||||
if args.time:
|
||||
system.benchmark(start_time, tree.benchmarking, 'MVE')
|
||||
|
||||
log.ODM_INFO('Running ODM FilterPoints Cell - Finished')
|
||||
return ecto.OK if args.end_with != 'odm_filterpoints' else ecto.QUIT
|
|
@ -83,6 +83,7 @@ class ODMGeoreferencingCell(ecto.Cell):
|
|||
# odm_georeference definitions
|
||||
kwargs = {
|
||||
'bin': context.odm_modules_path,
|
||||
'input_pc_file': tree.filtered_point_cloud,
|
||||
'bundle': tree.opensfm_bundle,
|
||||
'imgs': tree.dataset_raw,
|
||||
'imgs_list': tree.opensfm_bundle_list,
|
||||
|
@ -98,13 +99,6 @@ class ODMGeoreferencingCell(ecto.Cell):
|
|||
'verbose': verbose
|
||||
}
|
||||
|
||||
if args.fast_orthophoto:
|
||||
kwargs['input_pc_file'] = os.path.join(tree.opensfm, 'reconstruction.ply')
|
||||
elif args.use_opensfm_dense:
|
||||
kwargs['input_pc_file'] = tree.opensfm_model
|
||||
else:
|
||||
kwargs['input_pc_file'] = tree.mve_model
|
||||
|
||||
if transformPointCloud:
|
||||
kwargs['pc_params'] = '-inputPointCloudFile {input_pc_file} -outputPointCloudFile {output_pc_file}'.format(**kwargs)
|
||||
|
||||
|
|
|
@ -49,18 +49,12 @@ class ODMeshingCell(ecto.Cell):
|
|||
(args.rerun_from is not None and
|
||||
'odm_meshing' in args.rerun_from)
|
||||
|
||||
infile = tree.mve_model_output
|
||||
if args.fast_orthophoto:
|
||||
infile = os.path.join(tree.opensfm, 'reconstruction.ply')
|
||||
elif args.use_opensfm_dense:
|
||||
infile = tree.opensfm_model
|
||||
|
||||
# Create full 3D model unless --skip-3dmodel is set
|
||||
if not args.skip_3dmodel:
|
||||
if not io.file_exists(tree.odm_mesh) or rerun_cell:
|
||||
log.ODM_DEBUG('Writing ODM Mesh file in: %s' % tree.odm_mesh)
|
||||
|
||||
mesh.screened_poisson_reconstruction(infile,
|
||||
mesh.screened_poisson_reconstruction(tree.filtered_point_cloud,
|
||||
tree.odm_mesh,
|
||||
depth=self.params.oct_tree,
|
||||
samples=self.params.samples,
|
||||
|
@ -97,7 +91,7 @@ class ODMeshingCell(ecto.Cell):
|
|||
|
||||
log.ODM_DEBUG('ODM 2.5D DSM resolution: %s' % dsm_resolution)
|
||||
|
||||
mesh.create_25dmesh(infile, tree.odm_25dmesh,
|
||||
mesh.create_25dmesh(tree.filtered_point_cloud, tree.odm_25dmesh,
|
||||
dsm_radius=dsm_radius,
|
||||
dsm_resolution=dsm_resolution,
|
||||
depth=self.params.oct_tree,
|
||||
|
|
|
@ -172,9 +172,6 @@ class ODMOpenSfMCell(ecto.Cell):
|
|||
if args.fast_orthophoto:
|
||||
system.run('PYTHONPATH=%s %s/bin/opensfm export_ply --no-cameras %s' %
|
||||
(context.pyopencv_path, context.opensfm_path, tree.opensfm))
|
||||
|
||||
# Filter
|
||||
point_cloud.filter(os.path.join(tree.opensfm, 'reconstruction.ply'), standard_deviation=args.pc_filter, verbose=args.verbose)
|
||||
elif args.use_opensfm_dense:
|
||||
# Undistort images at full scale in JPG
|
||||
# (TODO: we could compare the size of the PNGs if they are < than depthmap_resolution
|
||||
|
@ -183,9 +180,6 @@ class ODMOpenSfMCell(ecto.Cell):
|
|||
(context.pyopencv_path, context.opensfm_path, tree.opensfm))
|
||||
system.run('PYTHONPATH=%s %s/bin/opensfm compute_depthmaps %s' %
|
||||
(context.pyopencv_path, context.opensfm_path, tree.opensfm))
|
||||
|
||||
# Filter
|
||||
point_cloud.filter(tree.opensfm_model, standard_deviation=args.pc_filter, verbose=args.verbose)
|
||||
else:
|
||||
log.ODM_WARNING('Found a valid OpenSfM reconstruction file in: %s' %
|
||||
tree.opensfm_reconstruction)
|
||||
|
|
Ładowanie…
Reference in New Issue