Merge pull request #549 from dakotabenjamin/pdal-dem

Add DEM generation using PDAL

Former-commit-id: eaf9ab2e26
pull/1161/head
Dakota Benjamin 2017-04-24 16:10:51 -04:00 zatwierdzone przez GitHub
commit f07ddc182a
7 zmienionych plików z 147 dodań i 50 usunięć

Wyświetl plik

@ -14,16 +14,16 @@ In a word, OpenDroneMap is a toolchain for processing raw civilian UAS imagery t
2. Digital Surface Models
3. Textured Digital Surface Models
4. Orthorectified Imagery
5. Classified Point Clouds
5. Classified Point Clouds (coming soon)
6. Digital Elevation Models
7. etc.
So far, it does Point Clouds, Digital Surface Models, Textured Digital Surface Models, and Orthorectified Imagery. Open Drone Map now includes state-of-the-art 3D reconstruction work by Michael Waechter, Nils Moehrle, and Michael Goesele. See their publication at http://www.gcc.tu-darmstadt.de/media/gcc/papers/Waechter-2014-LTB.pdf.
Open Drone Map now includes state-of-the-art 3D reconstruction work by Michael Waechter, Nils Moehrle, and Michael Goesele. See their publication at http://www.gcc.tu-darmstadt.de/media/gcc/papers/Waechter-2014-LTB.pdf.
## QUICKSTART
OpenDroneMap can run natively on Ubuntu 14.04 or later, see [Build and Run Using Docker](#build-and-run-using-docker) for running on Windows / MacOS. A Vagrant VM is also available: https://github.com/OpenDroneMap/odm_vagrant.
OpenDroneMap can run natively on Ubuntu 14.04 or later, see [Build and Run Using Docker](#build-and-run-using-docker) for running on Windows / MacOS. A [Vagrant VM](https://github.com/OpenDroneMap/odm_vagrant) is also available.
*Support for Ubuntu 12.04 is currently BROKEN with the addition of OpenSfM and Ceres-Solver. It is likely to remain broken unless a champion is found to fix it.*
@ -74,7 +74,7 @@ Note that using `run.sh` sets these temporarily in the shell.
First you need a set of images, taken from a drone or otherwise. Example data can be obtained from https://github.com/OpenDroneMap/odm_data
Next, you need to copy over the settings file `default.settings.yaml` and edit it. The only setting you must edit is the `project-path` key. Set this to an empty directory within projects will be saved. There are many options for tuning your project. See the [wiki](https://github.com/OpenDroneMap/OpenDroneMap/wiki/Run-Time-Parameters) or run `python run.py -h`
Next, you need to edit the `settings.yaml` file. The only setting you must edit is the `project-path` key. Set this to an empty directory within projects will be saved. There are many options for tuning your project. See the [wiki](https://github.com/OpenDroneMap/OpenDroneMap/wiki/Run-Time-Parameters) or run `python run.py -h`
Then run:

Wyświetl plik

@ -42,6 +42,10 @@ project_path: '/' #DO NOT CHANGE THIS OR DOCKER WILL NOT WORK. It should be '/'
#texturing_keep_unseen_faces: False
#texturing_tone_mapping: 'none'
#gcp: !!null # YAML tag for None
#dem: False
#dem_sample_radius: 1.0
#dem_resolution: 2
#dem_radius: 0.5
#use_exif: False # Set to True if you have a GCP file (it auto-detects) and want to use EXIF
#orthophoto_resolution: 20.0 # Pixels/meter
#orthophoto_target_srs: !!null # Currently does nothing

Wyświetl plik

@ -314,6 +314,34 @@ def config():
help=('Use this tag if you have a gcp_list.txt but '
'want to use the exif geotags instead'))
parser.add_argument('--dem',
action='store_true',
default=False,
help='Use this tag to build a DEM using a progressive '
'morphological filter in PDAL.')
parser.add_argument('--dem-sample-radius',
metavar='<float>',
default=1.0,
type=float,
help='Minimum distance between samples for DEM '
'generation.\nDefault=%(default)s')
parser.add_argument('--dem-resolution',
metavar='<float>',
type=float,
default=2,
help='Length of raster cell edges in X/Y units.'
'\nDefault: %(default)s')
parser.add_argument('--dem-radius',
metavar='<float>',
type=float,
default=0.5,
help='Radius about cell center bounding points to '
'use to calculate a cell value.\nDefault: '
'%(default)s')
parser.add_argument('--orthophoto-resolution',
metavar='<float > 0.0>',
default=20.0,

Wyświetl plik

@ -143,13 +143,13 @@ class ODM_GeoRef(object):
def coord_to_fractions(self, coord, refs):
deg_dec = abs(float(coord))
deg = int(deg_dec)
minute_dec = (deg_dec-deg)*60
minute_dec = (deg_dec - deg) * 60
minute = int(minute_dec)
sec_dec = (minute_dec-minute)*60
sec_dec = round(sec_dec,3)
sec_dec = (minute_dec - minute) * 60
sec_dec = round(sec_dec, 3)
sec_denominator = 1000
sec_numerator = int(sec_dec*sec_denominator)
sec_numerator = int(sec_dec * sec_denominator)
if float(coord) >= 0:
latRef = refs[0]
else:
@ -158,7 +158,7 @@ class ODM_GeoRef(object):
output = str(deg) + '/1 ' + str(minute) + '/1 ' + str(sec_numerator) + '/' + str(sec_denominator)
return output, latRef
def convert_to_las(self, _file, pdalXML):
def convert_to_las(self, _file, _file_out, json_file):
if not self.epsg:
log.ODM_ERROR('Empty EPSG: Could not convert to LAS')
@ -166,50 +166,82 @@ class ODM_GeoRef(object):
kwargs = {'bin': context.pdal_path,
'f_in': _file,
'f_out': _file + '.las',
'f_out': _file_out,
'east': self.utm_east_offset,
'north': self.utm_north_offset,
'epsg': self.epsg,
'xml': pdalXML}
'json': json_file}
# call txt2las
# system.run('{bin}/txt2las -i {f_in} -o {f_out} -skip 30 -parse xyzRGBssss ' \
# '-set_scale 0.01 0.01 0.01 -set_offset {east} {north} 0 ' \
# '-translate_xyz 0 -epsg {epsg}'.format(**kwargs))
#
# create pipeline file transform.xml to enable transformation
pipelineXml = '<?xml version=\"1.0\" encoding=\"utf-8\"?>'
pipelineXml += '<Pipeline version=\"1.0\">'
pipelineXml += ' <Writer type=\"writers.las\">'
pipelineXml += ' <Option name=\"filename\">'
pipelineXml += ' transformed.las'
pipelineXml += ' </Option>'
pipelineXml += ' <Option name=\"a_srs\">'
pipelineXml += ' EPSG:{epsg}'.format(**kwargs)
pipelineXml += ' </Option>'
pipelineXml += ' <Filter type=\"filters.transformation\">'
pipelineXml += ' <Option name=\"matrix\">'
pipelineXml += ' 1 0 0 {east}'.format(**kwargs)
pipelineXml += ' 0 1 0 {north}'.format(**kwargs)
pipelineXml += ' 0 0 1 0'
pipelineXml += ' 0 0 0 1'
pipelineXml += ' </Option>'
pipelineXml += ' <Reader type=\"readers.ply\">'
pipelineXml += ' <Option name=\"filename\">'
pipelineXml += ' untransformed.ply'
pipelineXml += ' </Option>'
pipelineXml += ' </Reader>'
pipelineXml += ' </Filter>'
pipelineXml += ' </Writer>'
pipelineXml += '</Pipeline>'
pipeline = '{{' \
' "pipeline":[' \
' "untransformed.ply",' \
' {{' \
' "type":"filters.transformation",' \
' "matrix":"1 0 0 {east} 0 1 0 {north} 0 0 1 0 0 0 0 1"' \
' }},' \
' {{' \
' "a_srs":"EPSG:{epsg}",' \
' "forward":"scale",' \
' "filename":"transformed.las"' \
' }}' \
' ]' \
'}}'.format(**kwargs)
with open(pdalXML, 'w') as f:
f.write(pipelineXml)
with open(json_file, 'w') as f:
f.write(pipeline)
# call pdal
system.run('{bin}/pdal pipeline -i {xml} --readers.ply.filename={f_in} '
system.run('{bin}/pdal pipeline -i {json} --readers.ply.filename={f_in} '
'--writers.las.filename={f_out}'.format(**kwargs))
def convert_to_dem(self, _file, _file_out, pdalJSON, sample_radius, gdal_res, gdal_radius):
# Check if exists f_in
if not io.file_exists(_file):
log.ODM_ERROR('LAS file does not exist')
return False
kwargs = {
'bin': context.pdal_path,
'f_in': _file,
'sample_radius': sample_radius,
'gdal_res': gdal_res,
'gdal_radius': gdal_radius,
'f_out': _file_out,
'json': pdalJSON
}
pipelineJSON = '{{' \
' "pipeline":[' \
' "input.las",' \
' {{' \
' "type":"filters.sample",' \
' "radius":"{sample_radius}"' \
' }},' \
' {{' \
' "type":"filters.pmf",' \
' "extract":"true"' \
' }},' \
' {{' \
' "resolution": {gdal_res},' \
' "radius": {gdal_radius},' \
' "output_type":"idw",' \
' "filename":"outputfile.tif"' \
' }}' \
' ]' \
'}}'.format(**kwargs)
with open(pdalJSON, 'w') as f:
f.write(pipelineJSON)
system.run('{bin}/pdal pipeline {json} --readers.las.filename={f_in} '
'--writers.gdal.filename={f_out}'.format(**kwargs))
if io.file_exists(kwargs['f_out']):
return True
else:
return False
def utm_to_latlon(self, _file, _photo, idx):
gcp = self.gcps[idx]
@ -271,7 +303,7 @@ class ODM_GeoRef(object):
metadata[key] = pyexiv2.ExifTag(key, value)
# GPS altitude
altitude = abs(int(float(latlon[2])*100))
altitude = abs(int(float(latlon[2]) * 100))
key = 'Exif.GPSInfo.GPSAltitude'
value = Fraction(altitude, 1)
metadata[key] = pyexiv2.ExifTag(key, value)
@ -301,7 +333,7 @@ class ODM_GeoRef(object):
log.ODM_DEBUG('Line: %s' % line)
ref = line.split(' ')
# match_wgs_utm = re.search('WGS84 UTM (\d{1,2})(N|S)', line, re.I)
if ref[0] == 'WGS84' and ref[1] == 'UTM': # match_wgs_utm:
if ref[0] == 'WGS84' and ref[1] == 'UTM': # match_wgs_utm:
self.datum = ref[0]
self.utm_pole = ref[2][len(ref) - 1]
self.utm_zone = int(ref[2][:len(ref) - 1])
@ -331,6 +363,7 @@ class ODM_GeoRef(object):
x, y = xyz[:2]
z = 0
self.gcps.append(ODM_GCPoint(float(x), float(y), float(z)))
# Write to json file
class ODM_Tree(object):
@ -390,7 +423,7 @@ class ODM_Tree(object):
self.odm_texturing, 'odm_textured_model.obj')
self.odm_textured_model_mtl = io.join_paths(
self.odm_texturing, 'odm_textured_model.mtl')
# Log is only used by old odm_texturing
# Log is only used by old odm_texturing
self.odm_texuring_log = io.join_paths(
self.odm_texturing, 'odm_texturing_log.txt')
@ -415,8 +448,14 @@ class ODM_Tree(object):
self.odm_texturing, 'odm_textured_model_geo.mtl') # these files will be kept in odm_texturing/
self.odm_georeferencing_xyz_file = io.join_paths(
self.odm_georeferencing, 'odm_georeferenced_model.csv')
self.odm_georeferencing_pdal = io.join_paths(
self.odm_georeferencing, 'pipeline.xml')
self.odm_georeferencing_las_json = io.join_paths(
self.odm_georeferencing, 'las.json')
self.odm_georeferencing_model_las = io.join_paths(
self.odm_georeferencing, 'odm_georeferenced_model.las')
self.odm_georeferencing_dem = io.join_paths(
self.odm_georeferencing, 'odm_georeferencing_model_dem.tif')
self.odm_georeferencing_dem_json = io.join_paths(
self.odm_georeferencing, 'dem.json')
# odm_orthophoto
self.odm_orthophoto_file = io.join_paths(self.odm_orthophoto, 'odm_orthophoto.png')

Wyświetl plik

@ -71,6 +71,10 @@ class ODMApp(ecto.BlackBox):
'georeferencing': ODMGeoreferencingCell(img_size=p.args.resize_to,
gcp_file=p.args.gcp,
use_exif=p.args.use_exif,
dem=p.args.dem,
sample_radius=p.args.dem_sample_radius,
gdal_res=p.args.dem_resolution,
gdal_radius=p.args.dem_radius,
verbose=p.args.verbose),
'orthophoto': ODMOrthoPhotoCell(resolution=p.args.orthophoto_resolution,
t_srs=p.args.orthophoto_target_srs,

Wyświetl plik

@ -17,6 +17,10 @@ class ODMGeoreferencingCell(ecto.Cell):
'northing height pixelrow pixelcol imagename', 'gcp_list.txt')
params.declare("img_size", 'image size used in calibration', 2400)
params.declare("use_exif", 'use exif', False)
params.declare("dem", 'Generate a dem', False)
params.declare("sample_radius", "Minimum distance between samples for DEM gen", 3)
params.declare("gdal_res", "Length of raster cell edges in X/Y units ", 2)
params.declare("gdal_radius", "Radius about cell center bounding points to use to calculate a cell value", 0.5)
params.declare("verbose", 'print additional messages to console', False)
def declare_io(self, params, inputs, outputs):
@ -147,10 +151,24 @@ class ODMGeoreferencingCell(ecto.Cell):
# convert ply model to LAS reference system
geo_ref.convert_to_las(tree.odm_georeferencing_model_ply_geo,
tree.odm_georeferencing_pdal)
tree.odm_georeferencing_model_las,
tree.odm_georeferencing_las_json)
# If --dem, create a DEM
if args.dem:
demcreated = geo_ref.convert_to_dem(tree.odm_georeferencing_model_las,
tree.odm_georeferencing_dem,
tree.odm_georeferencing_dem_json,
self.params.sample_radius,
self.params.gdal_res,
self.params.gdal_radius)
if not demcreated:
log.ODM_WARNING('Something went wrong. Check the logs in odm_georeferencing.')
else:
log.ODM_INFO('DEM created at {0}'.format(tree.odm_georeferencing_dem))
# XYZ point cloud output
log.ODM_INFO("Creating geo-referenced CSV file (XYZ format, can be used with GRASS to create DEM)")
log.ODM_INFO("Creating geo-referenced CSV file (XYZ format)")
with open(tree.odm_georeferencing_xyz_file, "wb") as csvfile:
csvfile_writer = csv.writer(csvfile, delimiter=",")
reachedpoints = False

Wyświetl plik

@ -43,6 +43,10 @@ project_path: '' # Example: '/home/user/ODMProjects
#texturing_tone_mapping: 'none'
#gcp: !!null # YAML tag for None
#use_exif: False # Set to True if you have a GCP file (it auto-detects) and want to use EXIF
#dem: False
#dem_sample_radius: 1.0
#dem_resolution: 2
#dem_radius: 0.5
#orthophoto_resolution: 20.0 # Pixels/meter
#orthophoto_target_srs: !!null # Currently does nothing
#orthophoto_no_tiled: False