kopia lustrzana https://github.com/OpenDroneMap/ODM
commit
d9c498e5ec
|
@ -24,7 +24,10 @@ RUN rm -rf \
|
|||
/code/SuperBuild/src/opencv \
|
||||
/code/SuperBuild/src/opengv \
|
||||
/code/SuperBuild/src/pcl \
|
||||
/code/SuperBuild/src/pdal
|
||||
/code/SuperBuild/src/pdal \
|
||||
/code/SuperBuild/src/openmvs \
|
||||
/code/SuperBuild/build/openmvs \
|
||||
/code/SuperBuild/src/vcg
|
||||
|
||||
# find in /code and delete...
|
||||
RUN find /code \
|
||||
|
|
|
@ -101,26 +101,18 @@ SETUP_EXTERNAL_PROJECT(Ceres ${ODM_Ceres_Version} ${ODM_BUILD_Ceres})
|
|||
SETUP_EXTERNAL_PROJECT(Hexer 1.4 ON)
|
||||
|
||||
# ---------------------------------------------------------------------------------------------
|
||||
# Open Geometric Vision (OpenGV)
|
||||
# Open Structure from Motion (OpenSfM)
|
||||
#
|
||||
|
||||
set(custom_libs OpenGV
|
||||
OpenSfM
|
||||
set(custom_libs OpenSfM
|
||||
LASzip
|
||||
Zstd
|
||||
PDAL
|
||||
Entwine
|
||||
MvsTexturing
|
||||
OpenMVS
|
||||
)
|
||||
|
||||
# Dependencies of the SLAM module
|
||||
if(ODM_BUILD_SLAM)
|
||||
list(APPEND custom_libs
|
||||
Pangolin
|
||||
ORB_SLAM2)
|
||||
endif()
|
||||
|
||||
foreach(lib ${custom_libs})
|
||||
SETUP_EXTERNAL_PROJECT_CUSTOM(${lib})
|
||||
endforeach()
|
||||
|
@ -128,19 +120,6 @@ endforeach()
|
|||
include(ProcessorCount)
|
||||
ProcessorCount(nproc)
|
||||
|
||||
## Add mve Build
|
||||
|
||||
externalproject_add(mve
|
||||
GIT_REPOSITORY https://github.com/OpenDroneMap/mve.git
|
||||
GIT_TAG 200
|
||||
UPDATE_COMMAND ""
|
||||
SOURCE_DIR ${SB_SOURCE_DIR}/elibs/mve
|
||||
CONFIGURE_COMMAND ""
|
||||
BUILD_IN_SOURCE 1
|
||||
BUILD_COMMAND make -j${nproc}
|
||||
INSTALL_COMMAND ""
|
||||
)
|
||||
|
||||
externalproject_add(poissonrecon
|
||||
GIT_REPOSITORY https://github.com/mkazhdan/PoissonRecon.git
|
||||
GIT_TAG ce5005ae3094d902d551a65a8b3131e06f45e7cf
|
||||
|
|
|
@ -47,6 +47,7 @@ ExternalProject_Add(${_proj_name}
|
|||
-DBUILD_opencv_ocl=OFF
|
||||
-DBUILD_opencv_ts=OFF
|
||||
-DBUILD_opencv_xfeatures2d=ON
|
||||
-DOPENCV_ALLOCATOR_STATS_COUNTER_TYPE=int64_t
|
||||
-DCMAKE_BUILD_TYPE:STRING=Release
|
||||
-DCMAKE_INSTALL_PREFIX:PATH=${SB_INSTALL_DIR}
|
||||
#--Build step-----------------
|
||||
|
|
|
@ -1,23 +1,35 @@
|
|||
set(_proj_name opengv)
|
||||
set(_proj_name openmvs)
|
||||
set(_SB_BINARY_DIR "${SB_BINARY_DIR}/${_proj_name}")
|
||||
|
||||
externalproject_add(vcg
|
||||
GIT_REPOSITORY https://github.com/cdcseacave/VCG.git
|
||||
GIT_TAG master
|
||||
UPDATE_COMMAND ""
|
||||
SOURCE_DIR ${SB_SOURCE_DIR}/vcg
|
||||
CONFIGURE_COMMAND ""
|
||||
BUILD_IN_SOURCE 1
|
||||
BUILD_COMMAND ""
|
||||
INSTALL_COMMAND ""
|
||||
)
|
||||
|
||||
ExternalProject_Add(${_proj_name}
|
||||
DEPENDS ceres opencv vcg
|
||||
PREFIX ${_SB_BINARY_DIR}
|
||||
TMP_DIR ${_SB_BINARY_DIR}/tmp
|
||||
STAMP_DIR ${_SB_BINARY_DIR}/stamp
|
||||
#--Download step--------------
|
||||
DOWNLOAD_DIR ${SB_DOWNLOAD_DIR}
|
||||
GIT_REPOSITORY https://github.com/paulinus/opengv/
|
||||
GIT_TAG 306a54e6c6b94e2048f820cdf77ef5281d4b48ad
|
||||
GIT_REPOSITORY https://github.com/OpenDroneMap/openMVS
|
||||
GIT_TAG 210
|
||||
#--Update/Patch step----------
|
||||
UPDATE_COMMAND git submodule update --init --recursive
|
||||
UPDATE_COMMAND ""
|
||||
#--Configure step-------------
|
||||
SOURCE_DIR ${SB_SOURCE_DIR}/${_proj_name}
|
||||
CMAKE_ARGS
|
||||
-DBUILD_TESTS=OFF
|
||||
-DBUILD_PYTHON=ON
|
||||
-DPYBIND11_PYTHON_VERSION=3.6
|
||||
-DCMAKE_INSTALL_PREFIX:PATH=${SB_INSTALL_DIR}
|
||||
-DOpenCV_DIR=${SB_INSTALL_DIR}/lib/cmake/opencv4
|
||||
-DVCG_ROOT=${SB_SOURCE_DIR}/vcg
|
||||
-DCMAKE_BUILD_TYPE=Release
|
||||
-DCMAKE_INSTALL_PREFIX=${SB_INSTALL_DIR}
|
||||
#--Build step-----------------
|
||||
BINARY_DIR ${_SB_BINARY_DIR}
|
||||
#--Install step---------------
|
||||
|
@ -27,4 +39,3 @@ ExternalProject_Add(${_proj_name}
|
|||
LOG_CONFIGURE OFF
|
||||
LOG_BUILD OFF
|
||||
)
|
||||
|
|
@ -2,22 +2,22 @@ set(_proj_name opensfm)
|
|||
set(_SB_BINARY_DIR "${SB_BINARY_DIR}/${_proj_name}")
|
||||
|
||||
ExternalProject_Add(${_proj_name}
|
||||
DEPENDS ceres opencv opengv gflags
|
||||
DEPENDS ceres opencv gflags
|
||||
PREFIX ${_SB_BINARY_DIR}
|
||||
TMP_DIR ${_SB_BINARY_DIR}/tmp
|
||||
STAMP_DIR ${_SB_BINARY_DIR}/stamp
|
||||
#--Download step--------------
|
||||
DOWNLOAD_DIR ${SB_DOWNLOAD_DIR}
|
||||
GIT_REPOSITORY https://github.com/OpenDroneMap/OpenSfM/
|
||||
GIT_TAG 200
|
||||
GIT_TAG 210
|
||||
#--Update/Patch step----------
|
||||
UPDATE_COMMAND git submodule update --init --recursive
|
||||
PATCH_COMMAND git apply ../../../patches/OpenSfM.diff
|
||||
#--Configure step-------------
|
||||
SOURCE_DIR ${SB_SOURCE_DIR}/${_proj_name}
|
||||
CONFIGURE_COMMAND cmake <SOURCE_DIR>/${_proj_name}/src
|
||||
-DCERES_ROOT_DIR=${SB_INSTALL_DIR}
|
||||
-DOpenCV_DIR=${SB_INSTALL_DIR}/lib/cmake/opencv4
|
||||
-DADDITIONAL_INCLUDE_DIRS=${SB_INSTALL_DIR}/include
|
||||
-DOPENSFM_BUILD_TESTS=off
|
||||
-DPYTHON_EXECUTABLE=/usr/bin/python3
|
||||
#--Build step-----------------
|
||||
|
|
2
VERSION
2
VERSION
|
@ -1 +1 @@
|
|||
2.0.0
|
||||
2.1.0
|
||||
|
|
|
@ -87,6 +87,9 @@ installruntimedepsonly() {
|
|||
installdepsfromsnapcraft runtime opencv
|
||||
echo "Installing OpenSfM Dependencies"
|
||||
installdepsfromsnapcraft runtime opensfm
|
||||
echo "Installing OpenMVS Dependencies"
|
||||
installdepsfromsnapcraft runtime openmvs
|
||||
|
||||
}
|
||||
|
||||
install() {
|
||||
|
@ -106,8 +109,11 @@ install() {
|
|||
installdepsfromsnapcraft build opencv
|
||||
echo "Installing OpenSfM Dependencies"
|
||||
installdepsfromsnapcraft build opensfm
|
||||
echo "Installing OpenMVS Dependencies"
|
||||
installdepsfromsnapcraft build openmvs
|
||||
|
||||
|
||||
pip install -r requirements.txt
|
||||
pip install --ignore-installed -r requirements.txt
|
||||
|
||||
if [ ! -z "$PORTABLE_INSTALL" ]; then
|
||||
echo "Replacing g++ and gcc with our scripts for portability..."
|
||||
|
|
|
@ -9,7 +9,7 @@ import os
|
|||
import sys
|
||||
|
||||
# parse arguments
|
||||
processopts = ['dataset', 'split', 'merge', 'opensfm', 'mve', 'odm_filterpoints',
|
||||
processopts = ['dataset', 'split', 'merge', 'opensfm', 'openmvs', 'odm_filterpoints',
|
||||
'odm_meshing', 'mvs_texturing', 'odm_georeferencing',
|
||||
'odm_dem', 'odm_orthophoto', 'odm_report']
|
||||
|
||||
|
@ -275,16 +275,6 @@ def config(argv=None, parser=None):
|
|||
help='Run local bundle adjustment for every image added to the reconstruction and a global '
|
||||
'adjustment every 100 images. Speeds up reconstruction for very large datasets.')
|
||||
|
||||
parser.add_argument('--mve-confidence',
|
||||
metavar='<float: 0 <= x <= 1>',
|
||||
action=StoreValue,
|
||||
type=float,
|
||||
default=0.60,
|
||||
help=('Discard points that have less than a certain confidence threshold. '
|
||||
'This only affects dense reconstructions performed with MVE. '
|
||||
'Higher values discard more points. '
|
||||
'Default: %(default)s'))
|
||||
|
||||
parser.add_argument('--use-3dmesh',
|
||||
action=StoreTrue,
|
||||
nargs=0,
|
||||
|
@ -743,7 +733,7 @@ def config(argv=None, parser=None):
|
|||
type=float,
|
||||
action=StoreValue,
|
||||
metavar='<positive float>',
|
||||
default=15,
|
||||
default=10,
|
||||
help='Set a value in meters for the GPS Dilution of Precision (DOP) '
|
||||
'information for all images. If your images are tagged '
|
||||
'with high precision GPS information (RTK), this value will be automatically '
|
||||
|
|
|
@ -27,12 +27,6 @@ opensfm_path = os.path.join(superbuild_path, "src/opensfm")
|
|||
# define orb_slam2 path
|
||||
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
|
||||
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')
|
||||
meshclean_path = os.path.join(superbuild_path, 'src', 'elibs', 'mve', 'apps', 'meshclean', 'meshclean')
|
||||
|
||||
poisson_recon_path = os.path.join(superbuild_path, 'src', 'PoissonRecon', 'Bin', 'Linux', 'PoissonRecon')
|
||||
dem2mesh_path = os.path.join(superbuild_path, 'src', 'dem2mesh', 'dem2mesh')
|
||||
dem2points_path = os.path.join(superbuild_path, 'src', 'dem2points', 'dem2points')
|
||||
|
@ -40,6 +34,9 @@ dem2points_path = os.path.join(superbuild_path, 'src', 'dem2points', 'dem2points
|
|||
# define mvstex path
|
||||
mvstex_path = os.path.join(superbuild_path, "install/bin/texrecon")
|
||||
|
||||
# openmvs paths
|
||||
omvs_densify_path = os.path.join(superbuild_path, "install/bin/OpenMVS/DensifyPointCloud")
|
||||
|
||||
# define txt2las path
|
||||
txt2las_path = os.path.join(superbuild_path, 'src/las-tools/bin')
|
||||
pdal_path = os.path.join(superbuild_path, 'build/pdal/bin')
|
||||
|
|
|
@ -12,8 +12,8 @@ def extract_path_from_file(file):
|
|||
return path
|
||||
|
||||
|
||||
def join_paths(path1, path2):
|
||||
return os.path.join(path1, path2)
|
||||
def join_paths(*args):
|
||||
return os.path.join(*args)
|
||||
|
||||
|
||||
def file_exists(path_file):
|
||||
|
|
|
@ -11,14 +11,15 @@ from opendm import context
|
|||
from opendm import camera
|
||||
from opensfm.large import metadataset
|
||||
from opensfm.large import tools
|
||||
from opensfm.commands import undistort
|
||||
from opensfm.actions import undistort
|
||||
from opensfm.dataset import DataSet
|
||||
|
||||
class OSFMContext:
|
||||
def __init__(self, opensfm_project_path):
|
||||
self.opensfm_project_path = opensfm_project_path
|
||||
|
||||
def run(self, command):
|
||||
system.run('/usr/bin/env python3 %s/bin/opensfm %s "%s"' %
|
||||
system.run('%s/bin/opensfm %s "%s"' %
|
||||
(context.opensfm_path, command, self.opensfm_project_path))
|
||||
|
||||
def is_reconstruction_done(self):
|
||||
|
@ -316,10 +317,8 @@ class OSFMContext:
|
|||
undistorted_images_path = self.path("undistorted", "images")
|
||||
|
||||
if not io.dir_exists(undistorted_images_path) or rerun:
|
||||
cmd = undistort.Command(imageFilter)
|
||||
parser = argparse.ArgumentParser()
|
||||
cmd.add_arguments(parser)
|
||||
cmd.run(parser.parse_args([self.opensfm_project_path]))
|
||||
undistort.run_dataset(DataSet(self.opensfm_project_path), "reconstruction.json",
|
||||
0, None, "undistorted", imageFilter)
|
||||
else:
|
||||
log.ODM_WARNING("Found an undistorted directory in %s" % undistorted_images_path)
|
||||
|
||||
|
|
|
@ -72,6 +72,9 @@ class ODM_Reconstruction(object):
|
|||
if not io.file_exists(output_coords_file) or not io.file_exists(output_gcp_file) or rerun:
|
||||
gcp = GCPFile(gcp_file)
|
||||
if gcp.exists():
|
||||
if gcp.entries_count() == 0:
|
||||
raise RuntimeError("This GCP file does not have any entries. Are the entries entered in the proper format?")
|
||||
|
||||
# Create coords file, we'll be using this later
|
||||
# during georeferencing
|
||||
with open(output_coords_file, 'w') as f:
|
||||
|
@ -213,7 +216,7 @@ class ODM_Tree(object):
|
|||
# whole reconstruction process.
|
||||
self.dataset_raw = os.path.join(self.root_path, 'images')
|
||||
self.opensfm = os.path.join(self.root_path, 'opensfm')
|
||||
self.mve = os.path.join(self.root_path, 'mve')
|
||||
self.openmvs = os.path.join(self.opensfm, 'undistorted', 'openmvs')
|
||||
self.odm_meshing = os.path.join(self.root_path, 'odm_meshing')
|
||||
self.odm_texturing = os.path.join(self.root_path, 'odm_texturing')
|
||||
self.odm_25dtexturing = os.path.join(self.root_path, 'odm_texturing_25d')
|
||||
|
@ -240,9 +243,8 @@ class ODM_Tree(object):
|
|||
self.opensfm_model = os.path.join(self.opensfm, 'undistorted/depthmaps/merged.ply')
|
||||
self.opensfm_transformation = os.path.join(self.opensfm, 'geocoords_transformation.txt')
|
||||
|
||||
# mve
|
||||
self.mve_model = os.path.join(self.mve, 'mve_dense_point_cloud.ply')
|
||||
self.mve_views = os.path.join(self.mve, 'views')
|
||||
# OpenMVS
|
||||
self.openmvs_model = os.path.join(self.openmvs, 'scene_dense_dense_filtered.ply')
|
||||
|
||||
# filter points
|
||||
self.filtered_point_cloud = os.path.join(self.odm_filterpoints, "point_cloud.ply")
|
||||
|
|
|
@ -1,47 +0,0 @@
|
|||
diff --git a/opensfm/context.py b/opensfm/context.py
|
||||
index a01dd700..f54fcf87 100644
|
||||
--- a/opensfm/context.py
|
||||
+++ b/opensfm/context.py
|
||||
@@ -17,6 +17,9 @@ BOW_PATH = os.path.join(abspath, 'data', 'bow')
|
||||
|
||||
|
||||
# Handle different OpenCV versions
|
||||
+OPENCV5 = int(cv2.__version__.split('.')[0]) >= 5 #future proofing SIFT support test (see features.py)
|
||||
+OPENCV4 = int(cv2.__version__.split('.')[0]) >= 4
|
||||
+OPENCV44 = int(cv2.__version__.split('.')[0]) == 4 and int(cv2.__version__.split('.')[1]) >= 4 # for SIFT support (see features.py)
|
||||
OPENCV3 = int(cv2.__version__.split('.')[0]) >= 3
|
||||
|
||||
if hasattr(cv2, 'flann_Index'):
|
||||
diff --git a/opensfm/features.py b/opensfm/features.py
|
||||
index 3e80224b..78e51ce5 100644
|
||||
--- a/opensfm/features.py
|
||||
+++ b/opensfm/features.py
|
||||
@@ -87,7 +87,13 @@ def _in_mask(point, width, height, mask):
|
||||
def extract_features_sift(image, config):
|
||||
sift_edge_threshold = config['sift_edge_threshold']
|
||||
sift_peak_threshold = float(config['sift_peak_threshold'])
|
||||
- if context.OPENCV3:
|
||||
+ # SIFT support is in cv2 main from version 4.4.0
|
||||
+ if context.OPENCV44 or context.OPENCV5:
|
||||
+ detector = cv2.SIFT_create(
|
||||
+ edgeThreshold=sift_edge_threshold,
|
||||
+ contrastThreshold=sift_peak_threshold)
|
||||
+ descriptor = detector
|
||||
+ elif context.OPENCV3:
|
||||
try:
|
||||
detector = cv2.xfeatures2d.SIFT_create(
|
||||
edgeThreshold=sift_edge_threshold,
|
||||
@@ -105,7 +110,12 @@ def extract_features_sift(image, config):
|
||||
while True:
|
||||
logger.debug('Computing sift with threshold {0}'.format(sift_peak_threshold))
|
||||
t = time.time()
|
||||
- if context.OPENCV3:
|
||||
+ # SIFT support is in cv2 main from version 4.4.0
|
||||
+ if context.OPENCV44 or context.OPENCV5:
|
||||
+ detector = cv2.SIFT_create(
|
||||
+ edgeThreshold=sift_edge_threshold,
|
||||
+ contrastThreshold=sift_peak_threshold)
|
||||
+ elif context.OPENCV3:
|
||||
detector = cv2.xfeatures2d.SIFT_create(
|
||||
edgeThreshold=sift_edge_threshold,
|
||||
contrastThreshold=sift_peak_threshold)
|
|
@ -24,7 +24,10 @@ RUN rm -rf \
|
|||
/code/SuperBuild/src/opencv \
|
||||
/code/SuperBuild/src/opengv \
|
||||
/code/SuperBuild/src/pcl \
|
||||
/code/SuperBuild/src/pdal
|
||||
/code/SuperBuild/src/pdal \
|
||||
/code/SuperBuild/src/openmvs \
|
||||
/code/SuperBuild/build/openmvs \
|
||||
/code/SuperBuild/src/vcg
|
||||
|
||||
# find in /code and delete...
|
||||
RUN find /code \
|
||||
|
|
|
@ -17,13 +17,13 @@ numpy==1.19.2
|
|||
pyproj==2.2.2
|
||||
Pysolar==0.6
|
||||
psutil==5.6.3
|
||||
joblib==0.13.2
|
||||
joblib==0.17.0
|
||||
Fiona==1.8.9.post2
|
||||
cryptography==2.8
|
||||
pyOpenSSL==19.1.0
|
||||
scikit-learn==0.20
|
||||
scikit-learn==0.23.2
|
||||
laspy==1.6.0
|
||||
beautifulsoup4==4.9.1
|
||||
lxml==4.5.1
|
||||
matplotlib==1.5.1
|
||||
edt==2.0.1
|
||||
edt==2.0.1
|
||||
|
|
3
run.py
3
run.py
|
@ -55,11 +55,12 @@ if __name__ == '__main__':
|
|||
quote(os.path.join(args.project_path, "odm_meshing")),
|
||||
quote(os.path.join(args.project_path, "odm_orthophoto")),
|
||||
quote(os.path.join(args.project_path, "odm_dem")),
|
||||
quote(os.path.join(args.project_path, "odm_report")),
|
||||
quote(os.path.join(args.project_path, "odm_texturing")),
|
||||
quote(os.path.join(args.project_path, "opensfm")),
|
||||
quote(os.path.join(args.project_path, "odm_filterpoints")),
|
||||
quote(os.path.join(args.project_path, "odm_texturing_25d")),
|
||||
quote(os.path.join(args.project_path, "mve")),
|
||||
quote(os.path.join(args.project_path, "openmvs")),
|
||||
quote(os.path.join(args.project_path, "entwine_pointcloud")),
|
||||
quote(os.path.join(args.project_path, "submodels")),
|
||||
]))
|
||||
|
|
|
@ -105,6 +105,17 @@ parts:
|
|||
- libtiff5
|
||||
- libvtk6.3
|
||||
- libxext6
|
||||
|
||||
openmvs:
|
||||
source: .
|
||||
plugin: nil
|
||||
override-pull: exit 0
|
||||
build-packages:
|
||||
- libcgal-dev
|
||||
- libboost-program-options-dev
|
||||
stage-packages:
|
||||
- libboost-program-options1.65.1
|
||||
- libcgal-dev
|
||||
|
||||
opensfm:
|
||||
source: .
|
||||
|
@ -141,6 +152,7 @@ parts:
|
|||
- prereqs
|
||||
- opencv
|
||||
- opensfm
|
||||
- openmvs
|
||||
source: .
|
||||
plugin: nil # We will script everything ourselves
|
||||
build-environment:
|
||||
|
@ -183,7 +195,7 @@ parts:
|
|||
- -odm/SuperBuild/src/laszip
|
||||
- -odm/SuperBuild/src/mvstexturing
|
||||
- -odm/SuperBuild/src/opencv
|
||||
- -odm/SuperBuild/src/opengv
|
||||
- -odm/SuperBuild/src/openmvs
|
||||
- -odm/SuperBuild/src/pcl
|
||||
- -odm/SuperBuild/src/pdal
|
||||
- -odm/SuperBuild/src/zstd
|
||||
|
|
|
@ -110,7 +110,7 @@ class ODMLoadDatasetStage(types.ODM_Stage):
|
|||
p.set_mask(find_mask(f, masks))
|
||||
photos += [p]
|
||||
dataset_list.write(photos[-1].filename + '\n')
|
||||
|
||||
|
||||
# Check if a geo file is available
|
||||
if tree.odm_geo_file is not None and os.path.exists(tree.odm_geo_file):
|
||||
log.ODM_INFO("Found image geolocation file")
|
||||
|
@ -134,6 +134,22 @@ class ODMLoadDatasetStage(types.ODM_Stage):
|
|||
|
||||
log.ODM_INFO('Found %s usable images' % len(photos))
|
||||
|
||||
# TODO: add support for masks in OpenMVS
|
||||
has_mask = False
|
||||
for p in photos:
|
||||
if p.mask is not None:
|
||||
has_mask = True
|
||||
break
|
||||
|
||||
if has_mask and not args.use_opensfm_dense and not args.fast_orthophoto:
|
||||
log.ODM_WARNING("Image masks found, will use OpenSfM for dense reconstruction")
|
||||
args.use_opensfm_dense = True
|
||||
|
||||
# Remove OpenMVS from pipeline. Yep.
|
||||
opensfm_stage = self.next_stage.next_stage.next_stage
|
||||
opensfm_stage.next_stage = opensfm_stage.next_stage.next_stage
|
||||
opensfm_stage.next_stage.prev_stage = opensfm_stage
|
||||
|
||||
# Create reconstruction object
|
||||
reconstruction = types.ODM_Reconstruction(photos)
|
||||
|
||||
|
|
102
stages/mve.py
102
stages/mve.py
|
@ -1,102 +0,0 @@
|
|||
import shutil, os, glob, math
|
||||
|
||||
from opendm import log
|
||||
from opendm import io
|
||||
from opendm import system
|
||||
from opendm import context
|
||||
from opendm import point_cloud
|
||||
from opendm import types
|
||||
from opendm.osfm import OSFMContext
|
||||
|
||||
class ODMMveStage(types.ODM_Stage):
|
||||
def process(self, args, outputs):
|
||||
# get inputs
|
||||
tree = outputs['tree']
|
||||
reconstruction = outputs['reconstruction']
|
||||
photos = reconstruction.photos
|
||||
|
||||
if not photos:
|
||||
log.ODM_ERROR('Not enough photos in photos array to start MVE')
|
||||
exit(1)
|
||||
|
||||
# check if reconstruction was done before
|
||||
if not io.file_exists(tree.mve_model) or self.rerun():
|
||||
# mve makescene wants the output directory
|
||||
# to not exists before executing it (otherwise it
|
||||
# will prompt the user for confirmation)
|
||||
if io.dir_exists(tree.mve):
|
||||
shutil.rmtree(tree.mve)
|
||||
|
||||
# run mve makescene
|
||||
if not io.dir_exists(tree.mve_views):
|
||||
nvm_file = tree.opensfm_reconstruction_nvm
|
||||
if reconstruction.multi_camera:
|
||||
# Reconstruct only the primary band
|
||||
primary = reconstruction.multi_camera[0]
|
||||
nvm_file = os.path.join(tree.opensfm, "undistorted", "reconstruction_%s.nvm" % primary['name'].lower())
|
||||
|
||||
system.run('%s "%s" "%s"' % (context.makescene_path, nvm_file, tree.mve), env_vars={'OMP_NUM_THREADS': args.max_concurrency})
|
||||
|
||||
self.update_progress(10)
|
||||
|
||||
# Compute mve output scale based on depthmap_resolution
|
||||
max_pixels = args.depthmap_resolution * args.depthmap_resolution
|
||||
if outputs['undist_image_max_size'] * outputs['undist_image_max_size'] <= max_pixels:
|
||||
mve_output_scale = 0
|
||||
else:
|
||||
ratio = float(outputs['undist_image_max_size'] * outputs['undist_image_max_size']) / float(max_pixels)
|
||||
mve_output_scale = int(math.ceil(math.log(ratio) / math.log(4.0)))
|
||||
|
||||
dmrecon_config = [
|
||||
"-s%s" % mve_output_scale,
|
||||
"--progress=fancy",
|
||||
"--local-neighbors=2",
|
||||
# "--filter-width=3",
|
||||
]
|
||||
|
||||
# Run MVE's dmrecon
|
||||
log.ODM_INFO("Running dense reconstruction. This might take a while.")
|
||||
|
||||
# TODO: find out why MVE is crashing at random
|
||||
# MVE *seems* to have a race condition, triggered randomly, regardless of dataset
|
||||
# https://gist.github.com/pierotofy/6c9ce93194ba510b61e42e3698cfbb89
|
||||
# Temporary workaround is to retry the reconstruction until we get it right
|
||||
# (up to a certain number of retries).
|
||||
retry_count = 1
|
||||
while retry_count < 10:
|
||||
try:
|
||||
system.run('%s %s "%s"' % (context.dmrecon_path, ' '.join(dmrecon_config), tree.mve), env_vars={'OMP_NUM_THREADS': args.max_concurrency})
|
||||
break
|
||||
except Exception as e:
|
||||
if str(e) == "Child returned 134" or str(e) == "Child returned 1":
|
||||
retry_count += 1
|
||||
log.ODM_WARNING("Caught error code, retrying attempt #%s" % retry_count)
|
||||
else:
|
||||
raise e
|
||||
|
||||
self.update_progress(90)
|
||||
|
||||
scene2pset_config = [
|
||||
"-F%s" % mve_output_scale,
|
||||
'-mmask'
|
||||
]
|
||||
|
||||
# run scene2pset
|
||||
system.run('%s %s "%s" "%s"' % (context.scene2pset_path, ' '.join(scene2pset_config), tree.mve, tree.mve_model), env_vars={'OMP_NUM_THREADS': args.max_concurrency})
|
||||
|
||||
# run cleanmesh (filter points by MVE confidence threshold)
|
||||
if args.mve_confidence > 0:
|
||||
mve_filtered_model = io.related_file_path(tree.mve_model, postfix=".filtered")
|
||||
system.run('%s -t%s --no-clean --component-size=0 "%s" "%s"' % (context.meshclean_path, min(1.0, args.mve_confidence), tree.mve_model, mve_filtered_model), env_vars={'OMP_NUM_THREADS': args.max_concurrency})
|
||||
|
||||
if io.file_exists(mve_filtered_model):
|
||||
os.remove(tree.mve_model)
|
||||
os.rename(mve_filtered_model, tree.mve_model)
|
||||
else:
|
||||
log.ODM_WARNING("Couldn't filter MVE model (%s does not exist)." % mve_filtered_model)
|
||||
|
||||
if args.optimize_disk_space:
|
||||
shutil.rmtree(tree.mve_views)
|
||||
else:
|
||||
log.ODM_WARNING('Found a valid MVE reconstruction file in: %s' %
|
||||
tree.mve_model)
|
|
@ -8,7 +8,7 @@ from opendm import log
|
|||
|
||||
from stages.dataset import ODMLoadDatasetStage
|
||||
from stages.run_opensfm import ODMOpenSfMStage
|
||||
from stages.mve import ODMMveStage
|
||||
from stages.openmvs import ODMOpenMVSStage
|
||||
from stages.odm_slam import ODMSlamStage
|
||||
from stages.odm_meshing import ODMeshingStage
|
||||
from stages.mvstex import ODMMvsTexStage
|
||||
|
@ -34,7 +34,7 @@ class ODMApp:
|
|||
merge = ODMMergeStage('merge', args, progress=100.0)
|
||||
opensfm = ODMOpenSfMStage('opensfm', args, progress=25.0)
|
||||
slam = ODMSlamStage('slam', args)
|
||||
mve = ODMMveStage('mve', args, progress=50.0)
|
||||
openmvs = ODMOpenMVSStage('openmvs', args, progress=50.0)
|
||||
filterpoints = ODMFilterPoints('odm_filterpoints', args, progress=52.0)
|
||||
meshing = ODMeshingStage('odm_meshing', args, progress=60.0,
|
||||
max_vertex=args.mesh_size,
|
||||
|
@ -71,8 +71,8 @@ class ODMApp:
|
|||
if args.use_opensfm_dense or args.fast_orthophoto:
|
||||
opensfm.connect(filterpoints)
|
||||
else:
|
||||
opensfm.connect(mve) \
|
||||
.connect(filterpoints)
|
||||
opensfm.connect(openmvs) \
|
||||
.connect(filterpoints)
|
||||
|
||||
filterpoints \
|
||||
.connect(meshing) \
|
||||
|
@ -82,14 +82,5 @@ class ODMApp:
|
|||
.connect(orthophoto) \
|
||||
.connect(report)
|
||||
|
||||
# # SLAM pipeline
|
||||
# # TODO: this is broken and needs work
|
||||
# log.ODM_WARNING("SLAM module is currently broken. We could use some help fixing this. If you know Python, get in touch at https://community.opendronemap.org.")
|
||||
# self.first_stage = slam
|
||||
|
||||
# slam.connect(mve) \
|
||||
# .connect(meshing) \
|
||||
# .connect(texturing)
|
||||
|
||||
def execute(self):
|
||||
self.first_stage.run()
|
|
@ -21,7 +21,7 @@ class ODMFilterPoints(types.ODM_Stage):
|
|||
elif args.use_opensfm_dense:
|
||||
inputPointCloud = tree.opensfm_model
|
||||
else:
|
||||
inputPointCloud = tree.mve_model
|
||||
inputPointCloud = tree.openmvs_model
|
||||
|
||||
point_cloud.filter(inputPointCloud, tree.filtered_point_cloud,
|
||||
standard_deviation=args.pc_filter,
|
||||
|
|
|
@ -131,9 +131,13 @@ class ODMGeoreferencingStage(types.ODM_Stage):
|
|||
if not args.fast_orthophoto:
|
||||
decimation_step *= int(len(reconstruction.photos) / 1000) + 1
|
||||
|
||||
cropper.create_bounds_gpkg(tree.odm_georeferencing_model_laz, args.crop,
|
||||
decimation_step=decimation_step)
|
||||
|
||||
try:
|
||||
cropper.create_bounds_gpkg(tree.odm_georeferencing_model_laz, args.crop,
|
||||
decimation_step=decimation_step)
|
||||
except:
|
||||
log.ODM_WARNING("Cannot calculate crop bounds! We will skip cropping")
|
||||
args.crop = 0
|
||||
|
||||
# Do not execute a second time, since
|
||||
# We might be doing georeferencing for
|
||||
# multiple models (3D, 2.5D, ...)
|
||||
|
|
|
@ -0,0 +1,90 @@
|
|||
import shutil, os, glob, math
|
||||
|
||||
from opendm import log
|
||||
from opendm import io
|
||||
from opendm import system
|
||||
from opendm import context
|
||||
from opendm import point_cloud
|
||||
from opendm import types
|
||||
from opendm.osfm import OSFMContext
|
||||
|
||||
class ODMOpenMVSStage(types.ODM_Stage):
|
||||
def process(self, args, outputs):
|
||||
# get inputs
|
||||
tree = outputs['tree']
|
||||
reconstruction = outputs['reconstruction']
|
||||
photos = reconstruction.photos
|
||||
|
||||
if not photos:
|
||||
log.ODM_ERROR('Not enough photos in photos array to start OpenMVS')
|
||||
exit(1)
|
||||
|
||||
# check if reconstruction was done before
|
||||
if not io.file_exists(tree.openmvs_model) or self.rerun():
|
||||
if io.dir_exists(tree.openmvs):
|
||||
shutil.rmtree(tree.openmvs)
|
||||
|
||||
# export reconstruction from opensfm
|
||||
octx = OSFMContext(tree.opensfm)
|
||||
cmd = 'export_openmvs'
|
||||
if reconstruction.multi_camera:
|
||||
# Export only the primary band
|
||||
primary = reconstruction.multi_camera[0]
|
||||
image_list = os.path.join(tree.opensfm, "image_list_%s.txt" % primary['name'].lower())
|
||||
cmd += ' --image_list "%s"' % image_list
|
||||
octx.run(cmd)
|
||||
|
||||
self.update_progress(10)
|
||||
|
||||
depthmaps_dir = os.path.join(tree.openmvs, "depthmaps")
|
||||
if not io.dir_exists(depthmaps_dir):
|
||||
os.mkdir(depthmaps_dir)
|
||||
|
||||
if outputs["undist_image_max_size"] <= args.depthmap_resolution:
|
||||
resolution_level = 0
|
||||
else:
|
||||
resolution_level = math.floor(math.log(outputs['undist_image_max_size'] / float(args.depthmap_resolution)) / math.log(2))
|
||||
|
||||
config = [
|
||||
" --resolution-level %s" % int(resolution_level),
|
||||
"--min-resolution %s" % int(args.depthmap_resolution),
|
||||
"--max-resolution %s" % int(outputs['undist_image_max_size']),
|
||||
"--max-threads %s" % args.max_concurrency,
|
||||
'-w "%s"' % depthmaps_dir,
|
||||
"-v 0",
|
||||
]
|
||||
|
||||
log.ODM_INFO("Running dense reconstruction. This might take a while.")
|
||||
|
||||
system.run('%s "%s" %s' % (context.omvs_densify_path,
|
||||
os.path.join(tree.openmvs, 'scene.mvs'),
|
||||
' '.join(config)))
|
||||
|
||||
self.update_progress(85)
|
||||
|
||||
# Filter points
|
||||
scene_dense = os.path.join(tree.openmvs, 'scene_dense.mvs')
|
||||
if os.path.exists(scene_dense):
|
||||
config = [
|
||||
"--filter-point-cloud -1",
|
||||
'-i "%s"' % scene_dense,
|
||||
"-v 0"
|
||||
]
|
||||
system.run('%s %s' % (context.omvs_densify_path, ' '.join(config)))
|
||||
else:
|
||||
log.ODM_WARNING("Cannot find scene_dense.mvs, dense reconstruction probably failed. Exiting...")
|
||||
exit(1)
|
||||
|
||||
self.update_progress(95)
|
||||
|
||||
if args.optimize_disk_space:
|
||||
files = [scene_dense,
|
||||
os.path.join(tree.openmvs, 'scene_dense.ply'),
|
||||
os.path.join(tree.openmvs, 'scene_dense_dense_filtered.mvs')]
|
||||
for f in files:
|
||||
if os.path.exists(f):
|
||||
os.remove(f)
|
||||
shutil.rmtree(depthmaps_dir)
|
||||
else:
|
||||
log.ODM_WARNING('Found a valid OpenMVS reconstruction file in: %s' %
|
||||
tree.openmvs_model)
|
|
@ -47,9 +47,14 @@ if [ "$1" = "--setup" ]; then
|
|||
|
||||
# Python paths
|
||||
echo $(python /code/opendm/context.py) >> $HOME/.bashrc
|
||||
|
||||
# Vim
|
||||
printf "syntax on\nset showmatch\nset ts=4\nset sts=4\nset sw=4\nset autoindent\nset smartindent\nset smarttab\nset expandtab" > $HOME/.vimrc
|
||||
|
||||
# Misc aliases
|
||||
echo "alias pdal=/code/SuperBuild/install/bin/pdal" >> $HOME/.bashrc
|
||||
echo "alias opensfm=/code/SuperBuild/src/opensfm/bin/opensfm" >> $HOME/.bashrc
|
||||
|
||||
|
||||
su -c bash $2
|
||||
exit 0
|
||||
|
@ -109,6 +114,6 @@ fi
|
|||
USER_ID=$(id -u)
|
||||
GROUP_ID=$(id -g)
|
||||
USER=$(id -un)
|
||||
xhost +
|
||||
xhost + || true
|
||||
docker run -ti --entrypoint bash --name odmdev -v $(pwd):/code -v "$DATA":/datasets -p $PORT:3000 --privileged -e DISPLAY -e LANG=C.UTF-8 -e LC_ALL=C.UTF-8 -v="/tmp/.X11-unix:/tmp/.X11-unix:rw" -v="$HOME/.odm-dev-home:/home/$USER" $IMAGE -c "/code/start-dev-env.sh --setup $USER $USER_ID $GROUP_ID $QTC"
|
||||
exit 0
|
||||
|
|
Ładowanie…
Reference in New Issue