kopia lustrzana https://github.com/OpenDroneMap/ODM
Add support for image geolocation files
rodzic
790088249f
commit
ffa63c74d6
|
@ -75,9 +75,9 @@ See http://docs.opendronemap.org for tutorials and more guides.
|
|||
|
||||
We have a vibrant [community forum](https://community.opendronemap.org/). You can [search it](https://community.opendronemap.org/search?expanded=true) for issues you might be having with ODM and you can post questions there. We encourage users of ODM to partecipate in the forum and to engage with fellow drone mapping users.
|
||||
|
||||
## Native Install (Ubuntu 16.04)
|
||||
## Native Install (Ubuntu 18.04)
|
||||
|
||||
You can run ODM natively on Ubuntu 16.04 LTS (although we don't recommend it):
|
||||
You can run ODM natively on Ubuntu 18.04 LTS (although we don't recommend it):
|
||||
|
||||
1. Download the source from [here](https://github.com/OpenDroneMap/ODM/archive/master.zip)
|
||||
2. Run `bash configure.sh install`
|
||||
|
|
|
@ -522,11 +522,23 @@ def config(argv=None):
|
|||
metavar='<path string>',
|
||||
action=StoreValue,
|
||||
default=None,
|
||||
help=('path to the file containing the ground control '
|
||||
help=('Path to the file containing the ground control '
|
||||
'points used for georeferencing. Default: '
|
||||
'%(default)s. The file needs to '
|
||||
'be on the following line format: \neasting '
|
||||
'northing height pixelrow pixelcol imagename'))
|
||||
'use the following format: \n'
|
||||
'EPSG:<code> or <+proj definition>\n'
|
||||
'geo_x geo_y geo_z im_x im_y image_name [gcp_name] [extra1] [extra2]'))
|
||||
|
||||
parser.add_argument('--geo',
|
||||
metavar='<path string>',
|
||||
action=StoreValue,
|
||||
default=None,
|
||||
help=('Path to the image geolocation file containing the camera center coordinates used for georeferencing. Default: '
|
||||
'%(default)s. The file needs to '
|
||||
'use the following format: \n'
|
||||
'EPSG:<code> or <+proj definition>\n'
|
||||
'image_name geo_x geo_y geo_z [omega (degrees)] [phi (degrees)] [kappa (degrees)] [horz (meters)] [vert accuracy (meters)]'
|
||||
''))
|
||||
|
||||
parser.add_argument('--use-exif',
|
||||
action=StoreTrue,
|
||||
|
|
|
@ -0,0 +1,80 @@
|
|||
import os
|
||||
from opendm import log
|
||||
from opendm import location
|
||||
from pyproj import CRS
|
||||
|
||||
class GeoFile:
|
||||
def __init__(self, geo_path):
|
||||
self.geo_path = geo_path
|
||||
self.entries = {}
|
||||
self.srs = None
|
||||
|
||||
with open(self.geo_path, 'r') as f:
|
||||
contents = f.read().strip()
|
||||
|
||||
lines = list(map(str.strip, contents.split('\n')))
|
||||
if lines:
|
||||
self.raw_srs = lines[0] # SRS
|
||||
self.srs = location.parse_srs_header(self.raw_srs)
|
||||
longlat = CRS.from_epsg("4326")
|
||||
|
||||
for line in lines[1:]:
|
||||
if line != "" and line[0] != "#":
|
||||
parts = line.split()
|
||||
if len(parts) >= 3:
|
||||
i = 3
|
||||
filename = parts[0]
|
||||
x, y = [float(p) for p in parts[1:3]]
|
||||
z = float(parts[3]) if len(parts) >= 4 else None
|
||||
|
||||
# Always convert coordinates to WGS84
|
||||
if z is not None:
|
||||
x, y, z = location.transform3(self.srs, longlat, x, y, z)
|
||||
else:
|
||||
x, y = location.transform2(self.srs, longlat, x, y)
|
||||
|
||||
omega = phi = kappa = None
|
||||
|
||||
if len(parts) >= 7:
|
||||
omega, phi, kappa = [float(p) for p in parts[4:7]]
|
||||
i = 7
|
||||
|
||||
horizontal_accuracy = vertical_accuracy = None
|
||||
if len(parts) >= 9:
|
||||
horizontal_accuracy,vertical_accuracy = [float(p) for p in parts[7:9]]
|
||||
i = 9
|
||||
|
||||
extras = " ".join(parts[i:])
|
||||
self.entries[filename] = GeoEntry(filename, x, y, z,
|
||||
omega, phi, kappa,
|
||||
horizontal_accuracy, vertical_accuracy,
|
||||
extras)
|
||||
else:
|
||||
logger.warning("Malformed geo line: %s" % line)
|
||||
|
||||
def get_entry(self, filename):
|
||||
return self.entries.get(filename)
|
||||
|
||||
|
||||
class GeoEntry:
|
||||
def __init__(self, filename, x, y, z, omega=None, phi=None, kappa=None, horizontal_accuracy=None, vertical_accuracy=None, extras=None):
|
||||
self.filename = filename
|
||||
self.x = x
|
||||
self.y = y
|
||||
self.z = z
|
||||
self.omega = omega
|
||||
self.phi = phi
|
||||
self.kappa = kappa
|
||||
self.horizontal_accuracy = horizontal_accuracy
|
||||
self.vertical_accuracy = vertical_accuracy
|
||||
self.extras = extras
|
||||
|
||||
def __str__(self):
|
||||
return "{} ({} {} {}) ({} {} {}) ({} {}) {}".format(self.filename,
|
||||
self.x, self.y, self.z,
|
||||
self.omega, self.phi, self.kappa,
|
||||
self.horizontal_accuracy, self.vertical_accuracy,
|
||||
self.extras).rstrip()
|
||||
|
||||
def position_string(self):
|
||||
return "{} {} {}".format(self.x, self.y, self.z)
|
|
@ -20,7 +20,7 @@ def extract_utm_coords(photos, images_path, output_coords_file):
|
|||
coords = []
|
||||
reference_photo = None
|
||||
for photo in photos:
|
||||
if photo.latitude is None or photo.longitude is None or photo.altitude is None:
|
||||
if photo.latitude is None or photo.longitude is None:
|
||||
log.ODM_ERROR("Failed parsing GPS position for %s, skipping" % photo.filename)
|
||||
continue
|
||||
|
||||
|
@ -28,7 +28,8 @@ def extract_utm_coords(photos, images_path, output_coords_file):
|
|||
utm_zone, hemisphere = get_utm_zone_and_hemisphere_from(photo.longitude, photo.latitude)
|
||||
|
||||
try:
|
||||
coord = convert_to_utm(photo.longitude, photo.latitude, photo.altitude, utm_zone, hemisphere)
|
||||
alt = photo.altitude if photo.altitude is not None else 0
|
||||
coord = convert_to_utm(photo.longitude, photo.latitude, alt, utm_zone, hemisphere)
|
||||
except:
|
||||
raise Exception("Failed to convert GPS position to UTM for %s" % photo.filename)
|
||||
|
||||
|
|
|
@ -103,33 +103,32 @@ class OSFMContext:
|
|||
use_bow = True
|
||||
|
||||
# GPSDOP override if we have GPS accuracy information (such as RTK)
|
||||
override_gps_dop = 'gps_accuracy_is_set' in args
|
||||
for p in photos:
|
||||
if p.get_gps_dop() is not None:
|
||||
override_gps_dop = True
|
||||
break
|
||||
if 'gps_accuracy_is_set' in args:
|
||||
log.ODM_INFO("Forcing GPS DOP to %s for all images" % args.gps_accuracy)
|
||||
|
||||
if override_gps_dop:
|
||||
log.ODM_INFO("Writing exif overrides")
|
||||
|
||||
exif_overrides = {}
|
||||
for p in photos:
|
||||
if 'gps_accuracy_is_set' in args:
|
||||
log.ODM_INFO("Forcing GPS DOP to %s for all images" % args.gps_accuracy)
|
||||
dop = args.gps_accuracy
|
||||
elif p.get_gps_dop() is not None:
|
||||
dop = p.get_gps_dop()
|
||||
else:
|
||||
log.ODM_INFO("Looks like we have RTK accuracy info for some photos. Good! We'll use it.")
|
||||
dop = args.gps_accuracy # default value
|
||||
|
||||
exif_overrides = {}
|
||||
for p in photos:
|
||||
dop = args.gps_accuracy if 'gps_accuracy_is_set' in args else p.get_gps_dop()
|
||||
if dop is not None and p.latitude is not None and p.longitude is not None:
|
||||
exif_overrides[p.filename] = {
|
||||
'gps': {
|
||||
'latitude': p.latitude,
|
||||
'longitude': p.longitude,
|
||||
'altitude': p.altitude if p.altitude is not None else 0,
|
||||
'dop': dop,
|
||||
}
|
||||
if p.latitude is not None and p.longitude is not None:
|
||||
exif_overrides[p.filename] = {
|
||||
'gps': {
|
||||
'latitude': p.latitude,
|
||||
'longitude': p.longitude,
|
||||
'altitude': p.altitude if p.altitude is not None else 0,
|
||||
'dop': dop,
|
||||
}
|
||||
}
|
||||
|
||||
with open(os.path.join(self.opensfm_project_path, "exif_overrides.json"), 'w') as f:
|
||||
f.write(json.dumps(exif_overrides))
|
||||
with open(os.path.join(self.opensfm_project_path, "exif_overrides.json"), 'w') as f:
|
||||
f.write(json.dumps(exif_overrides))
|
||||
|
||||
# Compute feature_process_size
|
||||
feature_process_size = 2048 # default
|
||||
|
|
|
@ -75,6 +75,13 @@ class ODM_Photo:
|
|||
self.filename, self.camera_make, self.camera_model, self.width, self.height,
|
||||
self.latitude, self.longitude, self.altitude, self.band_name, self.band_index)
|
||||
|
||||
def update_with_geo_entry(self, geo_entry):
|
||||
self.latitude = geo_entry.y
|
||||
self.longitude = geo_entry.x
|
||||
self.altitude = geo_entry.z
|
||||
self.gps_xy_stddev = geo_entry.horizontal_accuracy
|
||||
self.gps_z_stddev = geo_entry.vertical_accuracy
|
||||
|
||||
def parse_exif_values(self, _path_file):
|
||||
# Disable exifread log
|
||||
logging.getLogger('exifread').setLevel(logging.CRITICAL)
|
||||
|
|
|
@ -22,6 +22,7 @@ class ODM_Reconstruction(object):
|
|||
self.photos = photos
|
||||
self.georef = None
|
||||
self.gcp = None
|
||||
self.geo_file = None
|
||||
self.multi_camera = self.detect_multi_camera()
|
||||
|
||||
def detect_multi_camera(self):
|
||||
|
@ -200,7 +201,7 @@ class ODM_GeoRef(object):
|
|||
|
||||
|
||||
class ODM_Tree(object):
|
||||
def __init__(self, root_path, gcp_file = None):
|
||||
def __init__(self, root_path, gcp_file = None, geo_file = None):
|
||||
# root path to the project
|
||||
self.root_path = io.absolute_path_file(root_path)
|
||||
self.input_images = io.join_paths(self.root_path, 'images')
|
||||
|
@ -265,6 +266,8 @@ class ODM_Tree(object):
|
|||
self.odm_georeferencing, 'coords.txt')
|
||||
self.odm_georeferencing_gcp = gcp_file or io.find('gcp_list.txt', self.root_path)
|
||||
self.odm_georeferencing_gcp_utm = io.join_paths(self.odm_georeferencing, 'gcp_list_utm.txt')
|
||||
self.odm_geo_file = geo_file or io.find('geo.txt', self.root_path)
|
||||
|
||||
self.odm_georeferencing_utm_log = io.join_paths(
|
||||
self.odm_georeferencing, 'odm_georeferencing_utm_log.txt')
|
||||
self.odm_georeferencing_log = 'odm_georeferencing_log.txt'
|
||||
|
|
|
@ -6,6 +6,7 @@ from opendm import io
|
|||
from opendm import types
|
||||
from opendm import log
|
||||
from opendm import system
|
||||
from opendm.geo import GeoFile
|
||||
from shutil import copyfile
|
||||
from opendm import progress
|
||||
|
||||
|
@ -39,7 +40,7 @@ def load_images_database(database_file):
|
|||
|
||||
class ODMLoadDatasetStage(types.ODM_Stage):
|
||||
def process(self, args, outputs):
|
||||
tree = types.ODM_Tree(args.project_path, args.gcp)
|
||||
tree = types.ODM_Tree(args.project_path, args.gcp, args.geo)
|
||||
outputs['tree'] = tree
|
||||
|
||||
if args.time and io.file_exists(tree.benchmarking):
|
||||
|
@ -89,6 +90,18 @@ class ODMLoadDatasetStage(types.ODM_Stage):
|
|||
photos += [types.ODM_Photo(f)]
|
||||
dataset_list.write(photos[-1].filename + '\n')
|
||||
|
||||
# Check if a geo file is available
|
||||
if os.path.exists(tree.odm_geo_file):
|
||||
log.ODM_INFO("Found image geolocation file")
|
||||
gf = GeoFile(tree.odm_geo_file)
|
||||
updated = 0
|
||||
for p in photos:
|
||||
entry = gf.get_entry(p.filename)
|
||||
if entry:
|
||||
p.update_with_geo_entry(entry)
|
||||
updated += 1
|
||||
log.ODM_INFO("Updated %s image positions" % updated)
|
||||
|
||||
# Save image database for faster restart
|
||||
save_images_database(photos, images_database_file)
|
||||
else:
|
||||
|
|
Ładowanie…
Reference in New Issue