Commit 8c2c4881 authored by Clément Pinard's avatar Clément Pinard
Browse files

add colmap output filtering

parent ee07a2dc
...@@ -43,7 +43,8 @@ def preprocess_metadata(metadata, proj, centroid): ...@@ -43,7 +43,8 @@ def preprocess_metadata(metadata, proj, centroid):
if metadata["location_valid"].iloc[0] == 0: if metadata["location_valid"].iloc[0] == 0:
end = validity_start.pop(0) end = validity_start.pop(0)
positions[:end] = extrapolate_position(speed[:end], timestamps[:end], None, positions[end-1]) positions[:end] = extrapolate_position(speed[:end], timestamps[:end], None, positions[end])
print(positions[:end], end)
if metadata["location_valid"].iloc[-1] == 0: if metadata["location_valid"].iloc[-1] == 0:
start = invalidity_start.pop(-1) - 1 start = invalidity_start.pop(-1) - 1
positions[start:] = extrapolate_position(speed[start:], timestamps[start:], positions[start], None) positions[start:] = extrapolate_position(speed[start:], timestamps[start:], positions[start], None)
...@@ -52,7 +53,8 @@ def preprocess_metadata(metadata, proj, centroid): ...@@ -52,7 +53,8 @@ def preprocess_metadata(metadata, proj, centroid):
print("error") print("error")
for start, end in zip(invalidity_start, validity_start): for start, end in zip(invalidity_start, validity_start):
positions[start:end] = extrapolate_position(speed[start:end], timestamps[start:end], positions[start], positions[end-1]) positions[start:end] = extrapolate_position(speed[start:end], timestamps[start:end], positions[start], positions[end])
print(positions)
positions -= centroid positions -= centroid
metadata["x"], metadata["y"], metadata["z"] = positions.transpose() metadata["x"], metadata["y"], metadata["z"] = positions.transpose()
......
...@@ -6,8 +6,6 @@ import pandas as pd ...@@ -6,8 +6,6 @@ import pandas as pd
parser = ArgumentParser(description='create a new colmap model with only the frames of selected video', parser = ArgumentParser(description='create a new colmap model with only the frames of selected video',
formatter_class=ArgumentDefaultsHelpFormatter) formatter_class=ArgumentDefaultsHelpFormatter)
parser.add_argument('--video_list', metavar='PATH',
help='path to list with relative path to images', type=Path)
parser.add_argument('--input_model', metavar='DIR', type=Path) parser.add_argument('--input_model', metavar='DIR', type=Path)
parser.add_argument('--output_model', metavar='DIR', default=None, type=Path) parser.add_argument('--output_model', metavar='DIR', default=None, type=Path)
parser.add_argument('--output_format', choices=['.txt', '.bin'], default='.txt') parser.add_argument('--output_format', choices=['.txt', '.bin'], default='.txt')
...@@ -22,9 +20,7 @@ def extract_video(input, output, video_metadata_path, output_format='.bin'): ...@@ -22,9 +20,7 @@ def extract_video(input, output, video_metadata_path, output_format='.bin'):
image_names = video_metadata["image_path"].values image_names = video_metadata["image_path"].values
for id, image in images.items(): for id, image in images.items():
if image.name in image_names: if image.name in image_names:
image._replace(xys=[]) images_per_name[image.name] = image._replace(xys=[], point3D_ids=[])
image._replace(point3D_ids=[])
images_per_name[image.name] = image
camera_ids = video_metadata["camera_id"].unique() camera_ids = video_metadata["camera_id"].unique()
output_cameras = {cid: cameras[cid] for cid in camera_ids if cid in cameras.keys()} output_cameras = {cid: cameras[cid] for cid in camera_ids if cid in cameras.keys()}
......
from colmap_util import read_model as rm
import pandas as pd
import numpy as np
from argparse import ArgumentParser, ArgumentDefaultsHelpFormatter
from path import Path
import matplotlib.pyplot as plt
from scipy.signal import savgol_filter
from scipy.spatial.transform import Rotation, Slerp
parser = ArgumentParser(description='Take all the drone videos of a folder and put the frame '
'location in a COLMAP file for vizualisation',
formatter_class=ArgumentDefaultsHelpFormatter)
parser.add_argument('--colmap_model_folder', metavar='DIR', type=Path)
parser.add_argument('--output_folder_model', metavar='DIR', type=Path)
parser.add_argument('--interpolate', action="store_true")
parser.add_argument('--metadata', metavar='DIR', type=Path)
parser.add_argument('--visualize', action="store_true")
def world_to_colmap(frame_qvec, frame_tvec):
'''
frame_qvec is written in the NED system (north east down)
frame_tvec is already is the world system (east norht up)
'''
world2NED = np.float32([[0, 1, 0],
[1, 0, 0],
[0, 0, -1]])
NED2cam = np.float32([[0, 1, 0],
[0, 0, 1],
[1, 0, 0]])
world2cam = NED2cam @ rm.qvec2rotmat(frame_qvec).T @ world2NED
cam_tvec = - world2cam @ frame_tvec
cam_qvec = rm.rotmat2qvec(world2cam)
return cam_qvec, cam_tvec
'''
def colmap_to_world(tvec, qvec):
if any(np.isnan(qvec)):
return qvec, tvec
cam2world = rm.qvec2rotmat(qvec).T
world_tvec = - cam2world @ tvec
wolrd_qvec = np.array((qvec[0], *qvec[1:]))
return wolrd_qvec, world_tvec
'''
def colmap_to_world(tvec, qvec):
quats = Rotation.from_quat(qvec)
return -quats.apply(tvec, inverse=True)
def NEDtoworld(qvec):
world2NED = np.float32([[0, 1, 0],
[1, 0, 0],
[0, 0, -1]])
NED2world = world2NED
world_qvec = rm.rotmat2qvec(NED2world @ rm.qvec2rotmat(qvec).T @ world2NED)
return world_qvec
def quaternion_distances(prefix="", suffix=""):
def fun(row):
""" Create two Quaternions objects and calculate 3 distances between them """
q1 = np.array((row[['{}q{}{}'.format(prefix, col, suffix) for col in list("wxyz")]]))
q2 = np.array((row[['{}q{}2{}'.format(prefix, col, suffix) for col in list("wxyz")]]))
row['{}qdist{}'.format(prefix, suffix)] = np.arccos(2 * (q1.dot(q2)) ** 2 - 1)
return row
return fun
def get_outliers(series, threshold):
return ((series.diff(-1) > 0) & (series.diff(1) > 0) & (series > threshold)) | series.isnull()
def slerp_quats(quat_df, prefix=""):
valid_df = quat_df[~quat_df["outlier"]]
valid_index = valid_df["time"]
total_index = quat_df["time"]
# Note that scipy uses a different order convention than colmap
quats = Rotation.from_quat(valid_df[["{}q{}".format(prefix, col) for col in list("xyzw")]].values)
slerp = Slerp(valid_index, quats)
quats = slerp(total_index).as_quat()
quats[quats[:, -1] < 0] *= -1
return pd.DataFrame(slerp(total_index).as_quat(), index=quat_df.index)
def filter_colmap_model(input, output, metadata_path,
filter_degree=3, filter_time=0.1,
threshold_t=0.01, threshold_q=5e-3,
visualize=False, **env):
images_dict = rm.read_images_text(input / "images.txt")
metadata = pd.read_csv(metadata_path).set_index("db_id").sort_values("time")
framerate = metadata["framerate"].iloc[0]
filter_length = 2*int(filter_time * framerate) + 1
image_df = pd.DataFrame.from_dict(images_dict, orient="index").set_index("id")
image_df = image_df.reindex(metadata.index)
metadata["outlier"] = image_df.isna().any(axis="columns")
colmap_outliers = sum(metadata["outlier"])
image_df = image_df.dropna()
tvec = np.stack(image_df["tvec"].values)
qvec = np.stack(image_df["qvec"].values)
# Check if quats are flipped by computing shifted dot product.
# If no flip (and continuous orientation), the dot product is around 1. Otherwise, it's around -1
# A quaternion is flipped if the dot product is negative
flips = list((np.sum(qvec[1:] * qvec[:-1], axis=1) < 0).nonzero()[0] + 1)
print(flips)
flips.append(qvec.shape[0])
for j, k in zip(flips[::2], flips[1::2]):
qvec[j:k] *= -1
tvec_columns = ["colmap_tx", "colmap_ty", "colmap_tz"]
quat_columns = ["colmap_qw", "colmap_qx", "colmap_qy", "colmap_qz"]
metadata[tvec_columns] = pd.DataFrame(tvec, index=image_df.index)
metadata[quat_columns] = pd.DataFrame(qvec, index=image_df.index)
# Interpolate missing values for tvec and quat
metadata[tvec_columns] = metadata[tvec_columns].interpolate()
metadata[["colmap_qx", "colmap_qy", "colmap_qz", "colmap_qw"]] = slerp_quats(metadata, prefix="colmap_")
if visualize:
metadata[["colmap_qw", "colmap_qx", "colmap_qy", "colmap_qz"]].plot()
plt.gcf().canvas.set_window_title('Colmap quaternion (continuous)')
qvec = metadata[["colmap_qx", "colmap_qy", "colmap_qz", "colmap_qw"]].values
tvec = metadata[["colmap_tx", "colmap_ty", "colmap_tz"]].values
world_tvec = colmap_to_world(tvec, qvec)
world_tvec_filtered = savgol_filter(world_tvec, filter_length, filter_degree, axis=0)
# TODO : this is linear filtering with renormalization,
# mostly good enough but ideally should be something with slerp for quaternions
qvec_filtered = savgol_filter(qvec, filter_length, filter_degree, axis=0)
qvec_filtered = qvec_filtered / (np.linalg.norm(qvec_filtered, axis=-1, keepdims=True) + 1e-10)
# Distances from raw and filtered values, we will dismiss those that are too far
metadata["outlier_rot"] = np.arccos(2 * (np.sum(qvec * qvec_filtered, axis=1)) ** 2 - 1)
metadata["outliers_pos"] = np.linalg.norm(world_tvec - world_tvec_filtered, axis=1)
if visualize:
metadata[["outliers_pos"]].plot()
plt.gcf().canvas.set_window_title('difference between speed from colmap and from filtered')
metadata[["outlier_rot"]].plot()
plt.gcf().canvas.set_window_title('difference between rot speed from colmap and from filtered')
metadata["tx"] = world_tvec[:, 0]
metadata["ty"] = world_tvec[:, 1]
metadata["tz"] = world_tvec[:, 2]
metadata["qx"] = qvec[:, 0]
metadata["qy"] = qvec[:, 1]
metadata["qz"] = qvec[:, 2]
metadata["qw"] = qvec[:, 3]
if visualize:
frame_q = metadata[["frame_quat_w", "frame_quat_x", "frame_quat_y", "frame_quat_z"]].values
qref_list = []
for q in frame_q:
qref_list.append(NEDtoworld(q))
qref = np.stack(qref_list)
metadata["ref_qw"] = qref[:, 0]
metadata["ref_qx"] = qref[:, 1]
metadata["ref_qy"] = qref[:, 2]
metadata["ref_qz"] = qref[:, 3]
metadata["qw_filtered"] = qvec_filtered[:, 0]
metadata["qx_filtered"] = qvec_filtered[:, 1]
metadata["qy_filtered"] = qvec_filtered[:, 2]
metadata["qz_filtered"] = qvec_filtered[:, 3]
metadata["speed_up"] = -metadata["speed_down"]
metadata[["speed_east", "speed_north", "speed_up"]].plot()
plt.gcf().canvas.set_window_title('speed from sensors')
colmap_speeds = framerate * metadata[["tx", "ty", "tz"]].diff()
colmap_speeds.plot()
plt.gcf().canvas.set_window_title('speeds from colmap (noisy)')
metadata[["x", "y", "z", "tx", "ty", "tz"]].plot()
plt.gcf().canvas.set_window_title('GPS(xyz) vs colmap position (tx,ty,tz')
metadata[["ref_qw", "ref_qx", "ref_qy", "ref_qz"]].plot()
plt.gcf().canvas.set_window_title('quaternions from sensor')
metadata["outlier"] = metadata["outlier"] | \
get_outliers(metadata["outliers_pos"], threshold_t) | \
get_outliers(metadata["outlier_rot"], threshold_q)
metadata.loc[metadata["outlier"], ["tx", "ty", "tz", "qw", "qx", "qy", "qz"]] = np.NaN
world_tvec_interp = metadata[["tx", "ty", "tz"]].interpolate().values
world_qvec_interp = slerp_quats(metadata).values
world_tvec_smoothed = savgol_filter(world_tvec_interp, filter_length, filter_degree, axis=0)
qvec_smoothed = savgol_filter(world_qvec_interp, filter_length, filter_degree, axis=0)
qvec_smoothed /= np.linalg.norm(qvec_smoothed, axis=1, keepdims=True)
metadata["tx_smoothed"] = world_tvec_smoothed[:, 0]
metadata["ty_smoothed"] = world_tvec_smoothed[:, 1]
metadata["tz_smoothed"] = world_tvec_smoothed[:, 2]
metadata["qx_smoothed"] = qvec_smoothed[:, 0]
metadata["qy_smoothed"] = qvec_smoothed[:, 1]
metadata["qz_smoothed"] = qvec_smoothed[:, 2]
metadata["qw_smoothed"] = qvec_smoothed[:, 3]
if visualize:
metadata[["tx_smoothed", "ty_smoothed", "tz_smoothed"]].diff().plot()
plt.gcf().canvas.set_window_title('speed from filtered and smoothed')
metadata[["qw", "qx", "qy", "qz",
"qw_smoothed", "qx_smoothed", "qy_smoothed", "qz_smoothed"]].plot()
plt.gcf().canvas.set_window_title('quaternions from colmap vs from smoothed')
metadata[["colmap_q{}2".format(col) for col in list('wxyz')]] = metadata[['colmap_qw',
'colmap_qx',
'colmap_qy',
'colmap_qz']].shift()
metadata[["q{}2_filtered".format(col) for col in list('wxyz')]] = metadata[['qw_filtered',
'qx_filtered',
'qy_filtered',
'qz_filtered']].shift()
metadata[["q{}2_smoothed".format(col) for col in list('wxyz')]] = metadata[['qw_smoothed',
'qx_smoothed',
'qy_smoothed',
'qz_smoothed']].shift()
metadata = metadata.apply(quaternion_distances(prefix="colmap_"), axis='columns')
metadata = metadata.apply(quaternion_distances(suffix="_filtered"), axis='columns')
metadata = metadata.apply(quaternion_distances(suffix="_smoothed"), axis='columns')
metadata[["colmap_qdist", "qdist_filtered", "qdist_smoothed"]].plot()
plt.gcf().canvas.set_window_title('GPS(xyz) vs colmap position')
metadata[["outlier"]].astype(float).plot()
plt.gcf().canvas.set_window_title('outliers indices')
print("number of not localized by colmap : {}/{} ({:.2f}%)".format(colmap_outliers,
len(metadata),
100 * colmap_outliers/len(metadata)))
print("Total number of outliers : {} / {} ({:.2f}%)".format(sum(metadata["outlier"]),
len(metadata),
100 * sum(metadata["outlier"])/len(metadata)))
if visualize:
plt.show()
smoothed_images_dict = {}
for db_id, row in metadata.iterrows():
smoothed_images_dict[db_id] = rm.Image(id=db_id,
qvec=row[["qw_smoothed", "qx_smoothed", "qy_smoothed", "qz_smoothed"]].values,
tvec=row[["tx_smoothed", "ty_smoothed", "tz_smoothed"]].values,
camera_id=row["camera_id"],
name=row["image_path"],
xys=[], point3D_ids=[])
rm.write_images_text(smoothed_images_dict, output / "images.txt")
if __name__ == '__main__':
args = parser.parse_args()
env = vars(args)
filter_colmap_model(input=args.colmap_model_folder, output=args.output_folder_model, metadata_path=args.metadata, **env)
...@@ -144,7 +144,7 @@ def prepare_video_workspace(video_name, video_frames_folder, output_folder, vide ...@@ -144,7 +144,7 @@ def prepare_video_workspace(video_name, video_frames_folder, output_folder, vide
output["final_model"] = output["model_folder"] / "final" output["final_model"] = output["model_folder"] / "final"
output["video_fps"] = pd.read_csv(video_env["metadata"])["framerate"].values[0] output["video_fps"] = pd.read_csv(video_env["metadata"])["framerate"].values[0]
video_env["output_env"] = output video_env["output_env"] = output
video_env["already_localized"] = env["resume_work"] and output["images_folder"].isdir() video_env["already_localized"] = env["resume_work"] and output["model_folder"].isdir()
video_env["GT_already_done"] = env["resume_work"] and (output_folder / "groundtruth_depth" / video_name.namebase).isdir() video_env["GT_already_done"] = env["resume_work"] and (output_folder / "groundtruth_depth" / video_name.namebase).isdir()
return video_env return video_env
...@@ -165,16 +165,16 @@ def main(): ...@@ -165,16 +165,16 @@ def main():
image_path=env["image_path"], image_path=env["image_path"],
mask_path=env["mask_path"], mask_path=env["mask_path"],
binary=args.colmap, binary=args.colmap,
quiet=args.verbose < 1, verbose=args.verbose,
logfile=args.log) logfile=args.log)
env["colmap"] = colmap env["colmap"] = colmap
ffmpeg = FFMpeg(args.ffmpeg, quiet=args.verbose < 2, logfile=args.log) ffmpeg = FFMpeg(args.ffmpeg, verbose=args.verbose, logfile=args.log)
env["ffmpeg"] = ffmpeg env["ffmpeg"] = ffmpeg
pdraw = PDraw(args.nw, quiet=args.verbose < 2, logfile=args.log) pdraw = PDraw(args.nw, verbose=args.verbose, logfile=args.log)
env["pdraw"] = pdraw env["pdraw"] = pdraw
eth3d = ETH3D(args.eth3d, args.output_folder / "Images", quiet=args.verbose < 1, logfile=args.log) eth3d = ETH3D(args.eth3d, args.output_folder / "Images", verbose=args.verbose, logfile=args.log)
env["eth3d"] = eth3d env["eth3d"] = eth3d
pcl_util = PCLUtil(args.pcl_util, quiet=args.verbose < 2, logfile=args.log) pcl_util = PCLUtil(args.pcl_util, verbose=args.verbose, logfile=args.log)
env["pcl_util"] = pcl_util env["pcl_util"] = pcl_util
las_files = (args.input_folder/"Lidar").files("*.las") las_files = (args.input_folder/"Lidar").files("*.las")
......
...@@ -21,7 +21,6 @@ parser.add_argument('--video_folder', metavar='DIR', ...@@ -21,7 +21,6 @@ parser.add_argument('--video_folder', metavar='DIR',
parser.add_argument('--system', default='epsg:2154') parser.add_argument('--system', default='epsg:2154')
parser.add_argument('--centroid_path', default=None) parser.add_argument('--centroid_path', default=None)
parser.add_argument('--output_folder', metavar='DIR', type=Path) parser.add_argument('--output_folder', metavar='DIR', type=Path)
parser.add_argument('--workspace', metavar='DIR', type=Path)
parser.add_argument('--image_path', metavar='DIR', type=Path) parser.add_argument('--image_path', metavar='DIR', type=Path)
parser.add_argument('--output_format', metavar='EXT', default="bin") parser.add_argument('--output_format', metavar='EXT', default="bin")
parser.add_argument('--vid_ext', nargs='+', default=[".mp4", ".MP4"]) parser.add_argument('--vid_ext', nargs='+', default=[".mp4", ".MP4"])
...@@ -33,8 +32,9 @@ parser.add_argument('--fps', default=1, type=int, ...@@ -33,8 +32,9 @@ parser.add_argument('--fps', default=1, type=int,
parser.add_argument('--total_frames', default=200, type=int) parser.add_argument('--total_frames', default=200, type=int)
parser.add_argument('--orientation_weight', default=1, type=float) parser.add_argument('--orientation_weight', default=1, type=float)
parser.add_argument('--resolution_weight', default=1, type=float) parser.add_argument('--resolution_weight', default=1, type=float)
parser.add_argument('--num_neighbours', default=10, type=int)
parser.add_argument('--save_space', action="store_true") parser.add_argument('--save_space', action="store_true")
parser.add_argument('--thorough_db', type=Path)
parser.add_argument('-v', '--verbose', action="count", default=0)
def world_coord_from_frame(frame_qvec, frame_tvec): def world_coord_from_frame(frame_qvec, frame_tvec):
...@@ -121,7 +121,7 @@ def register_new_cameras(cameras_dataframe, database, camera_dict, model_name="P ...@@ -121,7 +121,7 @@ def register_new_cameras(cameras_dataframe, database, camera_dict, model_name="P
def process_video_folder(videos_list, existing_pictures, output_video_folder, image_path, system, centroid, def process_video_folder(videos_list, existing_pictures, output_video_folder, image_path, system, centroid,
thorough_db, workspace, fps=1, total_frames=500, orientation_weight=1, resolution_weight=1, thorough_db, fps=1, total_frames=500, orientation_weight=1, resolution_weight=1,
output_colmap_format="bin", save_space=False, max_sequence_length=1000, **env): output_colmap_format="bin", save_space=False, max_sequence_length=1000, **env):
proj = Proj(system) proj = Proj(system)
indoor_videos = [] indoor_videos = []
...@@ -130,6 +130,8 @@ def process_video_folder(videos_list, existing_pictures, output_video_folder, im ...@@ -130,6 +130,8 @@ def process_video_folder(videos_list, existing_pictures, output_video_folder, im
images = {} images = {}
colmap_cameras = {} colmap_cameras = {}
tempfile_database = Path(tempfile.NamedTemporaryFile().name) tempfile_database = Path(tempfile.NamedTemporaryFile().name)
if thorough_db.isfile():
thorough_db.copy(thorough_db.stripext() + "_backup.db")
path_lists_output = {} path_lists_output = {}
database = db.COLMAPDatabase.connect(thorough_db) database = db.COLMAPDatabase.connect(thorough_db)
database.create_tables() database.create_tables()
...@@ -238,9 +240,11 @@ def process_video_folder(videos_list, existing_pictures, output_video_folder, im ...@@ -238,9 +240,11 @@ def process_video_folder(videos_list, existing_pictures, output_video_folder, im
path_lists_output[v]["frames_lowfps"] = frame_paths path_lists_output[v]["frames_lowfps"] = frame_paths
path_lists_output[v]["georef_lowfps"] = georef path_lists_output[v]["georef_lowfps"] = georef
num_chunks = len(video_metadata) // max_sequence_length + 1 num_chunks = len(video_metadata) // max_sequence_length + 1
path_lists_output[v]["frames_full"] = [list(frames) for frames in np.array_split(video_metadata["image_path"], num_chunks)] path_lists_output[v]["frames_full"] = [list(frames) for frames in np.array_split(video_metadata["image_path"],
num_chunks)]
if save_space: if save_space:
frame_ids = list(video_metadata[video_metadata["sampled"]]["frame"].values) frame_ids = set(video_metadata[video_metadata["sampled"]]["frame"].values) | \
set(video_metadata_1fps["frame"].values)
if len(frame_ids) > 0: if len(frame_ids) > 0:
extracted_frames = env["ffmpeg"].extract_specific_frames(v, video_folder, frame_ids) extracted_frames = env["ffmpeg"].extract_specific_frames(v, video_folder, frame_ids)
else: else:
...@@ -254,14 +258,14 @@ if __name__ == '__main__': ...@@ -254,14 +258,14 @@ if __name__ == '__main__':
args = parser.parse_args() args = parser.parse_args()
env = vars(args) env = vars(args)
env["videos_list"] = sum((list(args.video_folder.walkfiles('*{}'.format(ext))) for ext in args.vid_ext), []) env["videos_list"] = sum((list(args.video_folder.walkfiles('*{}'.format(ext))) for ext in args.vid_ext), [])
args.workspace.makedirs_p()
output_video_folder = args.output_folder / "Videos" output_video_folder = args.output_folder / "Videos"
output_video_folder.makedirs_p() output_video_folder.makedirs_p()
env["image_path"] = args.output_folder env["image_path"] = args.output_folder
env["output_video_folder"] = output_video_folder env["output_video_folder"] = output_video_folder
env["existing_pictures"] = sum((list(args.output_folder.walkfiles('*{}'.format(ext))) for ext in args.pic_ext), []) env["existing_pictures"] = sum((list(args.output_folder.walkfiles('*{}'.format(ext))) for ext in args.pic_ext), [])
env["pdraw"] = PDraw(args.nw, quiet=True) env["pdraw"] = PDraw(args.nw, verbose=args.verbose)
env["ffmpeg"] = FFMpeg(quiet=True) env["ffmpeg"] = FFMpeg(verbose=args.verbose)
env["output_colmap_format"] = args.output_format
if args.centroid_path is not None: if args.centroid_path is not None:
centroid = np.loadtxt(args.centroid_path) centroid = np.loadtxt(args.centroid_path)
...@@ -272,9 +276,16 @@ if __name__ == '__main__': ...@@ -272,9 +276,16 @@ if __name__ == '__main__':
if lists is not None: if lists is not None:
with open(args.output_folder/"video_frames_for_thorough_scan.txt", "w") as f: with open(args.output_folder/"video_frames_for_thorough_scan.txt", "w") as f:
f.write("\n".join(lists["thorough"])) f.write("\n".join(lists["thorough"]["frames"]))
with open(args.output_folder/"georef.txt", "w") as f: with open(args.output_folder/"georef.txt", "w") as f:
f.write("\n".join(lists["georef"])) f.write("\n".join(lists["thorough"]["georef"]))
for v in env["videos_list"]: for v in env["videos_list"]:
with open(extracted_video_folders[v] / "to_scan.txt", "w") as f: video_folder = extracted_video_folders[v]
f.write("\n".join(lists[v])) with open(video_folder / "lowfps.txt", "w") as f:
f.write("\n".join(lists[v]["frames_lowfps"]) + "\n")
with open(video_folder / "georef.txt", "w") as f:
f.write("\n".join(lists["thorough"]["georef"]) + "\n")
f.write("\n".join(lists[v]["georef_lowfps"]) + "\n")
for j, l in enumerate(lists[v]["frames_full"]):
with open(video_folder / "full_chunk_{}.txt".format(j), "w") as f:
f.write("\n".join(l) + "\n")
...@@ -4,8 +4,8 @@ from .default_wrapper import Wrapper ...@@ -4,8 +4,8 @@ from .default_wrapper import Wrapper
class Colmap(Wrapper): class Colmap(Wrapper):
"""docstring for Colmap""" """docstring for Colmap"""
def __init__(self, db, image_path, mask_path, binary="colmap", logfile=None, quiet=False): def __init__(self, db, image_path, mask_path, *args, **kwargs):
super().__init__(binary, quiet, logfile) super().__init__(*args, **kwargs)
self.db = db self.db = db
self.image_path = image_path self.image_path = image_path
self.mask_path = mask_path self.mask_path = mask_path
...@@ -24,7 +24,8 @@ class Colmap(Wrapper): ...@@ -24,7 +24,8 @@ class Colmap(Wrapper):
else: else:
# See issue https://github.com/colmap/colmap/issues/627 # See issue https://github.com/colmap/colmap/issues/627
# If COLMAP is updated to work better on newest driver, this should be removed # If COLMAP is updated to work better on newest driver, this should be removed
options += ["--SiftExtraction.use_gpu", "0"] # options += ["--SiftExtraction.use_gpu", "0"]
pass
self.__call__(options) self.__call__(options)
def match(self, method="exhaustive", guided_matching=True, vocab_tree=None): def match(self, method="exhaustive", guided_matching=True, vocab_tree=None):
......
...@@ -3,10 +3,10 @@ from subprocess import check_call, STDOUT ...@@ -3,10 +3,10 @@ from subprocess import check_call, STDOUT
class Wrapper: class Wrapper:
def __init__(self, binary, quiet=False, logfile=None): def __init__(self, binary, verbose=2, logfile=None):
self.binary = binary self.binary = binary
self.quiet = quiet
self.logfile = logfile self.logfile = logfile
self.verbose = verbose
def tofile(self, command, file): def tofile(self, command, file):
with open(file, 'a') as f: with open(file, 'a') as f:
...@@ -14,12 +14,12 @@ class Wrapper: ...@@ -14,12 +14,12 @@ class Wrapper:
def __call__(self, options): def __call__(self, options):
command = [self.binary, *options] command = [self.binary, *options]
if not self.quiet: if self.verbose > 0:
print("Calling command") print("Calling command")
print(" ".join(command)) print(" ".join(command))
if self.logfile is not None: if self.logfile is not None:
self.tofile(command, self.logfile) self.tofile(command, self.logfile)
elif self.quiet: elif self.verbose < 2:
self.tofile(command, devnull) self.tofile(command, devnull)
else: else:
check_call(command) check_call(command)
...@@ -4,8 +4,8 @@ from .default_wrapper import Wrapper ...@@ -4,8 +4,8 @@ from .default_wrapper import Wrapper
class ETH3D(Wrapper): class ETH3D(Wrapper):
"""docstring for Colmap""" """docstring for Colmap"""
def __init__(self, build_folder, image_path, logfile=None, quiet=False): def __init__(self, build_folder, image_path, *args, **kwargs):
super().__init__(None, quiet, logfile) super().__init__(None, *args, **kwargs)
self.build_folder = build_folder self.build_folder = build_folder
self.image_path = image_path self.image_path = image_path
...@@ -50,7 +50,7 @@ class ETH3D(Wrapper): ...@@ -50,7 +50,7 @@ class ETH3D(Wrapper):
"--compress_depth_maps", "1"]