From a82717fa2ea95029c78a87fff00b5bada09b6a4a Mon Sep 17 00:00:00 2001 From: Adam Romlein Date: Thu, 19 Dec 2024 20:25:28 -0500 Subject: [PATCH 01/20] Add simple keypoint matching web page --- .../keypoint_server/key_point_server.py | 81 ++++ .../scripts/keypoint_server/keypoint.tpl | 357 ++++++++++++++++++ 2 files changed, 438 insertions(+) create mode 100644 kamera/postflight/scripts/keypoint_server/key_point_server.py create mode 100644 kamera/postflight/scripts/keypoint_server/keypoint.tpl diff --git a/kamera/postflight/scripts/keypoint_server/key_point_server.py b/kamera/postflight/scripts/keypoint_server/key_point_server.py new file mode 100644 index 0000000..014512e --- /dev/null +++ b/kamera/postflight/scripts/keypoint_server/key_point_server.py @@ -0,0 +1,81 @@ +from bottle import route, template, run, static_file, request, BaseRequest +import os +import argparse + +BaseRequest.MEMFILE_MAX = 6 * 1024 * 1024 + +image_dir = "" +right_img_file = "kamera_calibration_fl09_L_20240612_204629.686820_ir.png" +left_img_file = "kamera_calibration_fl09_L_20240612_204629.686820_rgb.jpg" + + +@route("/") +def index(): + return template("keypoint.tpl") + + +@route("/image-dir", method="POST") +def set_image_dir(): + global image_dir + + json = request.json + image_dir = json["image-dir"] + print(f"Set img dir to '{image_dir}'") + + +@route("/right-img-file", method="POST") +def set_right_img_file(): + global right_img_file + json = request.json + right_img_file = json["right-img-file"] + print(f"Set right img file to '{right_img_file}'") + + +@route("/left-img-file", method="POST") +def set_left_img_file(): + global left_img_file + json = request.json + left_img_file = json["left-img-file"] + print(f"Set left img file to '{left_img_file}'") + + +@route("/image/left") +def left_image(): + resp = static_file(left_img_file, root=image_dir) + resp.set_header("Cache-Control", "no-store") + return resp + + +@route("/image/right") +def right_image(): + resp = static_file(right_img_file, root=image_dir) + resp.set_header("Cache-Control", "no-store") + return resp + + +@route("/image/") +def image(fn): + return static_file(fn, root=dirname) + + +@route("/points", method="POST") +def points(): + global points + json = request.json + points = [] + for z in zip(json["leftPoints"], json["rightPoints"]): + points.append(z[0] + z[1]) + + +@route("/points", method="GET") +def get_points(): + return {"points": points} + + +if __name__ == "__main__": + dirname = os.path.abspath(os.path.dirname(__file__)) + parser = argparse.ArgumentParser() + parser.add_argument("--port", default=8080) + parser.add_argument("--host", default="localhost") + args = parser.parse_args() + run(host=args.host, port=args.port) diff --git a/kamera/postflight/scripts/keypoint_server/keypoint.tpl b/kamera/postflight/scripts/keypoint_server/keypoint.tpl new file mode 100644 index 0000000..8d679dd --- /dev/null +++ b/kamera/postflight/scripts/keypoint_server/keypoint.tpl @@ -0,0 +1,357 @@ + + + +
+ +
+ + + From 35bad990885b72e8957202dc148c2a8b360820ea Mon Sep 17 00:00:00 2001 From: Adam Romlein Date: Thu, 19 Dec 2024 20:26:02 -0500 Subject: [PATCH 02/20] Update imports --- kamera/postflight/scripts/create_flight_summary.py | 2 +- kamera/postflight/scripts/debayer.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/kamera/postflight/scripts/create_flight_summary.py b/kamera/postflight/scripts/create_flight_summary.py index 7fca5b8..9a7cb36 100644 --- a/kamera/postflight/scripts/create_flight_summary.py +++ b/kamera/postflight/scripts/create_flight_summary.py @@ -46,5 +46,5 @@ def main(): utilities.create_flight_summary(flight_dir, output_dir) -if __name__ == '__main__': +if __name__ == "__main__": main() diff --git a/kamera/postflight/scripts/debayer.py b/kamera/postflight/scripts/debayer.py index 555d497..537d5f2 100644 --- a/kamera/postflight/scripts/debayer.py +++ b/kamera/postflight/scripts/debayer.py @@ -38,7 +38,7 @@ import argparse # KAMERA imports. -from postflight_scripts import utilities +from kamera.postflight import utilities def main(): From aadef7f31034c22751e3efbe33a25271c5d87d90 Mon Sep 17 00:00:00 2001 From: Adam Romlein Date: Thu, 19 Dec 2024 20:27:10 -0500 Subject: [PATCH 03/20] Formatting (ruff) --- kamera/colmap_processing/camera_models.py | 1271 +++++++++++--------- kamera/colmap_processing/image_renderer.py | 213 ++-- 2 files changed, 822 insertions(+), 662 deletions(-) diff --git a/kamera/colmap_processing/camera_models.py b/kamera/colmap_processing/camera_models.py index c1211f8..4a45afc 100644 --- a/kamera/colmap_processing/camera_models.py +++ b/kamera/colmap_processing/camera_models.py @@ -4,37 +4,27 @@ import cv2 import time import yaml -from scipy.interpolate import interp1d, RectBivariateSpline -from scipy.optimize import fmin, fminbound, minimize +from scipy.interpolate import RectBivariateSpline import PIL from math import sqrt -import matplotlib.pyplot as plt - # Repository imports. -from kamera.colmap_processing.image_renderer import stitch_images from kamera.colmap_processing.platform_pose import PlatformPoseFixed from kamera.colmap_processing.geo_conversions import enu_to_llh, llh_to_enu from kamera.colmap_processing.rotations import ( - euler_from_quaternion, - quaternion_multiply, - quaternion_matrix, - quaternion_from_euler, - quaternion_inverse, - quaternion_from_matrix, - ) -import kamera.colmap_processing.dp as dp + quaternion_matrix, + quaternion_inverse, + quaternion_from_matrix, +) def to_str(v): - """Convert numerical values (scalar or float) to string for saving to yaml - - """ + """Convert numerical values (scalar or float) to string for saving to yaml""" if isinstance(v, np.ndarray): v = v.tolist() else: return str(v) - if isinstance(v, list): + if isinstance(v, list): if len(v) > 1: return repr(list(v)) else: @@ -57,13 +47,18 @@ class CamToCamTform(object): the view such that we can ignore parallax during transformation. """ + def __init__(self, src_cm, dst_cm): - if src_cm.platform_pose_provider != dst_cm.platform_pose_provider and \ - not isinstance(src_cm.platform_pose_provider, PlatformPoseFixed) and \ - not isinstance(dst_cm.platform_pose_provider, PlatformPoseFixed): - raise Exception('src_cm and dst_cm must have the same ' - 'platform_pose_provider indicating that the cameras ' - 'are rigidly mounted to the same platform') + if ( + src_cm.platform_pose_provider != dst_cm.platform_pose_provider + and not isinstance(src_cm.platform_pose_provider, PlatformPoseFixed) + and not isinstance(dst_cm.platform_pose_provider, PlatformPoseFixed) + ): + raise Exception( + "src_cm and dst_cm must have the same " + "platform_pose_provider indicating that the cameras " + "are rigidly mounted to the same platform" + ) self._src_cm = src_cm self._dst_cm = dst_cm @@ -84,11 +79,11 @@ def fit(self, tol=0.1, k=1): # the number of tiles. N = 10 while True: - dx = np.sqrt(w*h/N) - x = np.linspace(0, w, int(np.ceil(w/dx))) - y = np.linspace(0, h, int(np.ceil(h/dx))) - X,Y = np.meshgrid(x, y) - points = np.vstack([X.ravel(),Y.ravel()]) + dx = np.sqrt(w * h / N) + x = np.linspace(0, w, int(np.ceil(w / dx))) + y = np.linspace(0, h, int(np.ceil(h / dx))) + X, Y = np.meshgrid(x, y) + points = np.vstack([X.ravel(), Y.ravel()]) out_points = self.tform_rigorous(points) @@ -99,14 +94,14 @@ def fit(self, tol=0.1, k=1): self._model_y = RectBivariateSpline(x, y, out_y.T, kx=k, ky=k) # Test - x = np.linspace(0, w, int(np.ceil(w/dx))*2) - y = np.linspace(0, h, int(np.ceil(h/dx))*2) - X,Y = np.meshgrid(x, y) - points = np.vstack([X.ravel(),Y.ravel()]) + x = np.linspace(0, w, int(np.ceil(w / dx)) * 2) + y = np.linspace(0, h, int(np.ceil(h / dx)) * 2) + X, Y = np.meshgrid(x, y) + points = np.vstack([X.ravel(), Y.ravel()]) points_out = self.tform(points) points_out_truth = self.tform_rigorous(points) - err = np.sqrt(np.sum((points_out_truth - points_out)**2, 0)) + err = np.sqrt(np.sum((points_out_truth - points_out) ** 2, 0)) if np.max(err) < tol or N > 2000: break @@ -123,8 +118,8 @@ def tform(self, points): :rtype: numpy.ndarray of size (2,n) """ - if not hasattr(self, '_model_x'): - raise Exception('Must call \'fit\' before calling \'tform\'') + if not hasattr(self, "_model_x"): + raise Exception("Must call 'fit' before calling 'tform'") out_points = np.zeros_like(points) out_points[0] = self._model_x.ev(points[0], points[1]) @@ -148,7 +143,7 @@ def tform_rigorous(self, points): # We don't have a world model to intersect with, so we send it out # to "infinity". - point = (ray_pos + ray_dir*1e5) + point = ray_pos + ray_dir * 1e5 return self._dst_cm.project(point, -np.inf) @@ -182,35 +177,32 @@ def rt_from_quat_pos(position, quaternion): # system. So, we invert each quaternion. quaternion = quaternion_inverse(quaternion) - p = quaternion_matrix(quaternion) # R - p[:3,3] = -np.dot(p[:3,:3], position) # T + p = quaternion_matrix(quaternion) # R + p[:3, 3] = -np.dot(p[:3, :3], position) # T return p def load_from_file(filename, platform_pose_provider=None): - """Load from configuration yaml for any of the Camera subclasses. - - """ - with open(filename, 'r') as f: + """Load from configuration yaml for any of the Camera subclasses.""" + with open(filename, "r") as f: calib = yaml.safe_load(f) - if calib['model_type'] == 'standard': + if calib["model_type"] == "standard": return StandardCamera.load_from_file(filename, platform_pose_provider) - if calib['model_type'] == 'rolling_shutter': + if calib["model_type"] == "rolling_shutter": return RollingShutterCamera.load_from_file(filename, platform_pose_provider) - if calib['model_type'] == 'depth': + if calib["model_type"] == "depth": return DepthCamera.load_from_file(filename, platform_pose_provider) - if calib['model_type'] == 'static': + if calib["model_type"] == "static": return GeoStaticCamera.load_from_file(filename, platform_pose_provider) raise Exception() -def ray_intersect_plane(plane_point, plane_normal, ray_pos, ray_dir, - epsilon=1e-6): +def ray_intersect_plane(plane_point, plane_normal, ray_pos, ray_dir, epsilon=1e-6): """From https://rosettacode.org/wiki/Find_the_intersection_of_a_line_with_a_plane#Python :param ray_pos: Ray starting positions. @@ -260,6 +252,7 @@ class Camera(object): any time-varying parameters (e.g., navigation coordinate system state). """ + def __init__(self, width, height, platform_pose_provider=None): """ :param width: Width of the image provided by the imaging sensor, @@ -312,35 +305,35 @@ def depth_map(self, value): @property def platform_pose_provider(self): - """Instance of a subclass of NavStateProvider - - """ + """Instance of a subclass of NavStateProvider""" return self._platform_pose_provider @platform_pose_provider.setter def platform_pose_provider(self, value): - """Instance of a subclass of NavStateProvider - - """ + """Instance of a subclass of NavStateProvider""" self._platform_pose_provider = value def __str__(self): - string = [''.join(['image_width: ',repr(self._width),'\n'])] - string.append(''.join(['image_height: ',repr(self._height),'\n'])) - string.append(''.join(['platform_pose_provider: ', - repr(self._platform_pose_provider)])) + string = ["".join(["image_width: ", repr(self._width), "\n"])] + string.append("".join(["image_height: ", repr(self._height), "\n"])) + string.append( + "".join(["platform_pose_provider: ", repr(self._platform_pose_provider)]) + ) try: # Some time-dependent cameras may not have a queue of values. - string.append(''.join(['\nifov: ', - '({:.6g},{:.6g})'.format(*self.ifov(np.inf)), - '\n'])) - string.append(''.join(['fov: ', - '({:.6},{:.6},{:.6})'.format(*self.fov(np.inf))])) + string.append( + "".join( + ["\nifov: ", "({:.6g},{:.6g})".format(*self.ifov(np.inf)), "\n"] + ) + ) + string.append( + "".join(["fov: ", "({:.6},{:.6},{:.6})".format(*self.fov(np.inf))]) + ) except: pass - return ''.join(string) + return "".join(string) def __repr__(self): return self.__str__() @@ -364,7 +357,7 @@ def get_param_array(self, param_list): """ params = np.zeros(0) for param in param_list: - params = np.hstack([params,getattr(self, param)]) + params = np.hstack([params, getattr(self, param)]) return params @@ -381,8 +374,8 @@ def set_param_array(self, param_list, params): ind = 0 for param in param_list: p0 = getattr(self, param) - if hasattr(p0, '__len__') and len(p0) > 1: - setattr(self, param, params[ind:ind+len(p0)]) + if hasattr(p0, "__len__") and len(p0) > 1: + setattr(self, param, params[ind : ind + len(p0)]) ind += len(p0) else: setattr(self, param, params[ind]) @@ -483,8 +476,10 @@ def unproject_to_llh(self, points, t=None, cov=None): h0 = self.platform_pose_provider.h0 if lat0 is None or lon0 is None or h0 is None: - raise Exception('\'platform_pose_provider\' must have \'lat0\', ' - '\'lon0\', and \'ho\' defined.') + raise Exception( + "'platform_pose_provider' must have 'lat0', " + "'lon0', and 'ho' defined." + ) points = np.array(points) if points.ndim == 1: @@ -493,13 +488,13 @@ def unproject_to_llh(self, points, t=None, cov=None): else: was_1d = False points = np.array(points) - points = np.reshape(points, (2,-1)) + points = np.reshape(points, (2, -1)) llh = [] geo_cov = [] for i in range(points.shape[1]): - xyz = self.unproject_to_depth(points[:,i], t) + xyz = self.unproject_to_depth(points[:, i], t) if np.all(np.isfinite(xyz)): llh.append(enu_to_llh(xyz[0], xyz[1], xyz[2], lat0, lon0, h0)) else: @@ -508,16 +503,14 @@ def unproject_to_llh(self, points, t=None, cov=None): if cov is not None: # Sample 10 random points and project each into enu coordinate # system - rpoints = np.random.multivariate_normal(points[:,i], cov[i], - 20) + rpoints = np.random.multivariate_normal(points[:, i], cov[i], 20) # Points must be inside image. - ind = np.logical_and(rpoints[:,0] > 0, rpoints[:,1] > 0) - ind = np.logical_and(ind, rpoints[:,0] < self.width) - ind = np.logical_and(ind, rpoints[:,1] < self.height) + ind = np.logical_and(rpoints[:, 0] > 0, rpoints[:, 1] > 0) + ind = np.logical_and(ind, rpoints[:, 0] < self.width) + ind = np.logical_and(ind, rpoints[:, 1] < self.height) rpoints = rpoints[ind] - enu_pts = ([self.unproject_to_depth(_, t).ravel() - for _ in rpoints]) + enu_pts = [self.unproject_to_depth(_, t).ravel() for _ in rpoints] enu_pts = [_ for _ in enu_pts if np.all(np.isfinite(enu_pts))] @@ -527,7 +520,7 @@ def unproject_to_llh(self, points, t=None, cov=None): enu_pts = np.array(enu_pts) - if xyz[0]**2 + xyz[1]**2 > 6250000: + if xyz[0] ** 2 + xyz[1] ** 2 > 6250000: # If the point is further than 2.5km from the camera, we # want the covariance defined in an east/north/up # coordinate system centered at xyz, the most-likely @@ -538,12 +531,17 @@ def unproject_to_llh(self, points, t=None, cov=None): llh0 = enu_to_llh(xyz[0], xyz[1], xyz[2], lat0, lon0, h0) for i in range(len(enu_pts)): - llhi = enu_to_llh(enu_pts[i,0], enu_pts[i,1], - enu_pts[i,2], llh0[0], llh0[1], - llh0[2]) - enu_pts[i,:] = llh_to_enu(llhi[0], llhi[1], llhi[2], - llh0[0], llh0[1], llh0[2]) - + llhi = enu_to_llh( + enu_pts[i, 0], + enu_pts[i, 1], + enu_pts[i, 2], + llh0[0], + llh0[1], + llh0[2], + ) + enu_pts[i, :] = llh_to_enu( + llhi[0], llhi[1], llhi[2], llh0[0], llh0[1], llh0[2] + ) geo_cov.append(np.cov(enu_pts.T)) @@ -553,7 +551,7 @@ def unproject_to_llh(self, points, t=None, cov=None): llh = np.array(llh).T if cov is not None: - return llh,geo_cov + return llh, geo_cov else: return llh @@ -568,25 +566,34 @@ def points_along_image_border(self, num_points=4): :rtype: numpy.ndarry with shape (3,n) """ - perimeter = 2*(self.height + self.width) - ds = num_points/float(perimeter) - xn = np.max([2,int(ds*self.width)]) - yn = np.max([2,int(ds*self.height)]) + perimeter = 2 * (self.height + self.width) + ds = num_points / float(perimeter) + xn = np.max([2, int(ds * self.width)]) + yn = np.max([2, int(ds * self.height)]) x = np.linspace(0, self.width, xn) y = np.linspace(0, self.height, yn)[1:-1] - pts = np.vstack([np.hstack([x, - np.full(len(y), self.width, - dtype=np.float64), - x[::-1], - np.zeros(len(y))]), - np.hstack([np.zeros(xn), - y, - np.full(xn, self.height, - dtype=np.float64), - y[::-1]])]) + pts = np.vstack( + [ + np.hstack( + [ + x, + np.full(len(y), self.width, dtype=np.float64), + x[::-1], + np.zeros(len(y)), + ] + ), + np.hstack( + [ + np.zeros(xn), + y, + np.full(xn, self.height, dtype=np.float64), + y[::-1], + ] + ), + ] + ) return pts - def ifov(self, t=None): """Instantaneous field of view (ifov) at the image center. @@ -603,14 +610,14 @@ def ifov(self, t=None): if t is None: t = time.time() - cx = self.width/2 - cy = self.height/2 - ray1 = self.unproject([cx,cy], t)[1] - ray1 /= np.sqrt(np.sum(ray1**2, 0)) - ray2 = self.unproject([cx,cy+1], t)[1] - ray2 /= np.sqrt(np.sum(ray2**2, 0)) - ray3 = self.unproject([cx+1,cy], t)[1] - ray3 /= np.sqrt(np.sum(ray3**2, 0)) + cx = self.width / 2 + cy = self.height / 2 + ray1 = self.unproject([cx, cy], t)[1] + ray1 /= np.sqrt(np.sum(ray1 ** 2, 0)) + ray2 = self.unproject([cx, cy + 1], t)[1] + ray2 /= np.sqrt(np.sum(ray2 ** 2, 0)) + ray3 = self.unproject([cx + 1, cy], t)[1] + ray3 /= np.sqrt(np.sum(ray3 ** 2, 0)) ifovx = np.arccos(np.dot(ray1.ravel(), ray3.ravel())) ifovy = np.arccos(np.dot(ray1.ravel(), ray2.ravel())) @@ -632,33 +639,31 @@ def fov(self, t=None): if t is None: t = time.time() - cx = self.width/2 - cy = self.height/2 + cx = self.width / 2 + cy = self.height / 2 - ray1 = self.unproject([cx,0], t)[1] - ray1 /= np.sqrt(np.sum(ray1**2, 0)) - ray2 = self.unproject([cx,self.height], t)[1] - ray2 /= np.sqrt(np.sum(ray2**2, 0)) - fov_v = np.arccos(np.dot(ray1.ravel(), ray2.ravel()))*180/np.pi + ray1 = self.unproject([cx, 0], t)[1] + ray1 /= np.sqrt(np.sum(ray1 ** 2, 0)) + ray2 = self.unproject([cx, self.height], t)[1] + ray2 /= np.sqrt(np.sum(ray2 ** 2, 0)) + fov_v = np.arccos(np.dot(ray1.ravel(), ray2.ravel())) * 180 / np.pi - ray1 = self.unproject([0,cy], t)[1] - ray1 /= np.sqrt(np.sum(ray1**2, 0)) + ray1 = self.unproject([0, cy], t)[1] + ray1 /= np.sqrt(np.sum(ray1 ** 2, 0)) ray2 = self.unproject([self.width, cy], t)[1] - ray2 /= np.sqrt(np.sum(ray2**2, 0)) - fov_h = np.arccos(np.dot(ray1.ravel(), ray2.ravel()))*180/np.pi + ray2 /= np.sqrt(np.sum(ray2 ** 2, 0)) + fov_h = np.arccos(np.dot(ray1.ravel(), ray2.ravel())) * 180 / np.pi - ray1 = self.unproject([0,0], t)[1] - ray1 /= np.sqrt(np.sum(ray1**2, 0)) - ray2 = self.unproject([self.width,self.height], t)[1] - ray2 /= np.sqrt(np.sum(ray2**2, 0)) - fov_d = np.arccos(np.dot(ray1.ravel(), ray2.ravel()))*180/np.pi + ray1 = self.unproject([0, 0], t)[1] + ray1 /= np.sqrt(np.sum(ray1 ** 2, 0)) + ray2 = self.unproject([self.width, self.height], t)[1] + ray2 /= np.sqrt(np.sum(ray2 ** 2, 0)) + fov_d = np.arccos(np.dot(ray1.ravel(), ray2.ravel())) * 180 / np.pi return fov_h, fov_v, fov_d def unproject_to_depth(self, points, t=None): - """See Camera.unproject_to_depth documentation. - - """ + """See Camera.unproject_to_depth documentation.""" points = self._unproject_to_depth(points, self.depth_map, t=t) return points @@ -672,7 +677,7 @@ def save_depth_viz(self, fname): depth_image[depth_image < 0] = 0 v = vmax - vmin if v > 0: - depth_image /= v/255 + depth_image /= v / 255 depth_image = np.round(depth_image).astype(np.uint8) @@ -706,14 +711,15 @@ class StandardCamera(Camera): :type dist: numpy.ndarray """ - def __init__(self, width, height, K, dist, cam_pos, cam_quat, - platform_pose_provider=None): + + def __init__( + self, width, height, K, dist, cam_pos, cam_quat, platform_pose_provider=None + ): """ See additional documentation from base class above. """ - super(StandardCamera, self).__init__(width, height, - platform_pose_provider) + super(StandardCamera, self).__init__(width, height, platform_pose_provider) self._K = np.array(K, dtype=np.float64) self._dist = np.atleast_1d(dist).astype(np.float32) @@ -723,74 +729,69 @@ def __init__(self, width, height, K, dist, cam_pos, cam_quat, self._min_ray_cos = None def __str__(self): - string = ['model_type: standard\n'] + string = ["model_type: standard\n"] string.append(super(StandardCamera, self).__str__()) - string.append('\n') - string.append(''.join(['fx: ',repr(self._K[0,0]),'\n'])) - string.append(''.join(['fy: ',repr(self._K[1,1]),'\n'])) - string.append(''.join(['cx: ',repr(self._K[0,2]),'\n'])) - string.append(''.join(['cy: ',repr(self._K[1,2]),'\n'])) - string.append(''.join(['distortion_coefficients: ', - repr(tuple(self._dist)), - '\n'])) - string.append(''.join(['camera_quaternion: ', - repr(tuple(self._cam_quat)),'\n'])) - string.append(''.join(['camera_position: ',repr(tuple(self._cam_pos)), - '\n'])) - return ''.join(string) + string.append("\n") + string.append("".join(["fx: ", repr(self._K[0, 0]), "\n"])) + string.append("".join(["fy: ", repr(self._K[1, 1]), "\n"])) + string.append("".join(["cx: ", repr(self._K[0, 2]), "\n"])) + string.append("".join(["cy: ", repr(self._K[1, 2]), "\n"])) + string.append( + "".join(["distortion_coefficients: ", repr(tuple(self._dist)), "\n"]) + ) + string.append( + "".join(["camera_quaternion: ", repr(tuple(self._cam_quat)), "\n"]) + ) + string.append("".join(["camera_position: ", repr(tuple(self._cam_pos)), "\n"])) + return "".join(string) @classmethod def load_from_file(cls, filename, platform_pose_provider=None): - """See base class Camera documentation. - - """ - with open(filename, 'r') as f: + """See base class Camera documentation.""" + with open(filename, "r") as f: calib = yaml.safe_load(f) - assert calib['model_type'] == 'standard' + assert calib["model_type"] == "standard" # fill in CameraInfo fields - width = int(calib['image_width']) - height = int(calib['image_height']) - dist = calib['distortion_coefficients'] + width = int(calib["image_width"]) + height = int(calib["image_height"]) + dist = calib["distortion_coefficients"] - if dist == 'None': + if dist == "None": dist = np.zeros(4) dist = np.float64(dist) - fx = np.float64(calib['fx']) - fy = np.float64(calib['fy']) - cx = np.float64(calib['cx']) - cy = np.float64(calib['cy']) - K = np.array([[fx,0,cx],[0,fy,cy],[0,0,1]]) + fx = np.float64(calib["fx"]) + fy = np.float64(calib["fy"]) + cx = np.float64(calib["cx"]) + cy = np.float64(calib["cy"]) + K = np.array([[fx, 0, cx], [0, fy, cy], [0, 0, 1]]) - cam_quat = calib['camera_quaternion'] - cam_pos = calib['camera_position'] + cam_quat = calib["camera_quaternion"] + cam_pos = calib["camera_position"] - return cls(width, height, K, dist, cam_pos, cam_quat, - platform_pose_provider) + return cls(width, height, K, dist, cam_pos, cam_quat, platform_pose_provider) @classmethod def load_from_krtd(cls, filename): - """See base class Camera documentation. - - """ + """See base class Camera documentation.""" data = [] with open(filename) as f: for line in f.readlines(): - data.append(line.strip('\n')) + data.append(line.strip("\n")) - fx = float(data[0].split(' ' )[0]) - fy = float(data[1].split(' ' )[1]) - cx = float(data[0].split(' ' )[2]) - cy = float(data[1].split(' ' )[2]) + fx = float(data[0].split(" ")[0]) + fy = float(data[1].split(" ")[1]) + cx = float(data[0].split(" ")[2]) + cy = float(data[1].split(" ")[2]) R = np.zeros((3, 3)) for i in range(3): - R[i] = [float(d) for d in data[4 + i].split(' ')] + R[i] = [float(d) for d in data[4 + i].split(" ")] - tvec = [float(d) for d in data[8].split(' ')] + tvec = [float(d) for d in data[8].split(" ")] cam_pos = -np.dot(R.T, tvec).ravel() @@ -800,59 +801,79 @@ def load_from_krtd(cls, filename): width = None height = None - dist = [float(d) for d in data[10].split(' ') if len(d) > 0] + dist = [float(d) for d in data[10].split(" ") if len(d) > 0] dist = np.array(dist) - K = np.array([[fx, 0, cx], [0, fy, cy],[0, 0, 1]]) + K = np.array([[fx, 0, cx], [0, fy, cy], [0, 0, 1]]) return cls(width, height, K, dist, cam_pos, cam_quat) def save_to_file(self, filename): - """See base class Camera documentation. - - """ - with open(filename, 'w') as f: - f.write(''.join(['# The type of camera model.\n', - 'model_type: standard\n\n', - '# Image dimensions\n'])) - - f.write(''.join(['image_width: ',to_str(self.width),'\n'])) - f.write(''.join(['image_height: ',to_str(self.height),'\n\n'])) - - f.write('# Focal length along the image\'s x-axis.\n') - f.write(''.join(['fx: ',to_str(self.K[0,0]),'\n\n'])) - - f.write('# Focal length along the image\'s y-axis.\n') - f.write(''.join(['fy: ',to_str(self.K[1,1]),'\n\n'])) - - f.write('# Principal point is located at (cx,cy).\n') - f.write(''.join(['cx: ',to_str(self.K[0,2]),'\n'])) - f.write(''.join(['cy: ',to_str(self.K[1,2]),'\n\n'])) - - f.write(''.join(['# Distortion coefficients following OpenCv\'s ', - 'convention\n'])) + """See base class Camera documentation.""" + with open(filename, "w") as f: + f.write( + "".join( + [ + "# The type of camera model.\n", + "model_type: standard\n\n", + "# Image dimensions\n", + ] + ) + ) + + f.write("".join(["image_width: ", to_str(self.width), "\n"])) + f.write("".join(["image_height: ", to_str(self.height), "\n\n"])) + + f.write("# Focal length along the image's x-axis.\n") + f.write("".join(["fx: ", to_str(self.K[0, 0]), "\n\n"])) + + f.write("# Focal length along the image's y-axis.\n") + f.write("".join(["fy: ", to_str(self.K[1, 1]), "\n\n"])) + + f.write("# Principal point is located at (cx,cy).\n") + f.write("".join(["cx: ", to_str(self.K[0, 2]), "\n"])) + f.write("".join(["cy: ", to_str(self.K[1, 2]), "\n\n"])) + + f.write( + "".join( + ["# Distortion coefficients following OpenCv's ", "convention\n"] + ) + ) dist = self.dist if np.all(dist == 0): - dist = 'None' - - f.write(''.join(['distortion_coefficients: ', - to_str(self.dist),'\n\n'])) - - f.write(''.join(['# Quaternion (x, y, z, w) specifying the ', - 'orientation of the camera relative to\n# the ', - 'platform coordinate system. The quaternion ', - 'represents a coordinate\n# system rotation that ', - 'takes the platform coordinate system and ', - 'rotates it\n# into the camera coordinate ', - 'system.\ncamera_quaternion: ', - to_str(self.cam_quat),'\n\n'])) - - f.write(''.join(['# Position of the camera\'s center of ', - 'projection within the navigation\n# coordinate ', - 'system.\n', - 'camera_position: ', to_str(self.cam_pos), - '\n\n'])) + dist = "None" + + f.write("".join(["distortion_coefficients: ", to_str(self.dist), "\n\n"])) + + f.write( + "".join( + [ + "# Quaternion (x, y, z, w) specifying the ", + "orientation of the camera relative to\n# the ", + "platform coordinate system. The quaternion ", + "represents a coordinate\n# system rotation that ", + "takes the platform coordinate system and ", + "rotates it\n# into the camera coordinate ", + "system.\ncamera_quaternion: ", + to_str(self.cam_quat), + "\n\n", + ] + ) + ) + + f.write( + "".join( + [ + "# Position of the camera's center of ", + "projection within the navigation\n# coordinate ", + "system.\n", + "camera_position: ", + to_str(self.cam_pos), + "\n\n", + ] + ) + ) @property def K(self): @@ -860,77 +881,74 @@ def K(self): @property def K_no_skew(self): - """Returns a compact version of K assuming no skew. - - """ + """Returns a compact version of K assuming no skew.""" K = self.K - return np.array([K[0,0],K[1,1],K[0,2],K[1,2]]) + return np.array([K[0, 0], K[1, 1], K[0, 2], K[1, 2]]) @K_no_skew.setter def K_no_skew(self, value): - """fx, fy, cx, cy - """ - K = np.zeros((3,3), dtype=np.float64) - K[0,0] = value[0] - K[1,1] = value[1] - K[0,2] = value[2] - K[1,2] = value[3] + """fx, fy, cx, cy""" + K = np.zeros((3, 3), dtype=np.float64) + K[0, 0] = value[0] + K[1, 1] = value[1] + K[0, 2] = value[2] + K[1, 2] = value[3] self._K = K self._min_ray_cos = None @property def focal_length(self): - return self._K[0,0] + return self._K[0, 0] @focal_length.setter def focal_length(self, value): - self._K[0,0] = value - self._K[1,1] = value + self._K[0, 0] = value + self._K[1, 1] = value self._min_ray_cos = None @property def fx(self): - return self._K[0,0] + return self._K[0, 0] @property def fy(self): - return self._K[1,1] + return self._K[1, 1] @fx.setter def fx(self, value): - self._K[0,0] = value + self._K[0, 0] = value self._min_ray_cos = None @fy.setter def fy(self, value): - self._K[1,1] = value + self._K[1, 1] = value self._min_ray_cos = None @property def cx(self): - return self._K[0,2] + return self._K[0, 2] @property def cy(self): - return self._K[1,2] + return self._K[1, 2] @cx.setter def cx(self, value): - self._K[0,2] = value + self._K[0, 2] = value self._min_ray_cos = None @cy.setter def cy(self, value): - self._K[1,2] = value + self._K[1, 2] = value self._min_ray_cos = None @property def aspect_ratio(self): - return self._K[0,0]/self._K[1,1] + return self._K[0, 0] / self._K[1, 1] @aspect_ratio.setter def aspect_ratio(self, value): - self._K[1,1] = self._K[0,0]*value + self._K[1, 1] = self._K[0, 0] * value @property def dist(self): @@ -977,8 +995,8 @@ def min_ray_cos(self): ray0 = self.unproject(center, t, normalize_ray_dir=True)[1].ravel() w, h = self.width, self.height self._min_ray_cos = 1 - for x,y in [[0,0],[w,0],[w,h],[0,h]]: - ray1 = self.unproject([x, y], t, normalize_ray_dir=True)[1] + for x, y in [[0, 0], [w, 0], [w, h], [0, h]]: + ray1 = self.unproject([x, y], t, normalize_ray_dir=True)[1] ray1 = ray1.ravel() ray_cosi = np.dot(ray0, ray1) self._min_ray_cos = np.minimum(self._min_ray_cos, ray_cosi) @@ -988,8 +1006,7 @@ def min_ray_cos(self): return self._min_ray_cos def update_intrinsics(self, K=None, cam_quat=None, dist=None): - """ - """ + """ """ if K is not None: self._K = K.astype(np.float64) if cam_quat is not None: @@ -1022,9 +1039,7 @@ def get_camera_pose(self, t=None): return np.dot(p_cam, p_ins)[:3] def project(self, points, t=None): - """See Camera.project documentation. - - """ + """See Camera.project documentation.""" points = np.array(points, dtype=np.float64) if points.ndim == 1: points = np.atleast_2d(points).T @@ -1033,53 +1048,51 @@ def project(self, points, t=None): t = time.time() pose_mat = self.get_camera_pose(t) - pose_mat = np.vstack((pose_mat, np.array([0,0,0,1]))) + pose_mat = np.vstack((pose_mat, np.array([0, 0, 0, 1]))) # Project rays into camera coordinate system. - rvec = cv2.Rodrigues(pose_mat[:3,:3])[0].ravel() + rvec = cv2.Rodrigues(pose_mat[:3, :3])[0].ravel() tvec = pose_mat[:3, 3] - im_pts = cv2.projectPoints(points.T, rvec, tvec, self._K, - self._dist)[0] + im_pts = cv2.projectPoints(points.T, rvec, tvec, self._K, self._dist)[0] im_pts = np.squeeze(im_pts, 1).T # Make homogeneous points = np.vstack([points, np.ones(points.shape[1])]) points = np.dot(pose_mat, points) - #points /= np.sqrt(np.sum(points**2, 0)) + # points /= np.sqrt(np.sum(points**2, 0)) points /= points[3, :] # Add the 1e-8 to avoid "falling off the focal plane" due to rounding # error. # ind = points[2] <= self.min_ray_cos - #im_pts[:, ind] = np.nan + # im_pts[:, ind] = np.nan return im_pts def unproject(self, points, t=None, normalize_ray_dir=True): - """See Camera.unproject documentation. - - """ + """See Camera.unproject documentation.""" points = np.array(points, dtype=np.float64) if points.ndim == 1: points = np.atleast_2d(points).T - points = np.reshape(points, (2,-1)) + points = np.reshape(points, (2, -1)) if t is None: t = time.time() ins_pos, ins_quat = self.platform_pose_provider.pose(t) - #print('ins_pos', ins_pos) - #print('ins_quat', ins_quat) + # print('ins_pos', ins_pos) + # print('ins_quat', ins_quat) # Unproject rays into the camera coordinate system. - ray_dir = np.ones((3,points.shape[1]), dtype=points.dtype) - ray_dir0 = cv2.undistortPoints(np.expand_dims(points.T, 1), - self._K, self._dist, R=None) + ray_dir = np.ones((3, points.shape[1]), dtype=points.dtype) + ray_dir0 = cv2.undistortPoints( + np.expand_dims(points.T, 1), self._K, self._dist, R=None + ) ray_dir[:2] = np.squeeze(ray_dir0, 1).T # Rotate rays into the navigation coordinate system. - ray_dir = np.dot(quaternion_matrix(self._cam_quat)[:3,:3], ray_dir) + ray_dir = np.dot(quaternion_matrix(self._cam_quat)[:3, :3], ray_dir) # Translate ray positions into their navigation coordinate system # definition. @@ -1089,13 +1102,13 @@ def unproject(self, points, t=None, normalize_ray_dir=True): ray_pos[2] = self._cam_pos[2] # Rotate and translate rays into the world coordinate system. - R_ins_to_world = quaternion_matrix(ins_quat)[:3,:3] + R_ins_to_world = quaternion_matrix(ins_quat)[:3, :3] ray_dir = np.dot(R_ins_to_world, ray_dir) ray_pos = np.dot(R_ins_to_world, ray_pos) + np.atleast_2d(ins_pos).T if normalize_ray_dir: # Normalize - ray_dir /= np.sqrt(np.sum(ray_dir**2, 0)) + ray_dir /= np.sqrt(np.sum(ray_dir ** 2, 0)) return ray_pos, ray_dir @@ -1126,108 +1139,143 @@ class RollingShutterCamera(StandardCamera): :type dist: numpy.ndarray """ - def __init__(self, width, height, K, dist, cam_pos, cam_quat, - shutter_roll_time, platform_pose_provider=None): + + def __init__( + self, + width, + height, + K, + dist, + cam_pos, + cam_quat, + shutter_roll_time, + platform_pose_provider=None, + ): """ See additional documentation from base class above. """ - super(RollingShutterCamera, self).__init__(width, height, K, dist, - cam_pos, cam_quat, - platform_pose_provider) + super(RollingShutterCamera, self).__init__( + width, height, K, dist, cam_pos, cam_quat, platform_pose_provider + ) self.shutter_roll_time = shutter_roll_time def __str__(self): - string = ['model_type: rolling_shutter\n'] + string = ["model_type: rolling_shutter\n"] string.append(super(RollingShutterCamera, self).__str__()) - string.append('shutter_roll_time: %s\n' %self.shutter_roll_time) - return ''.join(string) + string.append("shutter_roll_time: %s\n" % self.shutter_roll_time) + return "".join(string) @classmethod def load_from_file(cls, filename, platform_pose_provider=None): - """See base class Camera documentation. - - """ - with open(filename, 'r') as f: + """See base class Camera documentation.""" + with open(filename, "r") as f: calib = yaml.safe_load(f) - assert calib['model_type'] == 'rolling_shutter' + assert calib["model_type"] == "rolling_shutter" # fill in CameraInfo fields - width = calib['image_width'] - height = calib['image_height'] - shutter_roll_time = calib['shutter_roll_time'] - dist = calib['distortion_coefficients'] + width = calib["image_width"] + height = calib["image_height"] + shutter_roll_time = calib["shutter_roll_time"] + dist = calib["distortion_coefficients"] - if dist == 'None': + if dist == "None": dist = np.zeros(4) - fx = calib['fx'] - fy = calib['fy'] - cx = calib['cx'] - cy = calib['cy'] - K = np.array([[fx,0,cx],[0,fy,cy],[0,0,1]]) - - cam_quat = calib['camera_quaternion'] - cam_pos = calib['camera_position'] - - return cls(width, height, K, dist, cam_pos, cam_quat, - shutter_roll_time, platform_pose_provider) + fx = calib["fx"] + fy = calib["fy"] + cx = calib["cx"] + cy = calib["cy"] + K = np.array([[fx, 0, cx], [0, fy, cy], [0, 0, 1]]) + + cam_quat = calib["camera_quaternion"] + cam_pos = calib["camera_position"] + + return cls( + width, + height, + K, + dist, + cam_pos, + cam_quat, + shutter_roll_time, + platform_pose_provider, + ) def save_to_file(self, filename): - """See base class Camera documentation. - - """ - with open(filename, 'w') as f: - f.write(''.join(['# The type of camera model.\n', - 'model_type: rolling_shutter\n\n', - '# Image dimensions\n'])) - - f.write(''.join(['image_width: ',to_str(self.width),'\n'])) - f.write(''.join(['image_height: ',to_str(self.height),'\n\n'])) - - f.write(''.join(['shutter_roll_time: ', - to_str(self.shutter_roll_time),'\n\n'])) - - f.write('# Focal length along the image\'s x-axis.\n') - f.write(''.join(['fx: ',to_str(self.K[0,0]),'\n\n'])) - - f.write('# Focal length along the image\'s y-axis.\n') - f.write(''.join(['fy: ',to_str(self.K[1,1]),'\n\n'])) - - f.write('# Principal point is located at (cx,cy).\n') - f.write(''.join(['cx: ',to_str(self.K[0,2]),'\n'])) - f.write(''.join(['cy: ',to_str(self.K[1,2]),'\n\n'])) - - f.write(''.join(['# Distortion coefficients following OpenCv\'s ', - 'convention\n'])) + """See base class Camera documentation.""" + with open(filename, "w") as f: + f.write( + "".join( + [ + "# The type of camera model.\n", + "model_type: rolling_shutter\n\n", + "# Image dimensions\n", + ] + ) + ) + + f.write("".join(["image_width: ", to_str(self.width), "\n"])) + f.write("".join(["image_height: ", to_str(self.height), "\n\n"])) + + f.write( + "".join(["shutter_roll_time: ", to_str(self.shutter_roll_time), "\n\n"]) + ) + + f.write("# Focal length along the image's x-axis.\n") + f.write("".join(["fx: ", to_str(self.K[0, 0]), "\n\n"])) + + f.write("# Focal length along the image's y-axis.\n") + f.write("".join(["fy: ", to_str(self.K[1, 1]), "\n\n"])) + + f.write("# Principal point is located at (cx,cy).\n") + f.write("".join(["cx: ", to_str(self.K[0, 2]), "\n"])) + f.write("".join(["cy: ", to_str(self.K[1, 2]), "\n\n"])) + + f.write( + "".join( + ["# Distortion coefficients following OpenCv's ", "convention\n"] + ) + ) dist = self.dist if np.all(dist == 0): - dist = 'None' - - f.write(''.join(['distortion_coefficients: ', - to_str(self.dist),'\n\n'])) - - f.write(''.join(['# Quaternion (x, y, z, w) specifying the ', - 'orientation of the camera relative to\n# the ', - 'platform coordinate system. The quaternion ', - 'represents a coordinate\n# system rotation that ', - 'takes the platform coordinate system and ', - 'rotates it\n# into the camera coordinate ', - 'system.\ncamera_quaternion: ', - to_str(self.cam_quat),'\n\n'])) - - f.write(''.join(['# Position of the camera\'s center of ', - 'projection within the navigation\n# coordinate ', - 'system.\n', - 'camera_position: ',to_str(self.cam_pos), - '\n\n'])) + dist = "None" + + f.write("".join(["distortion_coefficients: ", to_str(self.dist), "\n\n"])) + + f.write( + "".join( + [ + "# Quaternion (x, y, z, w) specifying the ", + "orientation of the camera relative to\n# the ", + "platform coordinate system. The quaternion ", + "represents a coordinate\n# system rotation that ", + "takes the platform coordinate system and ", + "rotates it\n# into the camera coordinate ", + "system.\ncamera_quaternion: ", + to_str(self.cam_quat), + "\n\n", + ] + ) + ) + + f.write( + "".join( + [ + "# Position of the camera's center of ", + "projection within the navigation\n# coordinate ", + "system.\n", + "camera_position: ", + to_str(self.cam_pos), + "\n\n", + ] + ) + ) def project(self, points, t=None): - """See Camera.project documentation. - - """ + """See Camera.project documentation.""" # The challenge projecting into a rolling shutter camera is that every # row of the image is exposed at a different time. So, if you assume a # particular time to evaluate the pose at and then project into the @@ -1238,7 +1286,7 @@ def project(self, points, t=None): # We start by projecting assuming all points are at the time associated # with the center of the field of view. - im_pts = proj_fun(points, t + 0.5*self.shutter_roll_time) + im_pts = proj_fun(points, t + 0.5 * self.shutter_roll_time) if False: # Slower but more accurate. @@ -1255,27 +1303,29 @@ def project(self, points, t=None): if ind[i]: # The fraction of the rolling shutter time this y # coordinate has accumulated. - alpha = np.clip(im_pts[1, i]/self.height, 0, 1) - t_ = t + alpha*self.shutter_roll_time - im_pt_ = proj_fun(points[:, i:i+1], t_) - d = sqrt(np.sum((im_pt_ - im_pts[:, i:i+1])**2)) + alpha = np.clip(im_pts[1, i] / self.height, 0, 1) + t_ = t + alpha * self.shutter_roll_time + im_pt_ = proj_fun(points[:, i : i + 1], t_) + d = sqrt(np.sum((im_pt_ - im_pts[:, i : i + 1]) ** 2)) if d > 0.01: cont = True else: ind[i] = False - im_pts[:, i:i+1] = im_pt_ + im_pts[:, i : i + 1] = im_pt_ if not cont: break else: N = 10 alphas = np.linspace(0, 1, N) - im_pts_list = [proj_fun(points, t + alpha*self.shutter_roll_time).T - for alpha in alphas] + im_pts_list = [ + proj_fun(points, t + alpha * self.shutter_roll_time).T + for alpha in alphas + ] im_pts_list = np.array(im_pts_list).T - alphas2 = np.clip(im_pts_list[1]/self.height, 0, 1) + alphas2 = np.clip(im_pts_list[1] / self.height, 0, 1) alpha_err = alphas2 - alphas # We want to interpolate to the zero-valued alpha error. @@ -1295,32 +1345,40 @@ def project(self, points, t=None): delta = alpha_err1 - alpha_err2 w = np.ones(len(alpha_err1)) ind = delta != 0 - w[ind] = (alpha_err1[ind])/delta[ind] + w[ind] = (alpha_err1[ind]) / delta[ind] - im_pts1 = np.hstack([np.take_along_axis(im_pts_list[0], ind1, axis=1), - np.take_along_axis(im_pts_list[1], ind1, axis=1)]).T + im_pts1 = np.hstack( + [ + np.take_along_axis(im_pts_list[0], ind1, axis=1), + np.take_along_axis(im_pts_list[1], ind1, axis=1), + ] + ).T - im_pts2 = np.hstack([np.take_along_axis(im_pts_list[0], ind2, axis=1), - np.take_along_axis(im_pts_list[1], ind2, axis=1)]).T + im_pts2 = np.hstack( + [ + np.take_along_axis(im_pts_list[0], ind2, axis=1), + np.take_along_axis(im_pts_list[1], ind2, axis=1), + ] + ).T - im_pts = w*im_pts2 + (1-w)*im_pts1 + im_pts = w * im_pts2 + (1 - w) * im_pts1 return im_pts def unproject(self, points, t, normalize_ray_dir=True): - """See Camera.unproject documentation. - - """ + """See Camera.unproject documentation.""" points = np.array(points, dtype=np.float64) if points.ndim == 1: points = np.atleast_2d(points).T - points = np.reshape(points, (2,-1)) + points = np.reshape(points, (2, -1)) - alphas = np.clip(points[1]/self.height, 0, 1) - ts_ = t + (alphas*self.shutter_roll_time).astype(np.float64) + alphas = np.clip(points[1] / self.height, 0, 1) + ts_ = t + (alphas * self.shutter_roll_time).astype(np.float64) - ret = [super(RollingShutterCamera, self).unproject(points[:, i:i+1], ts_[i]) - for i in range(len(ts_))] + ret = [ + super(RollingShutterCamera, self).unproject(points[:, i : i + 1], ts_[i]) + for i in range(len(ts_)) + ] ray_pos = np.hstack([ret_[0] for ret_ in ret]) ray_dir = np.hstack([ret_[1] for ret_ in ret]) @@ -1328,125 +1386,157 @@ def unproject(self, points, t, normalize_ray_dir=True): class DepthCamera(StandardCamera): - """Camera with depth map. - - """ - def __init__(self, width, height, K, dist, cam_pos, cam_quat, depth_map, - platform_pose_provider=None): + """Camera with depth map.""" + + def __init__( + self, + width, + height, + K, + dist, + cam_pos, + cam_quat, + depth_map, + platform_pose_provider=None, + ): """ See additional documentation from base class above. """ - super(DepthCamera, self).__init__(width=width, height=height, K=K, - dist=dist, cam_pos=cam_pos, - cam_quat=cam_quat, - platform_pose_provider=platform_pose_provider) + super(DepthCamera, self).__init__( + width=width, + height=height, + K=K, + dist=dist, + cam_pos=cam_pos, + cam_quat=cam_quat, + platform_pose_provider=platform_pose_provider, + ) self._depth_map = depth_map @classmethod def load_from_file(cls, filename, platform_pose_provider=None): - """See base class Camera documentation. - - """ - with open(filename, 'r') as f: + """See base class Camera documentation.""" + with open(filename, "r") as f: calib = yaml.safe_load(f) - assert calib['model_type'] == 'depth' + assert calib["model_type"] == "depth" # fill in CameraInfo fields - width = calib['image_width'] - height = calib['image_height'] - dist = calib['distortion_coefficients'] + width = calib["image_width"] + height = calib["image_height"] + dist = calib["distortion_coefficients"] - if dist == 'None': + if dist == "None": dist = np.zeros(4) - fx = calib['fx'] - fy = calib['fy'] - cx = calib['cx'] - cy = calib['cy'] - K = np.array([[fx,0,cx],[0,fy,cy],[0,0,1]]) + fx = calib["fx"] + fy = calib["fy"] + cx = calib["cx"] + cy = calib["cy"] + K = np.array([[fx, 0, cx], [0, fy, cy], [0, 0, 1]]) - cam_quat = calib['camera_quaternion'] - cam_pos = calib['camera_position'] + cam_quat = calib["camera_quaternion"] + cam_pos = calib["camera_position"] - return cls(width, height, K, dist, cam_pos, cam_quat, - platform_pose_provider) + return cls(width, height, K, dist, cam_pos, cam_quat, platform_pose_provider) def save_to_file(self, filename, save_depth_viz=True): - """See base class Camera documentation. - - """ - with open(filename, 'w') as f: - f.write(''.join(['# The type of camera model.\n', - 'model_type: depth\n\n', - '# Image dimensions\n'])) - - f.write(''.join(['image_width: ',to_str(self.width),'\n'])) - f.write(''.join(['image_height: ',to_str(self.height),'\n\n'])) - - f.write('# Focal length along the image\'s x-axis.\n') - f.write(''.join(['fx: ',to_str(self.K[0,0]),'\n\n'])) - - f.write('# Focal length along the image\'s y-axis.\n') - f.write(''.join(['fy: ',to_str(self.K[1,1]),'\n\n'])) - - f.write('# Principal point is located at (cx,cy).\n') - f.write(''.join(['cx: ',to_str(self.K[0,2]),'\n'])) - f.write(''.join(['cy: ',to_str(self.K[1,2]),'\n\n'])) - - f.write(''.join(['# Distortion coefficients following OpenCv\'s ', - 'convention\n'])) + """See base class Camera documentation.""" + with open(filename, "w") as f: + f.write( + "".join( + [ + "# The type of camera model.\n", + "model_type: depth\n\n", + "# Image dimensions\n", + ] + ) + ) + + f.write("".join(["image_width: ", to_str(self.width), "\n"])) + f.write("".join(["image_height: ", to_str(self.height), "\n\n"])) + + f.write("# Focal length along the image's x-axis.\n") + f.write("".join(["fx: ", to_str(self.K[0, 0]), "\n\n"])) + + f.write("# Focal length along the image's y-axis.\n") + f.write("".join(["fy: ", to_str(self.K[1, 1]), "\n\n"])) + + f.write("# Principal point is located at (cx,cy).\n") + f.write("".join(["cx: ", to_str(self.K[0, 2]), "\n"])) + f.write("".join(["cy: ", to_str(self.K[1, 2]), "\n\n"])) + + f.write( + "".join( + ["# Distortion coefficients following OpenCv's ", "convention\n"] + ) + ) dist = self.dist if np.all(dist == 0): - dist = 'None' - - f.write(''.join(['distortion_coefficients: ', - to_str(self.dist),'\n\n'])) - - f.write(''.join(['# Quaternion (x, y, z, w) specifying the ', - 'orientation of the camera relative to\n# the ', - 'navigation coordinate system. The quaternion ', - 'represents a coordinate\n# system rotation that ', - 'takes the navigation coordinate system and ', - 'rotates it\n# into the camera coordinate ', - 'system.\n camera_quaternion: ', - to_str(self.cam_quat),'\n\n'])) - - f.write(''.join(['# Position of the camera\'s center of ', - 'projection within the navigation\n# coordinate ', - 'system.\n', - 'camera_position: ',to_str(self.cam_pos), - '\n\n'])) + dist = "None" + + f.write("".join(["distortion_coefficients: ", to_str(self.dist), "\n\n"])) + + f.write( + "".join( + [ + "# Quaternion (x, y, z, w) specifying the ", + "orientation of the camera relative to\n# the ", + "navigation coordinate system. The quaternion ", + "represents a coordinate\n# system rotation that ", + "takes the navigation coordinate system and ", + "rotates it\n# into the camera coordinate ", + "system.\n camera_quaternion: ", + to_str(self.cam_quat), + "\n\n", + ] + ) + ) + + f.write( + "".join( + [ + "# Position of the camera's center of ", + "projection within the navigation\n# coordinate ", + "system.\n", + "camera_position: ", + to_str(self.cam_pos), + "\n\n", + ] + ) + ) if self.depth_map is not None: - im = PIL.Image.fromarray(self.depth_map.astype(np.float32), - mode='F') # float32 - depth_map_fname = '%s_depth_map.tif' % os.path.splitext(filename)[0] + im = PIL.Image.fromarray( + self.depth_map.astype(np.float32), mode="F" + ) # float32 + depth_map_fname = "%s_depth_map.tif" % os.path.splitext(filename)[0] im.save(depth_map_fname) if save_depth_viz: - depth_viz_fname = ('%s/depth_vizualization.png' % - os.path.split(filename)[0]) + depth_viz_fname = ( + "%s/depth_vizualization.png" % os.path.split(filename)[0] + ) self.save_depth_viz(depth_viz_fname) def __str__(self): - string = ['model_type: depth\n'] + string = ["model_type: depth\n"] string.append(super(DepthCamera, self).__str__()) - string.append('\n') - string.append(''.join(['fx: ',repr(self._K[0,0]),'\n'])) - string.append(''.join(['fy: ',repr(self._K[1,1]),'\n'])) - string.append(''.join(['cx: ',repr(self._K[0,2]),'\n'])) - string.append(''.join(['cy: ',repr(self._K[1,2]),'\n'])) - string.append(''.join(['distortion_coefficients: ', - repr(tuple(self._dist)), - '\n'])) - string.append(''.join(['camera_quaternion: ', - repr(tuple(self._cam_quat)),'\n'])) - string.append(''.join(['camera_position: ',repr(tuple(self._cam_pos)), - '\n'])) - return ''.join(string) + string.append("\n") + string.append("".join(["fx: ", repr(self._K[0, 0]), "\n"])) + string.append("".join(["fy: ", repr(self._K[1, 1]), "\n"])) + string.append("".join(["cx: ", repr(self._K[0, 2]), "\n"])) + string.append("".join(["cy: ", repr(self._K[1, 2]), "\n"])) + string.append( + "".join(["distortion_coefficients: ", repr(tuple(self._dist)), "\n"]) + ) + string.append( + "".join(["camera_quaternion: ", repr(tuple(self._cam_quat)), "\n"]) + ) + string.append("".join(["camera_position: ", repr(tuple(self._cam_pos)), "\n"])) + return "".join(string) def _unproject_to_depth(self, points, depth_map, t=None): """Unproject image points into the world at a particular time. @@ -1468,11 +1558,11 @@ def _unproject_to_depth(self, points, depth_map, t=None): """ points = np.atleast_2d(points) - points = np.reshape(points, (2,-1)) + points = np.reshape(points, (2, -1)) ray_pos, ray_dir = self.unproject(points, t=t, normalize_ray_dir=False) for i in range(points.shape[1]): - x,y = points[:,i] + x, y = points[:, i] # Get ray distance traveled until intersection. Therefore, we need # to evaluate the depth map at x,y. We need to convert from image # coordinates (i.e., upper-left corner of upper-left pixel is 0,0) @@ -1495,11 +1585,12 @@ def _unproject_to_depth(self, points, depth_map, t=None): if ix < 0 or iy < 0 or ix >= self.width or iy >= self.height: print(x == self.width) print(y == self.height) - raise ValueError('Coordinates (%0.1f,%0.f) are outside the ' - '%ix%i image' % - (x,y,self.width,self.height)) + raise ValueError( + "Coordinates (%0.1f,%0.f) are outside the " + "%ix%i image" % (x, y, self.width, self.height) + ) - ray_pos[:,i] += ray_dir[:,i]*depth_map[iy,ix] + ray_pos[:, i] += ray_dir[:, i] * depth_map[iy, ix] return ray_pos @@ -1510,8 +1601,10 @@ class GeoStaticCamera(DepthCamera): width, height, K, dist, lat, lon, altitude, cam_quat """ - def __init__(self, width, height, K, dist, depth_map, latitude, longitude, - altitude, R): + + def __init__( + self, width, height, K, dist, depth_map, latitude, longitude, altitude, R + ): """ See additional documentation from base class above. @@ -1527,140 +1620,160 @@ def __init__(self, width, height, K, dist, depth_map, latitude, longitude, """ R = np.array(R) R /= np.linalg.det(R) - cam_pos = np.array([0,0,0]) - cam_quat = np.array([0,0,0,1]) + cam_pos = np.array([0, 0, 0]) + cam_quat = np.array([0, 0, 0, 1]) # Quaternion for level system (z down) with x-axis pointing north. - enu_quat = np.array([1/np.sqrt(2),1/np.sqrt(2),0,0]) - - platform_pose_provider = PlatformPoseFixed(pos=np.array([0,0,0]), - quat=enu_quat, - lat0=latitude, lon0=longitude, - h0=altitude) - - super(GeoStaticCamera, self).__init__(width=width, height=height, K=K, - dist=dist, cam_pos=cam_pos, - cam_quat=cam_quat, - depth_map=depth_map, - platform_pose_provider=platform_pose_provider) + enu_quat = np.array([1 / np.sqrt(2), 1 / np.sqrt(2), 0, 0]) + + platform_pose_provider = PlatformPoseFixed( + pos=np.array([0, 0, 0]), + quat=enu_quat, + lat0=latitude, + lon0=longitude, + h0=altitude, + ) + + super(GeoStaticCamera, self).__init__( + width=width, + height=height, + K=K, + dist=dist, + cam_pos=cam_pos, + cam_quat=cam_quat, + depth_map=depth_map, + platform_pose_provider=platform_pose_provider, + ) self._R = R self._depth_map = depth_map # The local ENU coordinate system is located at the camera. - self._tvec = np.array([[0],[0],[0]], dtype=np.float64) - self._camera_pose = np.hstack([R,self._tvec]) + self._tvec = np.array([[0], [0], [0]], dtype=np.float64) + self._camera_pose = np.hstack([R, self._tvec]) def __str__(self): - string = ['model_type: static\n'] + string = ["model_type: static\n"] string.append(super(GeoStaticCamera, self).__str__()) - string.append('\n') - string.append(''.join(['fx: ',repr(self._K[0,0]),'\n'])) - string.append(''.join(['fy: ',repr(self._K[1,1]),'\n'])) - string.append(''.join(['cx: ',repr(self._K[0,2]),'\n'])) - string.append(''.join(['cy: ',repr(self._K[1,2]),'\n'])) - string.append(''.join(['distortion_coefficients: ', - repr(tuple(self._dist)), - '\n'])) - string.append(''.join(['latitude: %0.8f' % self.latitude, - '\n'])) - string.append(''.join(['longitude: %0.8f' % self.longitude, - '\n'])) - string.append(''.join(['altitude: %0.8f' % self.altitude, - '\n'])) - string.append(''.join(['R: ', - repr(tuple(self.R)),'\n'])) - return ''.join(string) + string.append("\n") + string.append("".join(["fx: ", repr(self._K[0, 0]), "\n"])) + string.append("".join(["fy: ", repr(self._K[1, 1]), "\n"])) + string.append("".join(["cx: ", repr(self._K[0, 2]), "\n"])) + string.append("".join(["cy: ", repr(self._K[1, 2]), "\n"])) + string.append( + "".join(["distortion_coefficients: ", repr(tuple(self._dist)), "\n"]) + ) + string.append("".join(["latitude: %0.8f" % self.latitude, "\n"])) + string.append("".join(["longitude: %0.8f" % self.longitude, "\n"])) + string.append("".join(["altitude: %0.8f" % self.altitude, "\n"])) + string.append("".join(["R: ", repr(tuple(self.R)), "\n"])) + return "".join(string) @classmethod def load_from_file(cls, filename, platform_pose_provider=None): - """See base class Camera documentation. - - """ - with open(filename, 'r') as f: + """See base class Camera documentation.""" + with open(filename, "r") as f: calib = yaml.safe_load(f) - assert calib['model_type'] == 'static' + assert calib["model_type"] == "static" # fill in CameraInfo fields - width = calib['image_width'] - height = calib['image_height'] - dist = np.array(calib['distortion_coefficients'], dtype=np.float64) + width = calib["image_width"] + height = calib["image_height"] + dist = np.array(calib["distortion_coefficients"], dtype=np.float64) - if isinstance(dist, str) and dist == 'None': + if isinstance(dist, str) and dist == "None": dist = np.zeros(4, dtype=np.float64) - fx = calib['fx'] - fy = calib['fy'] - cx = calib['cx'] - cy = calib['cy'] - K = np.array([[fx,0,cx],[0,fy,cy],[0,0,1]]) - R = np.reshape(np.array(calib['R']), (3,3)) - latitude = calib['latitude'] - longitude = calib['longitude'] - altitude = calib['altitude'] - - depth_map_fname = '%s_depth_map.tif' % os.path.splitext(filename)[0] + fx = calib["fx"] + fy = calib["fy"] + cx = calib["cx"] + cy = calib["cy"] + K = np.array([[fx, 0, cx], [0, fy, cy], [0, 0, 1]]) + R = np.reshape(np.array(calib["R"]), (3, 3)) + latitude = calib["latitude"] + longitude = calib["longitude"] + altitude = calib["altitude"] + + depth_map_fname = "%s_depth_map.tif" % os.path.splitext(filename)[0] try: depth_map = np.asarray(PIL.Image.open(depth_map_fname)) except OSError: depth_map = None - return cls(width, height, K, dist, depth_map, latitude, longitude, - altitude, R) + return cls(width, height, K, dist, depth_map, latitude, longitude, altitude, R) def save_to_file(self, filename): - """See base class Camera documentation. - - """ - with open(filename, 'w') as f: - f.write(''.join(['# The type of camera model.\n', - 'model_type: static\n\n', - '# Image dimensions\n'])) - - f.write(''.join(['image_width: ',to_str(self.width),'\n'])) - f.write(''.join(['image_height: ',to_str(self.height),'\n\n'])) - - f.write('# Focal length along the image\'s x-axis.\n') - f.write(''.join(['fx: ',to_str(self._K[0,0]),'\n\n'])) - - f.write('# Focal length along the image\'s y-axis.\n') - f.write(''.join(['fy: ',to_str(self._K[1,1]),'\n\n'])) - - f.write('# Principal point is located at (cx,cy).\n') - f.write(''.join(['cx: ',to_str(self._K[0,2]),'\n'])) - f.write(''.join(['cy: ',to_str(self._K[1,2]),'\n\n'])) - - f.write(''.join(['# Distortion coefficients following OpenCv\'s ', - 'convention\n'])) + """See base class Camera documentation.""" + with open(filename, "w") as f: + f.write( + "".join( + [ + "# The type of camera model.\n", + "model_type: static\n\n", + "# Image dimensions\n", + ] + ) + ) + + f.write("".join(["image_width: ", to_str(self.width), "\n"])) + f.write("".join(["image_height: ", to_str(self.height), "\n\n"])) + + f.write("# Focal length along the image's x-axis.\n") + f.write("".join(["fx: ", to_str(self._K[0, 0]), "\n\n"])) + + f.write("# Focal length along the image's y-axis.\n") + f.write("".join(["fy: ", to_str(self._K[1, 1]), "\n\n"])) + + f.write("# Principal point is located at (cx,cy).\n") + f.write("".join(["cx: ", to_str(self._K[0, 2]), "\n"])) + f.write("".join(["cy: ", to_str(self._K[1, 2]), "\n\n"])) + + f.write( + "".join( + ["# Distortion coefficients following OpenCv's ", "convention\n"] + ) + ) dist = self._dist if np.all(dist == 0): - dist = 'None' - - f.write(''.join(['distortion_coefficients: ', - to_str(self._dist),'\n\n'])) - - f.write(''.join(['# Rotation matrix mapping vectors defined in an ' - 'east/north/up coordinate system\n# centered at ' - 'the camera into vectors defined in the camera' - 'coordinate system.\n', - 'R: [%0.10f, %0.10f, %0.10f,\n' - ' %0.10f, %0.10f, %0.10f,\n' - ' %0.10f, %0.10f, %0.10f]' % - tuple(self.R.ravel()), '\n\n'])) - - f.write(''.join(['# Location of the camera\'s center of ' - 'projection. Latitude and longitude are in\n# ' - 'degrees, and altitude is meters above the WGS84 ' - 'ellipsoid.\n', - 'latitude: %0.10f\n' % self.latitude, - 'longitude: %0.10f\n' % self.longitude, - 'altitude: %0.10f' % self.altitude,'\n\n'])) + dist = "None" + + f.write("".join(["distortion_coefficients: ", to_str(self._dist), "\n\n"])) + + f.write( + "".join( + [ + "# Rotation matrix mapping vectors defined in an " + "east/north/up coordinate system\n# centered at " + "the camera into vectors defined in the camera" + "coordinate system.\n", + "R: [%0.10f, %0.10f, %0.10f,\n" + " %0.10f, %0.10f, %0.10f,\n" + " %0.10f, %0.10f, %0.10f]" % tuple(self.R.ravel()), + "\n\n", + ] + ) + ) + + f.write( + "".join( + [ + "# Location of the camera's center of " + "projection. Latitude and longitude are in\n# " + "degrees, and altitude is meters above the WGS84 " + "ellipsoid.\n", + "latitude: %0.10f\n" % self.latitude, + "longitude: %0.10f\n" % self.longitude, + "altitude: %0.10f" % self.altitude, + "\n\n", + ] + ) + ) if self.depth_map is not None: - im = PIL.Image.fromarray(self.depth_map, mode='F') # float32 - depth_map_fname = '%s_depth_map.tif' % os.path.splitext(filename)[0] + im = PIL.Image.fromarray(self.depth_map, mode="F") # float32 + depth_map_fname = "%s_depth_map.tif" % os.path.splitext(filename)[0] im.save(depth_map_fname) @property @@ -1669,7 +1782,7 @@ def R(self): @R.setter def R(self, value): - self._R /= value/np.linalg.det(value) + self._R /= value / np.linalg.det(value) self._rvec = cv2.Rodrigues(self.R)[0].ravel() @property @@ -1716,8 +1829,9 @@ def project(self, points, t=None): points = np.atleast_2d(points).T # Project rays into camera coordinate system. - im_pts = cv2.projectPoints(points.T, self._rvec, self._tvec, self.K, - self.dist)[0] + im_pts = cv2.projectPoints(points.T, self._rvec, self._tvec, self.K, self.dist)[ + 0 + ] return np.squeeze(im_pts, 1).T def unproject(self, points, t=None, normalize_ray_dir=True): @@ -1734,19 +1848,20 @@ def unproject(self, points, t=None, normalize_ray_dir=True): points = np.array(points, dtype=np.float64) if points.ndim == 1: points = np.atleast_2d(points).T - points = np.reshape(points, (2,-1)) + points = np.reshape(points, (2, -1)) # Unproject rays into the camera coordinate system. - ray_dir = np.ones((3,points.shape[1]), dtype=points.dtype) - ray_dir0 = cv2.undistortPoints(np.expand_dims(points.T, 1), - self.K, self.dist, R=None) + ray_dir = np.ones((3, points.shape[1]), dtype=points.dtype) + ray_dir0 = cv2.undistortPoints( + np.expand_dims(points.T, 1), self.K, self.dist, R=None + ) ray_dir[:2] = np.squeeze(ray_dir0, 1).T # Rotate rays into the local east/north/up coordinate system. ray_dir = np.dot(self.R.T, ray_dir) if normalize_ray_dir: - ray_dir /= np.sqrt(np.sum(ray_dir**2, 0)) + ray_dir /= np.sqrt(np.sum(ray_dir ** 2, 0)) ray_pos = np.zeros_like(ray_dir) @@ -1759,10 +1874,12 @@ class MapCamera(Camera): This object is primarily built around GDAL. """ + def __init__(self, base_layer): - super(MapCamera, self).__init__(width=base_layer.res_x, - height=base_layer.res_y) + super(MapCamera, self).__init__(width=base_layer.res_x, height=base_layer.res_y) self.base_layer = base_layer def project(self, points, t=None): - return np.array([self.base_layer.meters_to_raster(point) for point in points.T]).T + return np.array( + [self.base_layer.meters_to_raster(point) for point in points.T] + ).T diff --git a/kamera/colmap_processing/image_renderer.py b/kamera/colmap_processing/image_renderer.py index af7f720..9bcd4b7 100644 --- a/kamera/colmap_processing/image_renderer.py +++ b/kamera/colmap_processing/image_renderer.py @@ -6,8 +6,7 @@ import PIL -def save_gif(images, fname, duration=500, - loop=0): +def save_gif(images, fname, duration=500, loop=0): """ :param img1 :type img1: @@ -25,12 +24,12 @@ def save_gif(images, fname, duration=500, :type loop: int """ images = [PIL.Image.fromarray(img) for img in images] - images[0].save(fname, save_all=True, append_images=images[1:], - duration=duration, loop=loop) + images[0].save( + fname, save_all=True, append_images=images[1:], duration=duration, loop=loop + ) -def warp_perspective(image, h, dsize, interpolation=0, use_pyr=True, - precrop=True): +def warp_perspective(image, h, dsize, interpolation=0, use_pyr=True, precrop=True): """ :param h: Homography that takes output image coordinates and returns source image coordinates. @@ -69,26 +68,26 @@ def warp_perspective(image, h, dsize, interpolation=0, use_pyr=True, if precrop: # Select points from corners of output image. - im_pts = np.ones((3,4), np.float32) - im_pts[0] = [0,1,1,0] + im_pts = np.ones((3, 4), np.float32) + im_pts[0] = [0, 1, 1, 0] im_pts[0] *= dsize[0] - im_pts[1] = [0,0,1,1] + im_pts[1] = [0, 0, 1, 1] im_pts[1] *= dsize[1] src_im_pts = np.dot(h, im_pts) src_im_pts[0] /= src_im_pts[2] src_im_pts[1] /= src_im_pts[2] # Collect the bounding box on src_img - x_range = np.array([src_im_pts[0].min(),src_im_pts[0].max()]) - y_range = np.array([src_im_pts[1].min(),src_im_pts[1].max()]) + x_range = np.array([src_im_pts[0].min(), src_im_pts[0].max()]) + y_range = np.array([src_im_pts[1].min(), src_im_pts[1].max()]) # Clamp to actual image dimensions if exceeded. # Pad by p for interpolation. p = 8 - x_range[0] = np.maximum(0, x_range[0]-p) - x_range[1] = np.minimum(res_x, x_range[1]+p) - y_range[0] = np.maximum(0, y_range[0]-p) - y_range[1] = np.minimum(res_y, y_range[1]+p) + x_range[0] = np.maximum(0, x_range[0] - p) + x_range[1] = np.minimum(res_x, x_range[1] + p) + y_range[0] = np.maximum(0, y_range[0] - p) + y_range[1] = np.minimum(res_y, y_range[1] + p) x_range = np.round(x_range).astype(np.int) y_range = np.round(y_range).astype(np.int) @@ -96,50 +95,68 @@ def warp_perspective(image, h, dsize, interpolation=0, use_pyr=True, # Want a homography that maps from the full version of image to the # cropped version defined by x_range and y_range. h_crop = np.identity(3) - h_crop[:2,2] = -x_range[0], -y_range[0] + h_crop[:2, 2] = -x_range[0], -y_range[0] h = np.dot(h_crop, h) - image = image[y_range[0]:y_range[1],x_range[0]:x_range[1]] + image = image[y_range[0] : y_range[1], x_range[0] : x_range[1]] if 0 in image.shape: if image.ndim == 3: - return np.zeros((dsize[1],dsize[0],3), image.dtype) + return np.zeros((dsize[1], dsize[0], 3), image.dtype) else: - return np.zeros((dsize[1],dsize[0]), image.dtype) + return np.zeros((dsize[1], dsize[0]), image.dtype) flags = interpolation | cv2.WARP_INVERSE_MAP warped_image = cv2.warpPerspective(image, h, dsize=dsize, flags=flags) return warped_image + def visualize_camera_and_points(pose_mat, points): fig = plt.figure() - ax = fig.add_subplot(111, projection='3d') + ax = fig.add_subplot(111, projection="3d") # Plot camera position cam_pos = pose_mat[:3, 3] - ax.scatter(cam_pos[0], cam_pos[1], cam_pos[2], c='r', marker='^', label='Camera') + ax.scatter(cam_pos[0], cam_pos[1], cam_pos[2], c="r", marker="^", label="Camera") # Plot points points_np = np.array(points) - ax.scatter(points_np[:,0], points_np[:,1], points_np[:,2], c='b', marker='o', label='Points') + ax.scatter( + points_np[:, 0], + points_np[:, 1], + points_np[:, 2], + c="b", + marker="o", + label="Points", + ) # Draw camera orientation axes axes_length = 1.0 rotation_matrix = pose_mat[:3, :3] - for i, color in zip(range(3), ['r', 'g', 'b']): + for i, color in zip(range(3), ["r", "g", "b"]): axis = rotation_matrix[:, i] * axes_length - ax.quiver(cam_pos[0], cam_pos[1], cam_pos[2], - axis[0], axis[1], axis[2], color=color) + ax.quiver( + cam_pos[0], cam_pos[1], cam_pos[2], axis[0], axis[1], axis[2], color=color + ) - ax.set_xlabel('X') - ax.set_ylabel('Y') - ax.set_zlabel('Z') + ax.set_xlabel("X") + ax.set_ylabel("Y") + ax.set_zlabel("Z") ax.legend() plt.show() -def render_view(src_cm, src_img, src_t, dst_cm, dst_t, interpolation=1, - block_size=1, homog_approx=False, world_model=None): +def render_view( + src_cm, + src_img, + src_t, + dst_cm, + dst_t, + interpolation=1, + block_size=1, + homog_approx=False, + world_model=None, +): """Render view onto destination camera from a source camera image. :param src_cm: Camera model for the camera that acquired src_img. @@ -185,15 +202,16 @@ def render_view(src_cm, src_img, src_t, dst_cm, dst_t, interpolation=1, """ if world_model is None: - surface_distance = 1e5 + surface_distance = 1e4 if src_img is not None: if src_cm.width != src_img.shape[1] or src_cm.height != src_img.shape[0]: - print('Camera model for image topic %s with encoded image ' - 'size %i x %i is being used to render images with ' - 'size %i x %i' % (src_cm.image_topic,src_cm.width, - src_cm.height,src_img.shape[1], - src_img.shape[0])) + print( + "Camera model with encoded image " + "size %i x %i is being used to render images with " + "size %i x %i" + % (src_cm.width, src_cm.height, src_img.shape[1], src_img.shape[0]) + ) def get_mask(X, Y, edge_buffer=4): mask = np.logical_and(X > edge_buffer, Y > edge_buffer) @@ -205,17 +223,17 @@ def get_mask(X, Y, edge_buffer=4): if homog_approx: if False: # Select points from a square centered on the focal plane. - im_pts = np.zeros((2,4), np.float32) - im_pts[0] = [0.25,0.75,0.75,0.25] + im_pts = np.zeros((2, 4), np.float32) + im_pts[0] = [0.25, 0.75, 0.75, 0.25] im_pts[0] *= dst_cm.width - im_pts[1] = [0.25,0.25,0.75,0.75] + im_pts[1] = [0.25, 0.25, 0.75, 0.75] im_pts[1] *= dst_cm.height else: # Select points from focal plane corners. - im_pts = np.zeros((2,4), np.float32) - im_pts[0] = [0,1,1,0] + im_pts = np.zeros((2, 4), np.float32) + im_pts[0] = [0, 1, 1, 0] im_pts[0] *= dst_cm.width - im_pts[1] = [0,0,1,1] + im_pts[1] = [0, 0, 1, 1] im_pts[1] *= dst_cm.height # Unproject rays into camera coordinate system. @@ -231,10 +249,11 @@ def get_mask(X, Y, edge_buffer=4): im_pts_src = src_cm.project(points, src_t).astype(np.float32) h = cv2.findHomography(im_pts.T, im_pts_src.T)[0] - #np.dot(h, [res_x/2,res_y/2,1]) - dst_img = warp_perspective(src_img, h, (dst_cm.width, dst_cm.height), - interpolation=interpolation) - mask = np.ones((dst_img.shape[0],dst_img.shape[1]), dtype=np.bool) + # np.dot(h, [res_x/2,res_y/2,1]) + dst_img = warp_perspective( + src_img, h, (dst_cm.width, dst_cm.height), interpolation=interpolation + ) + mask = np.ones((dst_img.shape[0], dst_img.shape[1]), dtype=np.bool) return dst_img, mask else: if interpolation == 0: @@ -250,10 +269,10 @@ def get_mask(X, Y, edge_buffer=4): if block_size == 1: # Densely sample all pixels. - x = np.linspace(0, dst_cm.width-1, dst_cm.width) - y = np.linspace(0, dst_cm.height-1, dst_cm.height) + x = np.linspace(0, dst_cm.width - 1, dst_cm.width) + y = np.linspace(0, dst_cm.height - 1, dst_cm.height) xb, yb = np.meshgrid(x, y) - im_pts = np.vstack([xb.ravel(),yb.ravel()]) + im_pts = np.vstack([xb.ravel(), yb.ravel()]) # Unproject rays into camera coordinate system. ray_pos, ray_dir = dst_cm.unproject(im_pts, dst_t) @@ -267,8 +286,8 @@ def get_mask(X, Y, edge_buffer=4): im_pts_src = src_cm.project(points, src_t).astype(np.float32) - X = np.reshape(im_pts_src[0], (dst_cm.height,dst_cm.width)) - Y = np.reshape(im_pts_src[1], (dst_cm.height,dst_cm.width)) + X = np.reshape(im_pts_src[0], (dst_cm.height, dst_cm.width)) + Y = np.reshape(im_pts_src[1], (dst_cm.height, dst_cm.width)) else: # Define block size and calculate grid sampling points nx = dst_cm.width // block_size @@ -277,7 +296,7 @@ def get_mask(X, Y, edge_buffer=4): y = np.linspace(0, dst_cm.height - 1, ny) # Create sparse grid with consistent indexing - xb, yb = np.meshgrid(x, y, indexing='ij') # Shape: (nx, ny) + xb, yb = np.meshgrid(x, y, indexing="ij") # Shape: (nx, ny) sampled_im_pts = np.vstack([xb.ravel(), yb.ravel()]) # Shape: (2, nx*ny) # Unproject rays into camera coordinate system @@ -298,22 +317,36 @@ def get_mask(X, Y, edge_buffer=4): Y = np.reshape(im_pts_src[1], (nx, ny)) # Shape: (nx, ny) # Create the interpolators with grid axes (x, y) - interpx = RegularGridInterpolator((x, y), X, - bounds_error=False, fill_value=np.nan) - interpy = RegularGridInterpolator((x, y), Y, - bounds_error=False, fill_value=np.nan) + interpx = RegularGridInterpolator( + (x, y), X, bounds_error=False, fill_value=np.nan + ) + interpy = RegularGridInterpolator( + (x, y), Y, bounds_error=False, fill_value=np.nan + ) # Define dense grid for evaluation with consistent indexing xd = np.linspace(0, dst_cm.width - 1, dst_cm.width) yd = np.linspace(0, dst_cm.height - 1, dst_cm.height) - y_grid, x_grid = np.meshgrid(yd, xd, indexing='ij') # Shape: (height, width) + y_grid, x_grid = np.meshgrid( + yd, xd, indexing="ij" + ) # Shape: (height, width) # Prepare points as (n_points, 2) array with (x, y) coordinates - dense_points = np.vstack([x_grid.ravel(), y_grid.ravel()]).T # Shape: (width*height, 2) + dense_points = np.vstack( + [x_grid.ravel(), y_grid.ravel()] + ).T # Shape: (width*height, 2) # Evaluate interpolators with dense_points - X_dense = interpx(dense_points).reshape(dst_cm.height, dst_cm.width).astype(np.float32) - Y_dense = interpy(dense_points).reshape(dst_cm.height, dst_cm.width).astype(np.float32) + X_dense = ( + interpx(dense_points) + .reshape(dst_cm.height, dst_cm.width) + .astype(np.float32) + ) + Y_dense = ( + interpy(dense_points) + .reshape(dst_cm.height, dst_cm.width) + .astype(np.float32) + ) dst_img = cv2.remap(src_img, X_dense, Y_dense, interpolation) @@ -325,15 +358,13 @@ def get_mask(X, Y, edge_buffer=4): def show_warped_points(src_cm, src_img, src_t, dst_cm, dst_t, block_size=1): - """Plot out points to be samples in the source image. - - """ + """Plot out points to be samples in the source image.""" if block_size == 1: # Densely sample all pixels. - x = np.linspace(0, dst_cm.width-1, dst_cm.width) - y = np.linspace(0, dst_cm.height-1, dst_cm.height) - X,Y = np.meshgrid(x, y) - im_pts = np.vstack([X.ravel(),Y.ravel()]) + x = np.linspace(0, dst_cm.width - 1, dst_cm.width) + y = np.linspace(0, dst_cm.height - 1, dst_cm.height) + X, Y = np.meshgrid(x, y) + im_pts = np.vstack([X.ravel(), Y.ravel()]) # Unproject rays into camera coordinate system. ray_pos, ray_dir = dst_cm.unproject(im_pts, dst_t) @@ -344,12 +375,12 @@ def show_warped_points(src_cm, src_img, src_t, dst_cm, dst_t, block_size=1): # Sample the full projection equation every 'blocksize' pixels and # interpolate in between. - nx = dst_cm.width//block_size - ny = dst_cm.height//block_size - x = np.linspace(0, dst_cm.width-1, nx), - y = np.linspace(0, dst_cm.height-1, ny) - X,Y = np.meshgrid(x, y) - im_pts = np.vstack([X.ravel(),Y.ravel()]) + nx = dst_cm.width // block_size + ny = dst_cm.height // block_size + x = (np.linspace(0, dst_cm.width - 1, nx),) + y = np.linspace(0, dst_cm.height - 1, ny) + X, Y = np.meshgrid(x, y) + im_pts = np.vstack([X.ravel(), Y.ravel()]) # Unproject rays into camera coordinate system. ray_pos, ray_dir = dst_cm.unproject(im_pts, dst_t) @@ -357,11 +388,18 @@ def show_warped_points(src_cm, src_img, src_t, dst_cm, dst_t, block_size=1): im_pts_src = src_cm.project(ray_dir, src_t).astype(np.float32) - plt.plot(im_pts_src[0], im_pts_src[1], 'ro') + plt.plot(im_pts_src[0], im_pts_src[1], "ro") -def stitch_images(src_list, dst_cm, dst_t, interpolation=1, block_size=1, - homog_approx=False, world_model=None): +def stitch_images( + src_list, + dst_cm, + dst_t, + interpolation=1, + block_size=1, + homog_approx=False, + world_model=None, +): """ :param src_list: List of frames and cameras of the form [src_cm, src_img, src_t]. @@ -393,8 +431,7 @@ def stitch_images(src_list, dst_cm, dst_t, interpolation=1, block_size=1, out_dtype = src_list[0][1].dtype if out_dtype == np.uint8: out_channels = 3 - dst_img = np.zeros((dst_cm.height, dst_cm.width, out_channels), - out_dtype) + dst_img = np.zeros((dst_cm.height, dst_cm.width, out_channels), out_dtype) else: out_channels = 1 dst_img = np.zeros((dst_cm.height, dst_cm.width), out_dtype) @@ -402,13 +439,19 @@ def stitch_images(src_list, dst_cm, dst_t, interpolation=1, block_size=1, for i in range(len(src_list)): src_cm, src_img, src_t = src_list[i] - #show_warped_points(src_cm, src_img, src_t, dst_cm, dst_t, 10) + # show_warped_points(src_cm, src_img, src_t, dst_cm, dst_t, 10) - img, mask = render_view(src_cm, src_img, src_t, dst_cm, dst_t, - interpolation=interpolation, - block_size=block_size, - homog_approx=homog_approx, - world_model=world_model) + img, mask = render_view( + src_cm, + src_img, + src_t, + dst_cm, + dst_t, + interpolation=interpolation, + block_size=block_size, + homog_approx=homog_approx, + world_model=world_model, + ) if out_channels == 3: if img.ndim == 2: @@ -417,7 +460,7 @@ def stitch_images(src_list, dst_cm, dst_t, interpolation=1, block_size=1, # Couldn't find a more elegant/efficient way to hangle a 2-D mask with # an RGB image. mask2 = np.zeros_like(dst_img, dtype=np.bool) - mask2[:,:,0] = mask2[:,:,1] = mask2[:,:,2] = mask + mask2[:, :, 0] = mask2[:, :, 1] = mask2[:, :, 2] = mask dst_img[mask2] = img[mask2] else: From 79fa0bb6fa20a3cc976fba92366a8aafa3e400df Mon Sep 17 00:00:00 2001 From: Adam Romlein Date: Thu, 19 Dec 2024 20:30:04 -0500 Subject: [PATCH 04/20] Add new calibrations, refactor, use pycolmap instead of custom load scripts, create utility and dataclasses. Testing several different alignment methods, default iterative is still currently the best. --- kamera/postflight/alignment.py | 689 +++++++++++++++++++++++ kamera/postflight/colmap.py | 434 ++++++++++++++ kamera/postflight/scripts/calibration.py | 82 +++ 3 files changed, 1205 insertions(+) create mode 100644 kamera/postflight/alignment.py create mode 100644 kamera/postflight/colmap.py create mode 100644 kamera/postflight/scripts/calibration.py diff --git a/kamera/postflight/alignment.py b/kamera/postflight/alignment.py new file mode 100644 index 0000000..92ad6fe --- /dev/null +++ b/kamera/postflight/alignment.py @@ -0,0 +1,689 @@ +import random +import numpy as np +from dataclasses import dataclass +from typing import List, NamedTuple, Optional, Tuple +from scipy.optimize import minimize, fminbound +from scipy.spatial.transform import Rotation +import pycolmap +from kamera.colmap_processing.camera_models import StandardCamera +from kamera.sensor_models.nav_state import NavStateINSJson + + +@dataclass +class VisiblePoint: + """Point visible in a camera view.""" + + point_3d: np.ndarray # 3D point coordinates (3,) + point_2d: np.ndarray # 2D observation in image (2,) + uncertainty: float # Point uncertainty/error + time: float + visible: bool = False # Whether point is visible in this camera + + +@dataclass +class RotationEstimate: + """Result of rotation estimation.""" + + quaternion: np.ndarray # Estimated rotation quaternion (x,y,z,w) + covariance: np.ndarray # 3x3 covariance matrix in angle-axis space + fisher_information: np.ndarray # Fisher information matrix + num_inliers: int # Number of inlier observations used + mean_error: float # Mean error of the estimate + + +def compute_jacobian(points: np.ndarray, R: np.ndarray) -> np.ndarray: + """ + Compute Jacobian of rotation with respect to angle-axis parameters. + + Args: + points: Nx3 array of 3D points + R: 3x3 rotation matrix + Returns: + 3Nx3 Jacobian matrix + """ + jac = np.zeros((3 * len(points), 3)) + for i, p in enumerate(points): + # Skew-symmetric matrix for cross product + skew = np.array([[0, -p[2], p[1]], [p[2], 0, -p[0]], [-p[1], p[0], 0]]) + jac[3 * i : 3 * (i + 1)] = (-R @ skew)[0] # First row + jac[3 * i + 1 : 3 * (i + 2)] = (-R @ skew)[1] # Second row + jac[3 * i + 2 : 3 * (i + 3)] = (-R @ skew)[2] # Third row + return jac + + +def compute_fisher_information( + points: np.ndarray, R: np.ndarray, weights: np.ndarray +) -> np.ndarray: + """Compute Fisher Information Matrix without forming full weight matrix.""" + J = compute_jacobian(points, R) + fisher = np.zeros((3, 3)) + for i in range(len(weights)): + block = J[3 * i : 3 * (i + 3)] + fisher += weights[i] * (block.T @ block) + return fisher + + +def compute_covariance( + R: np.ndarray, observations: List[List[VisiblePoint]] +) -> np.ndarray: + """ + Compute covariance matrix for rotation estimate. + + Args: + R: 3x3 rotation matrix + observations: List of visible points per camera + Returns: + 3x3 covariance matrix in angle-axis space + """ + points = [] + weights = [] + + for camera_obs in observations: + for obs in camera_obs: + points.append(obs.point_3d) + weights.append(1.0 / (obs.uncertainty**2 + 1e-10)) + + points = np.array(points) + weights = np.array(weights) + + fisher = compute_fisher_information(points, R, weights) + return np.linalg.inv(fisher) + + +def weighted_horn_alignment_partial( + observations: np.ndarray[List[VisiblePoint]], + sfm_quats: np.ndarray, + ins_quats: np.ndarray, + min_points_per_image: int = 3, + ransac_iters: int = 100, + error_threshold: float = 0.1, + max_3d_points: int = 5000, +) -> RotationEstimate: + """ + Find rotation between INS and camera frames with partial point visibility. + + Args: + observations: List of visible points for each camera + sfm_quats: Nx4 array of SfM-derived camera quaternions + ins_quats: Nx4 array of INS-measured quaternions + min_points_per_image: Minimum points needed per camera + ransac_iters: Number of RANSAC iterations + error_threshold: Error threshold for inlier classification + + Returns: + RotationEstimate containing quaternion and uncertainty information + """ + + print(f"Number of observations: {len(observations)}") + print(f"Number of sfm quats: {len(sfm_quats)}, {len(ins_quats)}") + + def compute_rotation_for_subset( + image_indices: List[int], max_3d_points: int = 1000 + ) -> Tuple[Optional[np.ndarray], Optional[float], Optional[List[int]]]: + """Compute rotation for a subset of images.""" + points_ins = [] + points_cam = [] + weights = [] + inlier_indices = [] + + for idx, image_idx in enumerate(image_indices): + # Get visible points for this camera + visible_obs = [obs for obs in observations[image_idx] if obs.visible] + + if len(visible_obs) < min_points_per_image: + print("Not enough visible observations, skipping.") + return None, None, None + + # errors = [obs.uncertainty for obs in visible_obs] + # keep the smallest error points + # keep_idx = np.argsort(errors)[:max_3d_points] + # visible_obs = np.array(visible_obs)[keep_idx] + + R_ins = Rotation.from_quat(ins_quats[image_idx]) + R_sfm = Rotation.from_quat(sfm_quats[image_idx]) + + for obs in visible_obs: + # Transform point through both rotations + p_ins = R_ins.apply(obs.point_3d) + p_cam = R_sfm.apply(obs.point_3d) + + points_ins.append(p_ins) + points_cam.append(p_cam) + weights.append(1.0 / (obs.uncertainty**2 + 1e-10)) + inlier_indices.append(idx) + + if len(points_ins) < 5: # Need minimum points for reliable estimate + print( + f"Number of points is {points_ins}, which is less than the min of 5 needed." + ) + return None, None, None + + points_ins = np.array(points_ins) + points_cam = np.array(points_cam) + weights = np.array(weights) + + # Weighted Horn method + centroid_ins = np.sum(weights[:, None] * points_ins, axis=0) / np.sum(weights) + centroid_cam = np.sum(weights[:, None] * points_cam, axis=0) / np.sum(weights) + + centered_ins = points_ins - centroid_ins + centered_cam = points_cam - centroid_cam + + H = (centered_ins.T * weights) @ centered_cam + U, _, Vt = np.linalg.svd(H) + R = Vt.T @ U.T + + if np.linalg.det(R) < 0: + Vt[-1, :] *= -1 + R = Vt.T @ U.T + + errors = np.linalg.norm(R @ centered_ins.T - centered_cam.T, axis=0) + + # Identify inliers + inliers = errors < error_threshold + if np.sum(inliers) < min_points_per_image: + print( + f"Num inliers is {np.sum(inliers)}, which is less than the min required of {min_points_per_image}." + ) + print(f"Mean error is {np.mean(errors)}, threshold is {error_threshold}.") + return None, None, None + + mean_error = np.mean(errors[inliers]) + return R, mean_error, [inlier_indices[i] for i in np.where(inliers)[0]] + + best_R = None + best_error = float("inf") + best_inliers = [] + n_images = len(observations) + + for _ in range(ransac_iters): + # Sample subset of images + n_sample = min(5, n_images) + image_indices = np.random.choice(n_images, n_sample, replace=False) + + R, error, inliers = compute_rotation_for_subset( + image_indices, max_3d_points=max_3d_points + ) + if R is not None and error < best_error: + # Verify with all images + R_full, error_full, inliers_full = compute_rotation_for_subset( + inliers, + ) + if R_full is not None and error_full < best_error: + best_R = R_full + best_error = error_full + best_inliers = inliers_full + + if best_R is None: + raise RuntimeError("Could not find valid rotation - check visibility") + + print(best_R) + + # Compute uncertainty + # covariance = compute_covariance(best_R, observations) + # fisher = compute_fisher_information( + # np.array( + # [ + # obs.point_3d + # for i in best_inliers + # for obs in observations[i] + # if obs.visible + # ] + # ), + # best_R, + # np.array( + # [ + # 1.0 / (obs.uncertainty**2 + 1e-10) + # for i in best_inliers + # for obs in observations[i] + # if obs.visible + # ] + # ), + # ) + covariance = np.eye(3) + fisher = np.eye(3) + + return RotationEstimate( + quaternion=Rotation.from_matrix(best_R).as_quat(), + covariance=covariance, + fisher_information=fisher, + num_inliers=len(best_inliers), + mean_error=best_error, + ) + + +def analyze_rotation_estimate(estimate: RotationEstimate) -> None: + """ + Analyze and print information about rotation estimate quality. + + Args: + estimate: RotationEstimate from alignment + """ + # Extract principal uncertainties + eigenvals, eigenvecs = np.linalg.eigh(estimate.covariance) + std_devs = np.sqrt(eigenvals) + + print("\nRotation Alignment Analysis") + print("==========================") + print(f"Quaternion (x,y,z,w): {estimate.quaternion}") + print(f"\nNumber of inliers: {estimate.num_inliers}") + print(f"Mean error: {estimate.mean_error:.6f}") + + print("\nUncertainty Analysis:") + print("Standard deviations (degrees):") + for i, std in enumerate(std_devs): + print(f" Axis {i+1}: {np.degrees(std):.4f}°") + + # Condition number of Fisher Information + cond = np.linalg.cond(estimate.fisher_information) + print(f"\nFisher Information condition number: {cond:.2e}") + + # 99% confidence intervals + conf_intervals = 2.576 * std_devs + print("\n99% Confidence intervals (degrees):") + for i, interval in enumerate(conf_intervals): + print(f" Axis {i+1}: ±{np.degrees(interval):.4f}°") + + +class RANSACParams: + def __init__( + self, + min_samples: int = 3, + max_iterations: int = 1000, + inlier_threshold: float = 0.1, # radians + min_inliers_ratio: float = 0.5, + ): + self.min_samples = min_samples + self.max_iterations = max_iterations + self.inlier_threshold = inlier_threshold + self.min_inliers_ratio = min_inliers_ratio + + +def compute_rotation_horn( + sfm_rotations: np.ndarray, ins_rotations: np.ndarray +) -> np.ndarray: + """ + Compute optimal rotation matrix using Horn's method for a subset of rotations. + + Args: + sfm_rotations: Array of SfM rotation matrices (N, 3, 3) + ins_rotations: Array of INS rotation matrices (N, 3, 3) + + Returns: + optimal_rotation: 3x3 rotation matrix + """ + # Build correlation matrix + M = sum(ins_R @ sfm_R.T for sfm_R, ins_R in zip(sfm_rotations, ins_rotations)) + + # Perform SVD + U, _, Vt = np.linalg.svd(M) + + # Ensure proper rotation (det = 1) + det = np.linalg.det(U @ Vt) + S = np.eye(3) + if det < 0: + S[2, 2] = -1 + + return U @ S @ Vt + + +def compute_alignment_errors( + sfm_rotations: np.ndarray, ins_rotations: np.ndarray, optimal_rotation: np.ndarray +) -> np.ndarray: + """ + Compute angular errors between aligned rotations. + + Args: + sfm_rotations: Array of SfM rotation matrices + ins_rotations: Array of INS rotation matrices + optimal_rotation: Computed optimal rotation matrix + + Returns: + errors: Array of angular errors in radians + """ + errors = [] + for sfm_R, ins_R in zip(sfm_rotations, ins_rotations): + aligned_R = optimal_rotation @ sfm_R + relative_R = aligned_R.T @ ins_R + angle_error = abs(Rotation.from_matrix(relative_R).magnitude()) + errors.append(angle_error) + return np.array(errors) + + +def register_camera_horn_ransac( + sfm_poses: List[np.ndarray], + ins_poses: List[np.ndarray], + points_per_image: Optional[List] = None, + colmap_camera: Optional[object] = None, + ransac_params: Optional[RANSACParams] = None, +) -> Tuple[np.ndarray, float, np.ndarray]: + """ + Register camera poses using Horn's method with RANSAC for robust estimation. + + Args: + sfm_poses: List of quaternions from Structure from Motion + ins_poses: List of quaternions from INS measurements + points_per_image: Optional list of 2D-3D point correspondences + colmap_camera: Optional COLMAP camera object + ransac_params: Optional RANSAC parameters + + Returns: + optimal_rotation: 3x3 rotation matrix + best_rmse: Root mean square error of the alignment + inlier_mask: Boolean array indicating inlier poses + """ + if ransac_params is None: + ransac_params = RANSACParams() + + # Convert quaternions to rotation matrices + sfm_rotations = np.array([Rotation.from_quat(q).as_matrix() for q in sfm_poses]) + ins_rotations = np.array([Rotation.from_quat(q).as_matrix() for q in ins_poses]) + + num_poses = len(sfm_poses) + best_rotation = None + best_rmse = float("inf") + best_inlier_mask = None + + # RANSAC iterations + for _ in range(ransac_params.max_iterations): + # Randomly sample pose pairs + sample_indices = random.sample(range(num_poses), ransac_params.min_samples) + sample_sfm = sfm_rotations[sample_indices] + sample_ins = ins_rotations[sample_indices] + + # Compute candidate rotation using sampled pairs + candidate_rotation = compute_rotation_horn(sample_sfm, sample_ins) + + # Compute errors for all poses using this rotation + errors = compute_alignment_errors( + sfm_rotations, ins_rotations, candidate_rotation + ) + + # Identify inliers + print(np.mean(errors)) + inlier_mask = errors < ransac_params.inlier_threshold + num_inliers = np.sum(inlier_mask) + + # Check if we have enough inliers + if num_inliers / num_poses >= ransac_params.min_inliers_ratio: + # Recompute rotation using all inliers + inlier_sfm = sfm_rotations[inlier_mask] + inlier_ins = ins_rotations[inlier_mask] + refined_rotation = compute_rotation_horn(inlier_sfm, inlier_ins) + + # Compute RMSE for refined rotation + refined_errors = compute_alignment_errors( + sfm_rotations, ins_rotations, refined_rotation + ) + rmse = np.sqrt(np.mean(refined_errors[inlier_mask] ** 2)) + + # Update best solution if this is better + if rmse < best_rmse: + best_rotation = refined_rotation + best_rmse = rmse + best_inlier_mask = inlier_mask + + if best_rotation is None: + raise RuntimeError( + "RANSAC failed to find a good alignment. Consider adjusting parameters." + ) + + # Verify alignment using 3D points if available + if points_per_image and colmap_camera: + verify_alignment(points_per_image, best_rotation, colmap_camera) + + # Print some statistics about the solution + inlier_percentage = np.sum(best_inlier_mask) / len(best_inlier_mask) * 100 + print("RANSAC statistics:") + print(f"- Inlier percentage: {inlier_percentage:.1f}%") + print(f"- Final RMSE: {best_rmse:.3f} radians") + + return best_rotation, best_rmse, best_inlier_mask + + +def verify_alignment( + points_per_image: List, optimal_rotation: np.ndarray, colmap_camera: object +) -> None: + """ + Verify alignment quality using 3D point reprojection. + """ + reprojection_errors = [] + + for points in points_per_image: + for pt in points: + point_2d = pt.image_point + point_3d = pt.point_3d + # Transform 3D point using optimal rotation + transformed_point = optimal_rotation @ point_3d + + # Project 3D point using camera intrinsics + fx, fy, cx, cy = colmap_camera.params[:4] # Assuming standard pinhole model + + projected_x = fx * transformed_point[0] / transformed_point[2] + cx + projected_y = fy * transformed_point[1] / transformed_point[2] + cy + + error = np.sqrt( + (projected_x - point_2d[0]) ** 2 + (projected_y - point_2d[1]) ** 2 + ) + reprojection_errors.append(error) + + mean_reprojection_error = np.mean(reprojection_errors) + print(f"Mean reprojection error: {mean_reprojection_error:.2f} pixels") + + +def iterative_alignment( + sfm_quats: List[np.ndarray], + ins_quats: List[np.ndarray], + points_per_image: List[List[VisiblePoint]], + colmap_camera: pycolmap._core.Camera, + nav_state_provider: NavStateINSJson, +): + # Both quaternions are of the form (x, y, z, w) and represent a coordinate + # system rotation. + cam_quats = [ + (Rotation.from_quat(sfm_quats[k]) * Rotation.from_quat(ins_quats[k])) + .inv() + .as_quat() + for k in range(len(ins_quats)) + ] + + K = colmap_camera.calibration_matrix() + if colmap_camera.model.name == "OPENCV": + fx, fy, cx, cy, d1, d2, d3, d4 = colmap_camera.params + elif colmap_camera.model.name == "SIMPLE_RADIAL": + d1 = d2 = d3 = d4 = 0 + elif colmap_camera.model.name == "PINHOLE": + d1 = d2 = d3 = d4 = 0 + else: + raise SystemError(f"Unexpected camera model found: {colmap_camera.model.name}") + dist = np.array([d1, d2, d3, d4]) + + def cam_quat_error(cam_quat: np.ndarray) -> float: + camera_model = StandardCamera( + colmap_camera.width, + colmap_camera.height, + K, + dist, + [0, 0, 0], + cam_quat, + platform_pose_provider=nav_state_provider, + ) + + err = [] + + # check quaternion alignment over all images + for pts in points_per_image: + xys = [] + xyzs = [] + # uncertainties = [] + # time is the same for all points + t = pts[0].time + max_uncertainty = 1 + for pt in pts: + if pt.uncertainty < max_uncertainty: + xys.append(pt.point_2d) + xyzs.append(pt.point_3d) + xys = np.array(xys) + xyzs = np.array(xyzs) + # Error in meters. + # TODO: Add some error thresholding + + # Rays coming out of the camera in the direction of the imaged points. + ray_pos, ray_dir = camera_model.unproject(xys.T, t) + + # Direction coming out of the camera pointing at the actual 3-D points' + # locatinos. + ray_dir2 = xyzs.T - ray_pos + d = np.sqrt(np.sum((ray_dir2) ** 2, axis=0)) + ray_dir2 /= d + + dp = np.minimum(np.sum(ray_dir * ray_dir2, axis=0), 1) + dp = np.maximum(dp, -1) + theta = np.arccos(dp) + err_ = np.sin(theta) * d + # err.append(np.percentile(err_, 90)) + err.append(np.median(err_)) + + # print("Average uncertainty: ") + # print(np.mean(uncertainties)) + # err = err[err < np.percentile(err, 90)] + + err = np.mean(err) + # print('RMS reproject error for quat', cam_quat, ': %0.8f' % err) + return err + + print("Iterating through %s quaternion guesses." % len(cam_quats)) + random.shuffle(cam_quats) + best_quat = None + best_err = np.inf + for i in range(len(cam_quats)): + cam_quat = cam_quats[i] + + err = cam_quat_error(cam_quat) + if err < best_err: + best_err = err + best_quat = cam_quat + + if best_err < 5: + break + + print("Best error: ", best_err) + print("Best quat: ") + print(cam_quat) + + print("Minimizing error over camera quaternions") + + ret = minimize(cam_quat_error, best_quat) + best_quat = ret.x / np.linalg.norm(ret.x) + ret = minimize(cam_quat_error, best_quat, method="BFGS") + best_quat = ret.x / np.linalg.norm(ret.x) + ret = minimize(cam_quat_error, best_quat, method="Powell") + best_quat = ret.x / np.linalg.norm(ret.x) + + # Sequential 1-D optimizations. + for i in range(4): + + def set_x(x): + quat = best_quat.copy() + quat = quat / np.linalg.norm(quat) + while abs(quat[i] - x) > 1e-6: + quat[i] = x + quat = quat / np.linalg.norm(quat) + + return quat + + def func(x): + return cam_quat_error(set_x(x)) + + x = np.linspace(-1, 1, 100) + x = sorted(np.hstack([x, best_quat[i]])) + y = [func(x_) for x_ in x] + x = fminbound(func, x[np.argmin(y) - 1], x[np.argmin(y) + 1], xtol=1e-8) + best_quat = set_x(x) + + camera_model = StandardCamera( + colmap_camera.width, + colmap_camera.height, + K, + dist, + [0, 0, 0], + best_quat, + platform_pose_provider=nav_state_provider, + ) + + return camera_model + + +# Example usage +def example_usage(): + """Example showing how to use the alignment functions.""" + # Generate synthetic data + n_images = 10 + n_points = 20 + + # Create random points + points_3d = np.random.randn(n_points, 3) + + # Create random rotations + true_alignment = Rotation.random().as_quat() + ins_rotations = [Rotation.random() for _ in range(n_images)] + ins_quats = np.array([r.as_quat() for r in ins_rotations]) + + # Apply true alignment to get SfM rotations + R_align = Rotation.from_quat(true_alignment) + sfm_rotations = [R_align * r for r in ins_rotations] + sfm_quats = np.array([r.as_quat() for r in sfm_rotations]) + + # Create observations with partial visibility + observations = [] + for i in range(n_images): + camera_obs = [] + for j in range(n_points): + # Randomly make some points invisible + visible = random.random() > 0.3 + if visible: + # Add some noise to visible points + uncertainty = 0.01 * np.random.rand() + image_point = np.random.randn(2) # Dummy 2D point + camera_obs.append( + VisiblePoint( + point_3d=points_3d[j], + uncertainty=uncertainty, + image_point=image_point, + visible=True, + ) + ) + else: + camera_obs.append( + VisiblePoint( + point_3d=points_3d[j], + uncertainty=float("inf"), + image_point=np.zeros(2), + visible=False, + ) + ) + observations.append(camera_obs) + + # Estimate rotation + estimate = weighted_horn_alignment_partial( + observations=observations, + sfm_quats=sfm_quats, + ins_quats=ins_quats, + min_points_per_image=3, + ransac_iters=100, + ) + + # Analyze results + analyze_rotation_estimate(estimate) + + # Compare to ground truth + error_rot = ( + Rotation.from_quat(estimate.quaternion) + * Rotation.from_quat(true_alignment).inv() + ) + error_angle = np.abs(error_rot.magnitude()) + print(f"\nError from ground truth: {np.degrees(error_angle):.2f}°") + + +if __name__ == "__main__": + example_usage() diff --git a/kamera/postflight/colmap.py b/kamera/postflight/colmap.py new file mode 100644 index 0000000..3b88f61 --- /dev/null +++ b/kamera/postflight/colmap.py @@ -0,0 +1,434 @@ +import os +import json +import pathlib +import cv2 +import PIL.Image +import numpy as np +import os.path as osp +import ubelt as ub +from posixpath import basename +from re import I + +from shapely import points +import pycolmap as pc +from dataclasses import dataclass +from typing import Tuple, List, Dict +from kamera.sensor_models.nav_state import NavStateINSJson +from kamera.colmap_processing.camera_models import StandardCamera +from kamera.colmap_processing.image_renderer import render_view +from kamera.postflight.alignment import ( + VisiblePoint, + weighted_horn_alignment_partial, + analyze_rotation_estimate, + register_camera_horn_ransac, + verify_alignment, + iterative_alignment, +) + + +@dataclass(frozen=True) +class ColmapCalibrationData: + sfm_poses: List[np.ndarray] + ins_poses: List[np.ndarray] + img_fnames: List[np.ndarray] + img_times: List[np.ndarray] + llhs: List[np.ndarray] + points_per_image: List[List[VisiblePoint]] + basename_to_time: Dict[str, float] + fname_to_time_channel_modality: Dict[float, Dict[str, str]] + best_cameras: Dict[str, pc._core.Camera] + + +class ColmapCalibration(object): + def __init__( + self, flight_dir: str | os.PathLike, colmap_dir: str | os.PathLike + ) -> None: + self.flight_dir = flight_dir + self.colmap_dir = colmap_dir + # contains the images, 3D points, and cameras of the colmap database + self.R = pc.Reconstruction(self.colmap_dir) + self.ccd = ColmapCalibrationData + self.nav_state_provider = self.load_nav_state_provider() + print(self.R.summary()) + + def load_nav_state_provider(self): + # Create navigation stream + json_glob = pathlib.Path(self.flight_dir).rglob("*_meta.json") + try: + next(json_glob) + except StopIteration: + raise SystemExit("No meta jsons were found, please check your filepaths.") + return NavStateINSJson((json_glob)) + + def get_base_name(self, fname: str | os.PathLike) -> str: + """Given an arbitrary filename (could be UV, IR, RGB, json), + extract the portion of the filename that is just the time, flight, + machine (C, L, R), and effort name. + """ + # get base + base = osp.basename(fname) + # get it without an extension and modality + modality_agnostic = "_".join(base.split("_")[:-1]) + return modality_agnostic + + def get_modality(self, fname: str | os.PathLike) -> str: + """Extract image modality (e.g. ir/meta) from a given kamera filename.""" + base = osp.basename(fname) + modality = base.split("_")[-1].split(".")[0] + return modality + + def get_channel(self, fname: str | os.PathLike) -> str: + """Extract channel (e.g. L/R/C) from a given kamera filename.""" + base = osp.basename(fname) + channel = base.split("_")[3] + return channel + + def get_basename_to_time(self, flight_dir: str | os.PathLike) -> dict: + # Establish correspondence between real-world exposure times base of file + # names. + basename_to_time = {} + for json_fname in pathlib.Path(flight_dir).rglob("*_meta.json"): + try: + with open(json_fname) as json_file: + d = json.load(json_file) + # Time that the image was taken. + basename = self.get_base_name(json_fname) + basename_to_time[basename] = float(d["evt"]["time"]) + except (OSError, IOError): + pass + return basename_to_time + + def prepare_calibration_data(self): + img_fnames = [] + img_times = [] + ins_poses = [] + sfm_poses = [] + llhs = [] + points_per_image = [] + basename_to_time = self.get_basename_to_time(self.flight_dir) + best_cameras = {} + most_points = {} + for image_num, image in self.R.images.items(): + base_name = self.get_base_name(image.name) + try: + t = basename_to_time[base_name] + except KeyError: + print( + "Couldn't find a _meta.json file associated with '%s'" % base_name + ) + continue + + # Query the navigation state recorded by the INS for this time. + pose = self.nav_state_provider.pose(t) + llh = self.nav_state_provider.llh(t) + + # Query Colmaps pose for the camera. + R = image.cam_from_world.rotation.matrix() + pos = -np.dot(R.T, image.cam_from_world.translation) + + image.cam_from_world.rotation.normalize() + quat = image.cam_from_world.rotation.quat + + sfm_pose = [pos, quat] + + img_times.append(t) + ins_poses.append(pose) + img_fnames.append(image.name) + sfm_poses.append(sfm_pose) + llhs.append(llh) + points = [] + # associate all the 2D and 3D points seen by this image + for pt in image.points2D: + if pt.has_point3D(): + point_2d = pt.xy + uncertainty = self.R.points3D[pt.point3D_id].error + point_3d = self.R.points3D[pt.point3D_id].xyz + visible = True + vpt = VisiblePoint(point_3d, point_2d, uncertainty, t, visible) + points.append(vpt) + points_per_image.append(points) + camera_name = os.path.basename(os.path.dirname(image.name)) + if camera_name in best_cameras: + if image.num_points3D > most_points[camera_name]: + best_cameras[camera_name] = image.camera + most_points[camera_name] = image.num_points3D + else: + best_cameras[camera_name] = image.camera + most_points[camera_name] = image.num_points3D + + # sort all entries + ind = np.argsort(img_fnames) + img_fnames = [img_fnames[i] for i in ind] + img_times = [img_times[i] for i in ind] + ins_poses = [ins_poses[i] for i in ind] + sfm_poses = [sfm_poses[i] for i in ind] + points_per_image = [points_per_image[i] for i in ind] + llhs = [llhs[i] for i in ind] + + fname_to_time_channel_modality = self.create_fname_to_time_channel_modality( + img_fnames, basename_to_time + ) + + ccd = ColmapCalibrationData( + sfm_poses=sfm_poses, + ins_poses=ins_poses, + img_fnames=img_fnames, + img_times=img_times, + llhs=llhs, + points_per_image=points_per_image, + basename_to_time=basename_to_time, + fname_to_time_channel_modality=fname_to_time_channel_modality, + best_cameras=best_cameras, + ) + self.ccd = ccd + return ccd + + def calibrate_camera( + self, camera_name: str, error_threshold: float + ) -> StandardCamera: + sfm_quats = np.array([pose[1] for pose in self.ccd.sfm_poses]) + ins_quats = np.array([pose[1] for pose in self.ccd.ins_poses]) + # Find all valid indices of current camera + cam_idxs = [ + 1 if camera_name == os.path.basename(os.path.dirname(im)) else 0 + for im in self.ccd.img_fnames + ] + print(f"Number of images in camera {camera_name}.") + print(np.sum(cam_idxs)) + observations = [ + pts for i, pts in enumerate(self.ccd.points_per_image) if cam_idxs[i] == 1 + ] + cam_sfm_quats = [q for i, q in enumerate(sfm_quats) if cam_idxs[i] == 1] + cam_ins_quats = [q for i, q in enumerate(ins_quats) if cam_idxs[i] == 1] + if len(observations) < 10: + print(f"Only {len(observations)} seen for camera {camera_name}, skipping.") + cam = self.ccd.best_cameras[camera_name] + camera_model = iterative_alignment( + cam_sfm_quats, cam_ins_quats, observations, cam, self.nav_state_provider + ) + # best_rotation = weighted_horn_alignment_partial( + # observations, + # cam_sfm_quats, + # cam_ins_quats, + # min_points_per_image=10, + # ransac_iters=100, + # error_threshold=error_threshold, + # ) + # analyze_rotation_estimate(best_rotation) + # best_quat = best_rotation.quaternion + # K = cam.calibration_matrix() + # if cam.model.name == "OPENCV": + # fx, fy, cx, cy, d1, d2, d3, d4 = cam.params + # elif cam.model.name == "SIMPLE_RADIAL": + # d1 = d2 = d3 = d4 = 0 + # elif cam.model.name == "PINHOLE": + # d1 = d2 = d3 = d4 = 0 + # else: + # raise SystemError(f"Unexpected camera model found: {cam.model.name}") + + # dist = np.array([d1, d2, d3, d4]) + # camera_model = StandardCamera( + # cam.width, + # cam.height, + # K, + # dist, + # [0, 0, 0], + # best_quat, + # platform_pose_provider=self.nav_state_provider, + # ) + + return camera_model + + def create_fname_to_time_channel_modality( + self, img_fnames, basename_to_time + ) -> Dict[float, Dict[str, str]]: + print("Creating mapping between RGB and UV images...") + time_to_modality = ub.AutoDict() + for fname in img_fnames: + base_name = self.get_base_name(fname) + try: + t = basename_to_time[base_name] + except Exception as e: + print(e) + print(f"No ins time found for image {base_name}.") + continue + modality = self.get_modality(fname) + channel = self.get_channel(fname) + time_to_modality[t][channel][modality] = fname + return time_to_modality + + def write_gifs( + self, + gif_dir: str | os.PathLike, + colmap_dir: str | os.PathLike, + rgb_str: str, + camera_str: str, + cm_rgb: StandardCamera, + cm_uv: StandardCamera, + ) -> None: + print(f"Writing a registration gif for cameras {rgb_str} " f"and {camera_str}.") + # Pick an image pair and register. + ub.ensuredir(gif_dir) + + img_fnames = self.ccd.img_fnames + for k in range(10): + inds = list(range(len(img_fnames))) + np.random.shuffle(inds) + for i in range(len(img_fnames)): + uv_img = rgb_img = None + fname1 = img_fnames[inds[i]] + if osp.basename(osp.dirname(fname1)) != rgb_str: + continue + t1 = self.ccd.basename_to_time[self.get_base_name(fname1)] + channel = self.get_channel(fname1) # L/C/R + try: + rgb_fname = self.ccd.fname_to_time_channel_modality[t1][channel][ + "rgb" + ] + abs_rgb_fname = os.path.join(colmap_dir, "images0", rgb_fname) + rgb_img = cv2.imread(abs_rgb_fname, cv2.IMREAD_COLOR)[:, :, ::-1] + except Exception as e: + print(f"No rgb image found at time {t1}") + continue + try: + uv_fname = self.ccd.fname_to_time_channel_modality[t1][channel][ + "uv" + ] + abs_uv_fname = os.path.join(colmap_dir, "images0", uv_fname) + uv_img = cv2.imread(abs_uv_fname, cv2.IMREAD_COLOR)[:, :, ::-1] + break + except Exception as e: + print(f"No uv image found at time {t1}") + continue + + if uv_img is None or rgb_img is None: + print("Failed to find matching image pair, skipping.") + continue + print(f"Writing {rgb_fname} and {uv_fname} to gif.") + + # Warps the color image img1 into the uv camera model cm_uv + warped_rgb_img, mask = render_view( + cm_rgb, rgb_img, 0, cm_uv, 0, block_size=10 + ) + + ds_warped_rgb_img = PIL.Image.fromarray( + cv2.pyrDown(cv2.pyrDown(cv2.pyrDown(warped_rgb_img))) + ) + ds_uv_img = PIL.Image.fromarray( + cv2.pyrDown(cv2.pyrDown(cv2.pyrDown(uv_img))) + ) + fname_out = osp.join( + gif_dir, f"{rgb_str}_to_{camera_str}_registration_{k}.gif" + ) + print(f"Writing gif to {fname_out}.") + ds_uv_img.save( + fname_out, + save_all=True, + append_images=[ds_warped_rgb_img], + duration=350, + loop=0, + ) + + def align_model(self, output_dir: str | os.PathLike) -> None: + img_fnames = [im.name for im in self.R.images().values()] + points = [] + ins_poses = [] + for image_name in img_fnames: + base_name = self.get_base_name(image_name) + t = self.basename_to_time[base_name] + # Query the navigation state recorded by the INS for this time. + pose = self.nav_state_provider.pose(t) + ins_poses.append(pose) + x, y, z = pose[0] + points.append([x, y, z]) + points = np.array(points) + locations_txt = os.path.join(output_dir, "image_locations.txt") + self.write_image_locations(locations_txt, img_fnames, ins_poses) + print( + f"Aligning model given {len(img_fnames)} images and their ENU coordinates." + ) + ransac_options = pc.RANSACOptions( + max_error=4.0, # for example, the reprojection error in pixels + min_inlier_ratio=0.01, + confidence=0.9999, + min_num_trials=1000, + max_num_trials=100000, + ) + min_common_observations = 5 + tform = pc.align_reconstruction_to_locations( + self.R, img_fnames, points, min_common_observations, ransac_options + ) + print("Transformation after alignment: ") + print(tform.scale, tform.rotation, tform.translation) + # Apply transform to self + self.R.transform(tform) + print(f"Saving aligned model to {output_dir}...") + self.R.write(output_dir) + + def read_image_locations( + self, fname: str | os.PathLike + ) -> Tuple[List[str], np.ndarray]: + with open(fname, "r") as f: + lines = f.readlines() + points = [] + image_fnames = [] + for line in lines: + # Pull x,y,z out in ENU + try: + img_fname, x, y, z = line.split(" ") + except Exception as e: + print(e) + print("Skipping location line.") + continue + image_fnames.append(img_fname.strip()) + points.append((float(x), float(y), float(z))) + points = np.array(points) + + def write_image_locations( + self, + locations_fname: str | os.PathLike, + img_fnames: List[str], + ins_poses: List[np.ndarray], + ) -> None: + print(f"Writing image locations to {locations_fname}") + img_fnames = sorted(img_fnames) + with open(locations_fname, "w") as fo: + for i in range(len(img_fnames)): + name = img_fnames[i] + pos = ins_poses[i][0] + fo.write("%s %0.8f %0.8f %0.8f\n" % (name, pos[0], pos[1], pos[2])) + + def calibrate_ir(self): + pass + + +def find_best_sparse_model(sparse_dir: str | os.PathLike): + if os.listdir(sparse_dir) == 0: + raise SystemError( + f"Sparse directory given ({sparse_dir}) is empty, please verify your model built correctly." + ) + all_models = sorted(os.listdir(sparse_dir)) + print(f"All Models: {all_models}") + best_model = "" + most_images_aligned = 0 + for subdir in all_models: + R = pc.Reconstruction(subdir) + num_images = len(R.images.keys()) + print(f"Number of images in {subdir}: {num_images}") + if num_images > most_images_aligned: + best_model = subdir + print(f"Selecting {subdir} as the best model.") + return best_model + + +def main(): + flight_dir = "/home/local/KHQ/adam.romlein/noaa/data/2024_AOC_AK_Calibration/fl09" + colmap_dir = ( + "/home/local/KHQ/adam.romlein/noaa/data/2024_AOC_AK_Calibration/fl09/colmap_ir" + ) + cc = ColmapCalibration(flight_dir, colmap_dir) + cc.calibrate_ir() + + +if __name__ == "__main__": + main() diff --git a/kamera/postflight/scripts/calibration.py b/kamera/postflight/scripts/calibration.py new file mode 100644 index 0000000..0e58cad --- /dev/null +++ b/kamera/postflight/scripts/calibration.py @@ -0,0 +1,82 @@ +import os +import time +import ubelt as ub + +from kamera.postflight.colmap import ColmapCalibration, find_best_sparse_model + + +def main(): + # REQUIREMENTS: Must already have built a reasonable 3-D model using Colmap + # And have a flight directory populated by the kamera system + flight_dir = "" + colmap_dir = os.path.join(flight_dir, "colmap") + # Location to save KAMERA camera models. + save_dir = os.path.join(flight_dir, "kamera_models") + # Location to find / build aligned model + align_dir = os.path.join(colmap_dir, "aligned") + + # Step 1: Make sure the model is aligned to the INS readings, if not, + # find the best model and align it. + if os.path.exists(align_dir) and len(os.listdir(align_dir)) == 1: + print( + f"The directory {align_dir} exists and is not empty," + " assuming model is aligned." + ) + aligned_sparse_dir = os.path.join(align_dir, os.listdir(align_dir)[0]) + cc = ColmapCalibration(flight_dir, aligned_sparse_dir) + elif os.path.exists(align_dir) and len(os.listdir(align_dir) > 1): + raise SystemError( + f"{len(os.listdir(align_dir))} aligned models are present, only 1 should exist in {align_dir}." + ) + elif not os.path.exists(align_dir) or len(os.listdir(align_dir) == 0): + print( + f"The directory {align_dir} does not exist, or is empty, selecting and aligning the best sparse model." + ) + # location of sparsely constructed colmap models (always sparse if using default colmap options) + sparse_dir = os.path.join(colmap_dir, "sparse") + # Step 1: Find the "best" sparse model (most images aligned) + best_reconstruction_dir = find_best_sparse_model(sparse_dir) + sparse_idx = os.path.split(best_reconstruction_dir)[-1] + + # Step 2: Align and save this model + aligned_sparse_dir = os.path.join(align_dir, sparse_idx) + ub.ensuredir(aligned_sparse_dir) + cc = ColmapCalibration(flight_dir, best_reconstruction_dir) + cc.align_model(aligned_sparse_dir) + + # We now have an aligned 3-D model, so we can calibrate the cameras + print("Preparing calibration data...") + cc.prepare_calibration_data() + ub.ensuredir(save_dir) + cameras = ub.AutoDict() + for camera_str in cc.ccd.best_cameras.keys(): + channel, modality = camera_str.split("_")[2:] + # if modality != "rgb": + # continue + print(f"Calibrating camera {camera_str}.") + tic = time.time() + camera_model = cc.calibrate_camera(camera_str, error_threshold=100) + toc = time.time() + if camera_model is not None: + out_path = os.path.join(save_dir, f"{camera_str}_v2.yaml") + print(f"Saving camera model to {out_path}") + camera_model.save_to_file(out_path) + print(f"Time to calibrate camera {camera_str} was {(toc - tic):.3f}s") + print(camera_model) + cameras[channel][modality] = camera_model + else: + print(f"Calibrating camera {camera_str} failed.") + + aircraft, angle = camera_str.split("_")[0:2] + gif_dir = os.path.join(save_dir, "registration_gifs_v2") + ub.ensuredir(gif_dir) + for channel in cameras.keys(): + rgb_model = cameras[channel]["rgb"] + uv_model = cameras[channel]["uv"] + rgb_name = "_".join([aircraft, angle, channel, "rgb"]) + uv_name = "_".join([aircraft, angle, channel, "uv"]) + cc.write_gifs(gif_dir, colmap_dir, rgb_name, uv_name, rgb_model, uv_model) + + +if __name__ == "__main__": + main() From 5ba65c454224d2e918c6734b02b8cbf41815095c Mon Sep 17 00:00:00 2001 From: Adam Romlein Date: Thu, 19 Dec 2024 20:30:35 -0500 Subject: [PATCH 05/20] Add simple quaternion viz script --- kamera/postflight/viz.py | 127 +++++++++++++++++++++++++++++++++++++++ 1 file changed, 127 insertions(+) create mode 100644 kamera/postflight/viz.py diff --git a/kamera/postflight/viz.py b/kamera/postflight/viz.py new file mode 100644 index 0000000..1b1bf06 --- /dev/null +++ b/kamera/postflight/viz.py @@ -0,0 +1,127 @@ +import numpy as np +import matplotlib.pyplot as plt +from mpl_toolkits.mplot3d import Axes3D +from scipy.spatial.transform import Rotation + + +def visualize_quaternions(q1, q2, q3=None): + """ + Visualizes three quaternions in 3D space by showing their corresponding rotated coordinate frames. + + Parameters: + - q1: list or array of 4 elements representing the first quaternion [w, x, y, z] + - q2: list or array of 4 elements representing the second quaternion [w, x, y, z] + - q3: list or array of 4 elements representing the second quaternion [w, x, y, z] + """ + + def normalize(q): + norm = np.linalg.norm(q) + return q / norm if norm != 0 else q + + # Normalize the quaternions + q1 = normalize(np.array(q1, dtype=np.float64)) + q2 = normalize(np.array(q2, dtype=np.float64)) + q3 = normalize(np.array(q3, dtype=np.float64)) + + # Convert to rotation matrices + R1 = Rotation.from_quat(q1).as_matrix() + R2 = Rotation.from_quat(q2).as_matrix() + # R3 = Rotation.from_quat(q3).as_matrix() + + # Original coordinate axes + origin = np.zeros(3) + axes = np.eye(3) # 3x3 identity matrix + + # Apply rotations + rotated_axes1 = R1 @ axes + rotated_axes2 = R2 @ axes + # rotated_axes3 = R3 @ axes + + # Plotting + fig = plt.figure(figsize=(10, 8)) + ax = fig.add_subplot(111, projection="3d") + + # Function to plot axes + def plot_axes(ax, origin, axes, colors, labels, linewidth=2, alpha=1.0): + for i in range(3): + ax.quiver( + origin[0], + origin[1], + origin[2], + axes[0, i], + axes[1, i], + axes[2, i], + color=colors[i], + label=labels[i] if origin is origin else "", + linewidth=linewidth, + arrow_length_ratio=0.1, + alpha=alpha, + ) + + # Plot original axes + plot_axes( + ax, origin, axes, ["k", "k", "k"], ["X", "Y", "Z"], linewidth=1, alpha=0.3 + ) + + # Plot first quaternion rotated axes + plot_axes( + ax, + origin, + rotated_axes1, + ["r", "g", "b"], + ["Q1 X", "Q1 Y", "Q1 Z"], + linewidth=2, + alpha=0.8, + ) + + # Plot second quaternion rotated axes + plot_axes( + ax, + origin, + rotated_axes2, + ["c", "m", "y"], + ["Q2 X", "Q2 Y", "Q2 Z"], + linewidth=2, + alpha=0.8, + ) + + # Plot third quaternion rotated axes + # plot_axes(ax, origin, rotated_axes3, ["b", "m", "y"], ['Q3 X', 'Q3 Y', 'Q3 Z'], linewidth=2, alpha=0.8) + + # Setting the labels + ax.set_xlabel("X-axis") + ax.set_ylabel("Y-axis") + ax.set_zlabel("Z-axis") + + # Setting the aspect ratio to be equal + ax.set_box_aspect([1, 1, 1]) # Requires matplotlib >= 3.3.0 + + # Setting the limits + limit = 1.0 + ax.set_xlim([-limit, limit]) + ax.set_ylim([-limit, limit]) + ax.set_zlim([-limit, limit]) + + # Adding a legend + # To avoid duplicate labels in legend + handles, labels = ax.get_legend_handles_labels() + by_label = dict(zip(labels, handles)) + ax.legend(by_label.values(), by_label.keys()) + + plt.title("Visualization of Two Quaternions in 3D Space") + plt.show() + + +# Example Usage +if __name__ == "__main__": + # Define two quaternions + # Quaternion q1 represents a rotation of 90 degrees around the X-axis + q1 = [np.cos(np.pi / 4), np.sin(np.pi / 4), 0, 0] + + # Quaternion q2 represents a rotation of 90 degrees around the Y-axis + q2 = [np.cos(np.pi / 4), 0, np.sin(np.pi / 4), 0] + + # Quaternion q3 represents a rotation of 90 degrees around the Z-axis + q3 = [np.cos(np.pi / 4), np.sin(np.pi / 4), np.sin(np.pi / 4), 0] + + visualize_quaternions(q1, q2, q3) From ddbedcf1b7866e5c390f31b127aa3e6ed236839e Mon Sep 17 00:00:00 2001 From: Adam Romlein Date: Thu, 19 Dec 2024 20:31:17 -0500 Subject: [PATCH 06/20] Add pycolmap, bottle, to dependencies. --- poetry.lock | 115 +++++++++++++++++++++++-------------------------- pyproject.toml | 2 + 2 files changed, 56 insertions(+), 61 deletions(-) diff --git a/poetry.lock b/poetry.lock index 689f34d..a2d0a89 100644 --- a/poetry.lock +++ b/poetry.lock @@ -1,10 +1,9 @@ -# This file is automatically @generated by Poetry and should not be changed by hand. +# This file is automatically @generated by Poetry 1.8.3 and should not be changed by hand. [[package]] name = "asttokens" version = "2.4.1" description = "Annotate AST trees with source code positions" -category = "main" optional = false python-versions = "*" files = [ @@ -19,11 +18,21 @@ six = ">=1.12.0" astroid = ["astroid (>=1,<2)", "astroid (>=2,<4)"] test = ["astroid (>=1,<2)", "astroid (>=2,<4)", "pytest"] +[[package]] +name = "bottle" +version = "0.13.2" +description = "Fast and simple WSGI-framework for small web-applications." +optional = false +python-versions = "*" +files = [ + {file = "bottle-0.13.2-py2.py3-none-any.whl", hash = "sha256:27569ab8d1332fbba3e400b3baab2227ab4efb4882ff147af05a7c00ed73409c"}, + {file = "bottle-0.13.2.tar.gz", hash = "sha256:e53803b9d298c7d343d00ba7d27b0059415f04b9f6f40b8d58b5bf914ba9d348"}, +] + [[package]] name = "colorama" version = "0.4.6" description = "Cross-platform colored terminal text." -category = "main" optional = false python-versions = "!=3.0.*,!=3.1.*,!=3.2.*,!=3.3.*,!=3.4.*,!=3.5.*,!=3.6.*,>=2.7" files = [ @@ -35,7 +44,6 @@ files = [ name = "contourpy" version = "1.3.0" description = "Python library for calculating contours of 2D quadrilateral grids" -category = "main" optional = false python-versions = ">=3.9" files = [ @@ -120,7 +128,6 @@ test-no-images = ["pytest", "pytest-cov", "pytest-rerunfailures", "pytest-xdist" name = "cycler" version = "0.12.1" description = "Composable style cycles" -category = "main" optional = false python-versions = ">=3.8" files = [ @@ -136,7 +143,6 @@ tests = ["pytest", "pytest-cov", "pytest-xdist"] name = "datetime" version = "5.5" description = "This package provides a DateTime data type, as known from Zope. Unless you need to communicate with Zope APIs, you're probably better off using Python's built-in datetime module." -category = "main" optional = false python-versions = ">=3.7" files = [ @@ -152,7 +158,6 @@ pytz = "*" name = "decorator" version = "5.1.1" description = "Decorators for Humans" -category = "main" optional = false python-versions = ">=3.5" files = [ @@ -164,7 +169,6 @@ files = [ name = "exceptiongroup" version = "1.2.2" description = "Backport of PEP 654 (exception groups)" -category = "main" optional = false python-versions = ">=3.7" files = [ @@ -179,7 +183,6 @@ test = ["pytest (>=6)"] name = "executing" version = "2.1.0" description = "Get the currently executing AST node of a frame, and other information" -category = "main" optional = false python-versions = ">=3.8" files = [ @@ -194,7 +197,6 @@ tests = ["asttokens (>=2.1.0)", "coverage", "coverage-enable-subprocess", "ipyth name = "exifread" version = "3.0.0" description = "Read Exif metadata from tiff and jpeg files." -category = "main" optional = false python-versions = "*" files = [ @@ -209,7 +211,6 @@ dev = ["mypy (==0.950)", "pylint (==2.13.8)"] name = "fonttools" version = "4.54.1" description = "Tools to manipulate font files" -category = "main" optional = false python-versions = ">=3.8" files = [ @@ -281,7 +282,6 @@ woff = ["brotli (>=1.0.1)", "brotlicffi (>=0.8.0)", "zopfli (>=0.1.4)"] name = "GDAL" version = "3.9.2" description = "GDAL: Geospatial Data Abstraction Library" -category = "main" optional = false python-versions = ">=3.7.0" files = [ @@ -299,7 +299,6 @@ url = "https://github.com/girder/large_image_wheels/raw/wheelhouse/GDAL-3.9.2-cp name = "ipdb" version = "0.13.13" description = "IPython-enabled pdb" -category = "main" optional = false python-versions = ">=2.7, !=3.0.*, !=3.1.*, !=3.2.*, !=3.3.*" files = [ @@ -316,7 +315,6 @@ tomli = {version = "*", markers = "python_version > \"3.6\" and python_version < name = "ipython" version = "8.28.0" description = "IPython: Productive Interactive Computing" -category = "main" optional = false python-versions = ">=3.10" files = [ @@ -355,7 +353,6 @@ test-extra = ["curio", "ipython[test]", "matplotlib (!=3.2.0)", "nbformat", "num name = "jedi" version = "0.19.1" description = "An autocompletion tool for Python that can be used for text editors." -category = "main" optional = false python-versions = ">=3.6" files = [ @@ -375,7 +372,6 @@ testing = ["Django", "attrs", "colorama", "docopt", "pytest (<7.0.0)"] name = "kiwisolver" version = "1.4.7" description = "A fast implementation of the Cassowary constraint solver" -category = "main" optional = false python-versions = ">=3.8" files = [ @@ -499,7 +495,6 @@ files = [ name = "markdown-it-py" version = "3.0.0" description = "Python port of markdown-it. Markdown parsing, done right!" -category = "main" optional = false python-versions = ">=3.8" files = [ @@ -524,7 +519,6 @@ testing = ["coverage", "pytest", "pytest-cov", "pytest-regressions"] name = "matplotlib" version = "3.9.2" description = "Python plotting package" -category = "main" optional = false python-versions = ">=3.9" files = [ @@ -588,7 +582,6 @@ dev = ["meson-python (>=0.13.1)", "numpy (>=1.25)", "pybind11 (>=2.6)", "setupto name = "matplotlib-inline" version = "0.1.7" description = "Inline Matplotlib backend for Jupyter" -category = "main" optional = false python-versions = ">=3.8" files = [ @@ -603,7 +596,6 @@ traitlets = "*" name = "mdurl" version = "0.1.2" description = "Markdown URL utilities" -category = "main" optional = false python-versions = ">=3.7" files = [ @@ -615,7 +607,6 @@ files = [ name = "numpy" version = "2.1.1" description = "Fundamental package for array computing in Python" -category = "main" optional = false python-versions = ">=3.10" files = [ @@ -678,7 +669,6 @@ files = [ name = "opencv-python" version = "4.10.0.84" description = "Wrapper package for OpenCV python bindings." -category = "main" optional = false python-versions = ">=3.6" files = [ @@ -693,12 +683,9 @@ files = [ [package.dependencies] numpy = [ - {version = ">=1.21.2", markers = "python_version >= \"3.10\""}, - {version = ">=1.21.4", markers = "python_version >= \"3.10\" and platform_system == \"Darwin\""}, - {version = ">=1.23.5", markers = "python_version >= \"3.11\""}, - {version = ">=1.19.3", markers = "python_version >= \"3.6\" and platform_system == \"Linux\" and platform_machine == \"aarch64\" or python_version >= \"3.9\""}, - {version = ">=1.17.0", markers = "python_version >= \"3.7\""}, - {version = ">=1.17.3", markers = "python_version >= \"3.8\""}, + {version = ">=1.23.5", markers = "python_version >= \"3.11\" and python_version < \"3.12\""}, + {version = ">=1.21.4", markers = "python_version >= \"3.10\" and platform_system == \"Darwin\" and python_version < \"3.11\""}, + {version = ">=1.21.2", markers = "platform_system != \"Darwin\" and python_version >= \"3.10\" and python_version < \"3.11\""}, {version = ">=1.26.0", markers = "python_version >= \"3.12\""}, ] @@ -706,7 +693,6 @@ numpy = [ name = "packaging" version = "24.1" description = "Core utilities for Python packages" -category = "main" optional = false python-versions = ">=3.8" files = [ @@ -718,7 +704,6 @@ files = [ name = "parso" version = "0.8.4" description = "A Python Parser" -category = "main" optional = false python-versions = ">=3.6" files = [ @@ -734,7 +719,6 @@ testing = ["docopt", "pytest"] name = "pexpect" version = "4.9.0" description = "Pexpect allows easy control of interactive console applications." -category = "main" optional = false python-versions = "*" files = [ @@ -749,7 +733,6 @@ ptyprocess = ">=0.5" name = "pillow" version = "10.4.0" description = "Python Imaging Library (Fork)" -category = "main" optional = false python-versions = ">=3.8" files = [ @@ -847,7 +830,6 @@ xmp = ["defusedxml"] name = "prompt-toolkit" version = "3.0.48" description = "Library for building powerful interactive command lines in Python" -category = "main" optional = false python-versions = ">=3.7.0" files = [ @@ -862,7 +844,6 @@ wcwidth = "*" name = "ptyprocess" version = "0.7.0" description = "Run a subprocess in a pseudo terminal" -category = "main" optional = false python-versions = "*" files = [ @@ -874,7 +855,6 @@ files = [ name = "pure-eval" version = "0.2.3" description = "Safely evaluate AST nodes without side effects" -category = "main" optional = false python-versions = "*" files = [ @@ -885,11 +865,42 @@ files = [ [package.extras] tests = ["pytest"] +[[package]] +name = "pycolmap" +version = "3.11.1" +description = "COLMAP bindings" +optional = false +python-versions = ">=3.8" +files = [ + {file = "pycolmap-3.11.1-cp310-cp310-macosx_10_15_x86_64.whl", hash = "sha256:52810e9d63c3f2d5e0e0ebac97b453c14ca06f42072ede26fe9bc5207e5f32ea"}, + {file = "pycolmap-3.11.1-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:92d12806ed7252e2c8f9584d2751e3afacbd21be5150d8f24c52b067c67695ab"}, + {file = "pycolmap-3.11.1-cp310-cp310-manylinux_2_28_x86_64.whl", hash = "sha256:413b95d933b8ed10ece2011cbd80fe32704464b5ba38cfbc978dec68757dfaec"}, + {file = "pycolmap-3.11.1-cp310-cp310-win_amd64.whl", hash = "sha256:b3bb1831287246b0825a17f9ee19e90d18fbfe096eada7b89bdee3a1d8c5e040"}, + {file = "pycolmap-3.11.1-cp311-cp311-macosx_10_15_x86_64.whl", hash = "sha256:1949ca7eaa0a74ff76d3758d10496a0147d98bb89c6c7aad2514f1c70d88b852"}, + {file = "pycolmap-3.11.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:7c8f9679a78fa68e3b718f5efc87d520012330c32b1c0c1321766addda7903e5"}, + {file = "pycolmap-3.11.1-cp311-cp311-manylinux_2_28_x86_64.whl", hash = "sha256:9bb98585e540a403df718b26ffdf475eba74891d16bf59ba94eef0f3acb827a5"}, + {file = "pycolmap-3.11.1-cp311-cp311-win_amd64.whl", hash = "sha256:f41e1c057b5acfd4363aac0c85960fd880b612c93b96569bdc188b743e31ec0d"}, + {file = "pycolmap-3.11.1-cp312-cp312-macosx_10_15_x86_64.whl", hash = "sha256:994dc06fb94d733897cf696df25f1217f3491f34b3c26354ceee5a5e60f7a22b"}, + {file = "pycolmap-3.11.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:6d3541c671b7e61f5e381ed6a08de522f4f26ada957cecff1f8e7f964f03d3d7"}, + {file = "pycolmap-3.11.1-cp312-cp312-manylinux_2_28_x86_64.whl", hash = "sha256:14f04f48d13358e9418d71b3a806f1aa39ab0b2a35904907f74142e4964b098b"}, + {file = "pycolmap-3.11.1-cp312-cp312-win_amd64.whl", hash = "sha256:e023af9e4fb54c5e2dec23ff7410eedfa79d53f5f8eeac31f435cf560a9e4c94"}, + {file = "pycolmap-3.11.1-cp38-cp38-macosx_10_15_x86_64.whl", hash = "sha256:f7ab7704f0692347027e17cb218bf1e56933a670561a988fe2d3608a7b836d38"}, + {file = "pycolmap-3.11.1-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:aa51d8adbd52b310ec46f71220443acf5d54d1ec5f809fba741774a7532a78e8"}, + {file = "pycolmap-3.11.1-cp38-cp38-manylinux_2_28_x86_64.whl", hash = "sha256:9ee22f77230fb92519327a5bfb48c9f9624840a5103007a0fc62b2b9940221b5"}, + {file = "pycolmap-3.11.1-cp38-cp38-win_amd64.whl", hash = "sha256:d9f94f5d4134a3b29d38e85e07aa88ae502567fd549bc000312a5d4f3932cb9f"}, + {file = "pycolmap-3.11.1-cp39-cp39-macosx_10_15_x86_64.whl", hash = "sha256:0564490d3511ccadd3dc0e7e640f1109fda1e59b883041ce744a08f1393abb52"}, + {file = "pycolmap-3.11.1-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:c7e107117837ccd0a4b6a22adc5a26849afed26b0d2ddde354e402614e5cad51"}, + {file = "pycolmap-3.11.1-cp39-cp39-manylinux_2_28_x86_64.whl", hash = "sha256:2c6d3671f84eebd005ae5b77d39a8fad5bf49d85caea49ef81f87325316437d1"}, + {file = "pycolmap-3.11.1-cp39-cp39-win_amd64.whl", hash = "sha256:26dcd876aceca8dffa8877c4beefda68b1ce37369621b27c5ae6fed8409cb41d"}, +] + +[package.dependencies] +numpy = "*" + [[package]] name = "pygeodesy" version = "24.9.29" description = "Pure Python geodesy tools" -category = "main" optional = false python-versions = "*" files = [ @@ -901,7 +912,6 @@ files = [ name = "pygments" version = "2.18.0" description = "Pygments is a syntax highlighting package written in Python." -category = "main" optional = false python-versions = ">=3.8" files = [ @@ -916,7 +926,6 @@ windows-terminal = ["colorama (>=0.4.6)"] name = "pyparsing" version = "3.1.4" description = "pyparsing module - Classes and methods to define and execute parsing grammars" -category = "main" optional = false python-versions = ">=3.6.8" files = [ @@ -931,7 +940,6 @@ diagrams = ["jinja2", "railroad-diagrams"] name = "pyshp" version = "2.3.1" description = "Pure Python read/write support for ESRI Shapefile format" -category = "main" optional = false python-versions = ">=2.7" files = [ @@ -943,7 +951,6 @@ files = [ name = "python-dateutil" version = "2.9.0.post0" description = "Extensions to the standard Python datetime module" -category = "main" optional = false python-versions = "!=3.0.*,!=3.1.*,!=3.2.*,>=2.7" files = [ @@ -958,7 +965,6 @@ six = ">=1.5" name = "pytz" version = "2024.2" description = "World timezone definitions, modern and historical" -category = "main" optional = false python-versions = "*" files = [ @@ -970,7 +976,6 @@ files = [ name = "pyyaml" version = "6.0.2" description = "YAML parser and emitter for Python" -category = "main" optional = false python-versions = ">=3.8" files = [ @@ -1033,7 +1038,6 @@ files = [ name = "rich" version = "13.9.1" description = "Render rich text, tables, progress bars, syntax highlighting, markdown and more to the terminal" -category = "main" optional = false python-versions = ">=3.8.0" files = [ @@ -1053,7 +1057,6 @@ jupyter = ["ipywidgets (>=7.5.1,<9)"] name = "scipy" version = "1.14.1" description = "Fundamental algorithms for scientific computing in Python" -category = "main" optional = false python-versions = ">=3.10" files = [ @@ -1104,7 +1107,6 @@ test = ["Cython", "array-api-strict (>=2.0)", "asv", "gmpy2", "hypothesis (>=6.3 name = "scriptconfig" version = "0.8.0" description = "Easy dict-based script configuration with CLI support" -category = "main" optional = false python-versions = ">=3.6" files = [ @@ -1114,7 +1116,7 @@ files = [ [package.dependencies] PyYAML = [ - {version = ">=6.0", markers = "python_version >= \"3.10\" and python_version < \"3.12\""}, + {version = ">=6.0", markers = "python_version < \"3.12\" and python_version >= \"3.10\""}, {version = ">=6.0.1", markers = "python_version < \"4.0\" and python_version >= \"3.12\""}, ] ubelt = ">=1.3.6" @@ -1132,7 +1134,6 @@ tests-strict = ["coverage (==4.3.4)", "coverage (==4.5)", "coverage (==5.3.1)", name = "setuptools" version = "75.1.0" description = "Easily download, build, install, upgrade, and uninstall Python packages" -category = "main" optional = false python-versions = ">=3.8" files = [ @@ -1147,13 +1148,12 @@ cover = ["pytest-cov"] doc = ["furo", "jaraco.packaging (>=9.3)", "jaraco.tidelift (>=1.4)", "pygments-github-lexers (==0.0.5)", "pyproject-hooks (!=1.1)", "rst.linker (>=1.9)", "sphinx (>=3.5)", "sphinx-favicon", "sphinx-inline-tabs", "sphinx-lint", "sphinx-notfound-page (>=1,<2)", "sphinx-reredirects", "sphinxcontrib-towncrier", "towncrier (<24.7)"] enabler = ["pytest-enabler (>=2.2)"] test = ["build[virtualenv] (>=1.0.3)", "filelock (>=3.4.0)", "ini2toml[lite] (>=0.14)", "jaraco.develop (>=7.21)", "jaraco.envs (>=2.2)", "jaraco.path (>=3.2.0)", "jaraco.test", "packaging (>=23.2)", "pip (>=19.1)", "pyproject-hooks (!=1.1)", "pytest (>=6,!=8.1.*)", "pytest-home (>=0.5)", "pytest-perf", "pytest-subprocess", "pytest-timeout", "pytest-xdist (>=3)", "tomli-w (>=1.0.0)", "virtualenv (>=13.0.0)", "wheel (>=0.44.0)"] -type = ["importlib-metadata (>=7.0.2)", "jaraco.develop (>=7.21)", "mypy (>=1.11.0,<1.12.0)", "pytest-mypy"] +type = ["importlib-metadata (>=7.0.2)", "jaraco.develop (>=7.21)", "mypy (==1.11.*)", "pytest-mypy"] [[package]] name = "shapely" version = "2.0.6" description = "Manipulation and analysis of geometric objects" -category = "main" optional = false python-versions = ">=3.7" files = [ @@ -1205,14 +1205,13 @@ files = [ numpy = ">=1.14,<3" [package.extras] -docs = ["matplotlib", "numpydoc (>=1.1.0,<1.2.0)", "sphinx", "sphinx-book-theme", "sphinx-remove-toctrees"] +docs = ["matplotlib", "numpydoc (==1.1.*)", "sphinx", "sphinx-book-theme", "sphinx-remove-toctrees"] test = ["pytest", "pytest-cov"] [[package]] name = "simplekml" version = "1.3.6" description = "A Simple KML creator" -category = "main" optional = false python-versions = "*" files = [ @@ -1223,7 +1222,6 @@ files = [ name = "six" version = "1.16.0" description = "Python 2 and 3 compatibility utilities" -category = "main" optional = false python-versions = ">=2.7, !=3.0.*, !=3.1.*, !=3.2.*" files = [ @@ -1235,7 +1233,6 @@ files = [ name = "stack-data" version = "0.6.3" description = "Extract data from python stack frames and tracebacks for informative displays" -category = "main" optional = false python-versions = "*" files = [ @@ -1255,7 +1252,6 @@ tests = ["cython", "littleutils", "pygments", "pytest", "typeguard"] name = "tomli" version = "2.0.2" description = "A lil' TOML parser" -category = "main" optional = false python-versions = ">=3.8" files = [ @@ -1267,7 +1263,6 @@ files = [ name = "traitlets" version = "5.14.3" description = "Traitlets Python configuration system" -category = "main" optional = false python-versions = ">=3.8" files = [ @@ -1283,7 +1278,6 @@ test = ["argcomplete (>=3.0.3)", "mypy (>=1.7.0)", "pre-commit", "pytest (>=7.0, name = "transformations" version = "2024.5.24" description = "Homogeneous Transformation Matrices and Quaternions" -category = "main" optional = false python-versions = ">=3.9" files = [ @@ -1304,6 +1298,9 @@ files = [ {file = "transformations-2024.5.24-cp312-cp312-win32.whl", hash = "sha256:f713ac891a46abfd98158c8a72166a1f92ebaba1644dc8aa59b5357391d6d9e0"}, {file = "transformations-2024.5.24-cp312-cp312-win_amd64.whl", hash = "sha256:d81ed1df5dbdd204cd447728cc5b44d4bf1ccd4af5401ee61032477f5de5788b"}, {file = "transformations-2024.5.24-cp312-cp312-win_arm64.whl", hash = "sha256:bbb74d4701be2fc7852c80493e2b92cd52485d4712ce8bfc03c92fb7bdd365c5"}, + {file = "transformations-2024.5.24-cp313-cp313-win32.whl", hash = "sha256:a52ae7bc8a194dc6d9b5809f9c1bb38cd5088cefcb46fc18fac9d193e48b981a"}, + {file = "transformations-2024.5.24-cp313-cp313-win_amd64.whl", hash = "sha256:77b2d2ce824cfd2b555cbe35a05aed74a78e71f5783665b495a80e71ede2fd65"}, + {file = "transformations-2024.5.24-cp313-cp313-win_arm64.whl", hash = "sha256:2b86b05f304d2da980dabeb52a6bc49fbcc6c4f830f470b82c3559623ca1bae7"}, {file = "transformations-2024.5.24-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:d70a175f7baff6cc70236f74d51c5adb14a3cc3d89fc2e108c1f086f9a834e88"}, {file = "transformations-2024.5.24-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:29f4ebee83c2fb6857f7dbb15917e39bc6bed1f309179452a0dfeda37e2d4d0d"}, {file = "transformations-2024.5.24-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:00b20a57cfe4b5f5fadf957bff68c40a86437f85e75b2ed655b87beb45d62940"}, @@ -1319,7 +1316,6 @@ numpy = "*" name = "typing-extensions" version = "4.12.2" description = "Backported and Experimental Type Hints for Python 3.8+" -category = "main" optional = false python-versions = ">=3.8" files = [ @@ -1331,7 +1327,6 @@ files = [ name = "ubelt" version = "1.3.6" description = "A Python utility belt containing simple tools, a stdlib like feel, and extra batteries" -category = "main" optional = false python-versions = ">=3.6" files = [ @@ -1355,7 +1350,6 @@ types-strict = ["autoflake (==1.4)", "mypy", "yapf (==0.32.0)"] name = "wcwidth" version = "0.2.13" description = "Measures the displayed width of unicode strings in a terminal" -category = "main" optional = false python-versions = "*" files = [ @@ -1367,7 +1361,6 @@ files = [ name = "zope-interface" version = "7.0.3" description = "Interfaces for Python" -category = "main" optional = false python-versions = ">=3.8" files = [ @@ -1418,4 +1411,4 @@ testing = ["coverage (>=5.0.3)", "zope.event", "zope.testing"] [metadata] lock-version = "2.0" python-versions = "^3.10" -content-hash = "f12fd4cb5e2ba880d79c054b211f719ad02260180998d7090af72a2cf619e730" +content-hash = "e592e34b5bad869b2938ac89d0c685ea78a6a71ea5ef9e0f2b97fc96f4380a2c" diff --git a/pyproject.toml b/pyproject.toml index adddc10..04686dd 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -26,6 +26,8 @@ ubelt = "^1.3.6" rich = "^13.9.1" gdal = {url = "https://github.com/girder/large_image_wheels/raw/wheelhouse/GDAL-3.9.2-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl#sha256=0ccdfd68893818a86d2225c1efe6b4a64a6d84676f6fb1e7ec5a4138f70d837b"} ipdb = "^0.13.13" +bottle = "^0.13.2" +pycolmap = "^3.11.1" [build-system] From 3708ae34cb6024763540bb9b028618a4b9ae4d85 Mon Sep 17 00:00:00 2001 From: romleiaj Date: Thu, 2 Jan 2025 16:53:07 -0500 Subject: [PATCH 07/20] Add dynamic uncertainty --- kamera/postflight/alignment.py | 12 +++++++++++- 1 file changed, 11 insertions(+), 1 deletion(-) diff --git a/kamera/postflight/alignment.py b/kamera/postflight/alignment.py index 92ad6fe..a5d0f86 100644 --- a/kamera/postflight/alignment.py +++ b/kamera/postflight/alignment.py @@ -511,6 +511,9 @@ def cam_quat_error(cam_quat: np.ndarray) -> float: err = [] + # Update uncertainty based on errors + max_uncertainty = np.inf + num_skipped = 0 # check quaternion alignment over all images for pts in points_per_image: xys = [] @@ -518,11 +521,15 @@ def cam_quat_error(cam_quat: np.ndarray) -> float: # uncertainties = [] # time is the same for all points t = pts[0].time - max_uncertainty = 1 for pt in pts: if pt.uncertainty < max_uncertainty: xys.append(pt.point_2d) xyzs.append(pt.point_3d) + else: + num_skipped += 1 + if num_skipped > 1: + print(f"NUMBER of pts skipped: {num_skipped:.3f}") + xys = np.array(xys) xyzs = np.array(xyzs) # Error in meters. @@ -544,6 +551,9 @@ def cam_quat_error(cam_quat: np.ndarray) -> float: # err.append(np.percentile(err_, 90)) err.append(np.median(err_)) + # Eliminate points 10x the distance away from median + max_uncertainty = np.median(err) * 10 + # print("Average uncertainty: ") # print(np.mean(uncertainties)) # err = err[err < np.percentile(err, 90)] From 97787efdd2f107104e35fef0e6b4cc0427264dea Mon Sep 17 00:00:00 2001 From: Adam Romlein Date: Wed, 5 Feb 2025 10:37:19 -0500 Subject: [PATCH 08/20] Fix bug: invert rotation so we get perspective from cam to world. Begin development of calibration transfer function. --- kamera/postflight/alignment.py | 425 ++++++++++++++++++----- kamera/postflight/colmap.py | 83 +++-- kamera/postflight/scripts/calibration.py | 43 ++- 3 files changed, 417 insertions(+), 134 deletions(-) diff --git a/kamera/postflight/alignment.py b/kamera/postflight/alignment.py index a5d0f86..a7fccc6 100644 --- a/kamera/postflight/alignment.py +++ b/kamera/postflight/alignment.py @@ -14,6 +14,7 @@ class VisiblePoint: """Point visible in a camera view.""" point_3d: np.ndarray # 3D point coordinates (3,) + point_3d_id: int # Unique ID given by Colmap of the 3D point point_2d: np.ndarray # 2D observation in image (2,) uncertainty: float # Point uncertainty/error time: float @@ -477,7 +478,7 @@ def iterative_alignment( points_per_image: List[List[VisiblePoint]], colmap_camera: pycolmap._core.Camera, nav_state_provider: NavStateINSJson, -): +) -> StandardCamera: # Both quaternions are of the form (x, y, z, w) and represent a coordinate # system rotation. cam_quats = [ @@ -498,7 +499,27 @@ def iterative_alignment( raise SystemError(f"Unexpected camera model found: {colmap_camera.model.name}") dist = np.array([d1, d2, d3, d4]) + organized_points_per_frame = [] + max_uncertainty = np.inf + errs = [] + for pts in points_per_image: + xy = [] + xyz = [] + for pt in pts: + errs.append(pt.uncertainty) + if pt.uncertainty < max_uncertainty: + xy.append(pt.point_2d) + xyz.append(pt.point_3d) + + # Eliminate points 10x the distance away from median + max_uncertainty = np.median(errs) * 10 + # time is the same for all points, since it's a single frame + xy = np.array(xy) + xyz = np.array(xyz) + organized_points_per_frame.append((xy, xyz, pts[0].time)) + def cam_quat_error(cam_quat: np.ndarray) -> float: + cam_quat = cam_quat / np.linalg.norm(cam_quat) camera_model = StandardCamera( colmap_camera.width, colmap_camera.height, @@ -508,38 +529,22 @@ def cam_quat_error(cam_quat: np.ndarray) -> float: cam_quat, platform_pose_provider=nav_state_provider, ) - err = [] # Update uncertainty based on errors - max_uncertainty = np.inf - num_skipped = 0 - # check quaternion alignment over all images - for pts in points_per_image: + # check quaternion alignment over all frames + for xys, xyzs, t in organized_points_per_frame: xys = [] xyzs = [] - # uncertainties = [] - # time is the same for all points - t = pts[0].time - for pt in pts: - if pt.uncertainty < max_uncertainty: - xys.append(pt.point_2d) - xyzs.append(pt.point_3d) - else: - num_skipped += 1 - if num_skipped > 1: - print(f"NUMBER of pts skipped: {num_skipped:.3f}") xys = np.array(xys) xyzs = np.array(xyzs) # Error in meters. - # TODO: Add some error thresholding - # Rays coming out of the camera in the direction of the imaged points. ray_pos, ray_dir = camera_model.unproject(xys.T, t) # Direction coming out of the camera pointing at the actual 3-D points' - # locatinos. + # locations. ray_dir2 = xyzs.T - ray_pos d = np.sqrt(np.sum((ray_dir2) ** 2, axis=0)) ray_dir2 /= d @@ -551,14 +556,11 @@ def cam_quat_error(cam_quat: np.ndarray) -> float: # err.append(np.percentile(err_, 90)) err.append(np.median(err_)) - # Eliminate points 10x the distance away from median - max_uncertainty = np.median(err) * 10 - # print("Average uncertainty: ") # print(np.mean(uncertainties)) # err = err[err < np.percentile(err, 90)] - err = np.mean(err) + err = np.median(err) # print('RMS reproject error for quat', cam_quat, ': %0.8f' % err) return err @@ -566,9 +568,7 @@ def cam_quat_error(cam_quat: np.ndarray) -> float: random.shuffle(cam_quats) best_quat = None best_err = np.inf - for i in range(len(cam_quats)): - cam_quat = cam_quats[i] - + for cam_quat in cam_quats: err = cam_quat_error(cam_quat) if err < best_err: best_err = err @@ -624,76 +624,311 @@ def func(x): return camera_model -# Example usage -def example_usage(): - """Example showing how to use the alignment functions.""" - # Generate synthetic data - n_images = 10 - n_points = 20 - - # Create random points - points_3d = np.random.randn(n_points, 3) - - # Create random rotations - true_alignment = Rotation.random().as_quat() - ins_rotations = [Rotation.random() for _ in range(n_images)] - ins_quats = np.array([r.as_quat() for r in ins_rotations]) - - # Apply true alignment to get SfM rotations - R_align = Rotation.from_quat(true_alignment) - sfm_rotations = [R_align * r for r in ins_rotations] - sfm_quats = np.array([r.as_quat() for r in sfm_rotations]) - - # Create observations with partial visibility - observations = [] - for i in range(n_images): - camera_obs = [] - for j in range(n_points): - # Randomly make some points invisible - visible = random.random() > 0.3 - if visible: - # Add some noise to visible points - uncertainty = 0.01 * np.random.rand() - image_point = np.random.randn(2) # Dummy 2D point - camera_obs.append( - VisiblePoint( - point_3d=points_3d[j], - uncertainty=uncertainty, - image_point=image_point, - visible=True, - ) - ) - else: - camera_obs.append( - VisiblePoint( - point_3d=points_3d[j], - uncertainty=float("inf"), - image_point=np.zeros(2), - visible=False, - ) - ) - observations.append(camera_obs) - - # Estimate rotation - estimate = weighted_horn_alignment_partial( - observations=observations, - sfm_quats=sfm_quats, - ins_quats=ins_quats, - min_points_per_image=3, - ransac_iters=100, - ) +def transfer_alignment( + colmap_camera: pycolmap._core.Camera, + calibrated_camera: pycolmap._core.Camera, + nav_state_provider: NavStateINSJson, + points_per_image: List[List[VisiblePoint]], + calibrated_camera_model: StandardCamera, +) -> StandardCamera: + # Both quaternions are of the form (x, y, z, w) and represent a coordinate + # system rotation. + skipped = 0 + total = 0 + im_pts_uv = [] + im_pts_rgb = [] + + organized_points_per_frame = [] + for pts in points_per_image: + max_uncertainty = 1 + xy = [] + xyz = [] + xyz_ids = [] + for pt in pts: + if pt.uncertainty < max_uncertainty: + xy.append(pt.point_2d) + xyz.append(pt.point_3d) + xyz_ids.append(pt.point_3d_id) + # time is the same for all points, since it's a single frame + xy = np.array(xy) + xyz = np.array(xyz) + organized_points_per_frame.append((xy, xyz, xyz_ids, pts[0].time)) + return + + # Build up pairs of image coordinates between the two cameras from image + # pairs acquired from the same time. + # for pts in zip(points_per_image): + # xys1, xyzs1, xyz1_ids, t1 = pts + + # for _id in xyz1_ids: + # if calibrated_camera.has_point3D(_id): + + # xys2, xyzs2, t2 = colocated_pts + # base_name = get_base_name(image_uv.name) + + # try: + # t1 = basename_to_time[base_name] + # except KeyError: + # print(f"No time found for {base_name}.") + # continue + + # try: + # image_rgb = time_to_modality[t1]["rgb"] + # except KeyError: + # print(f"No rgb image found at {t1}.") + # continue + + # # Both 'uv_image' and 'image_rgb' are from the same time. + # pt_ids1 = image_uv.point3D_ids + # ind = pt_ids1 != -1 + # xys1 = dict(zip(pt_ids1[ind], image_uv.xys[ind])) + + # pt_ids2 = image_rgb.point3D_ids + # ind = pt_ids2 != -1 + # xys2 = dict(zip(pt_ids2[ind], image_rgb.xys[ind])) + + # match_ids = set(xys1.keys()).intersection(set(xys2.keys())) + # total += 1 + # if len(match_ids) < 1: + # # print("No match IDs found.") + # skipped += 1 + # continue + + # for match_id in match_ids: + # im_pts_uv.append(xys1[match_id]) + # im_pts_rgb.append(xys2[match_id]) + + # print( + # f"Matched {total-skipped}/{total} image pairs, resulting in " + # f"{len(im_pts_uv)} matching UV and RGB points." + # ) + + # im_pts_uv = np.array(im_pts_uv) + # im_pts_rgb = np.array(im_pts_rgb) + ## Arbitrary cut off + # minimum_pts_required = 10 + # if len(im_pts_rgb) < minimum_pts_required or len(im_pts_uv) < minimum_pts_required: + # print( + # "[ERROR] Not enough matching RGB/UV image points were found " + # f"for camera {uv_str}." + # ) + # continue + + # if False: + # plt.subplot(121) + # plt.plot(im_pts_uv[:, 0], im_pts_uv[:, 1], "ro") + # plt.subplot(122) + # plt.plot(im_pts_rgb[:, 0], im_pts_rgb[:, 1], "bo") + + ## Treat as co-located cameras (they are) and unproject out of RGB and into + ## the other camera. + # ray_pos, ray_dir = cm_rgb.unproject(im_pts_rgb.T) + # wrld_pts = ray_dir.T * 1e4 + # assert np.all(np.isfinite(wrld_pts)), "World points contain non-finite values." + + # colmap_camera = camera_from_camera_str[uv_str] + + # if colmap_camera.model == "OPENCV": + # fx, fy, cx, cy, d1, d2, d3, d4 = colmap_camera.params + # elif colmap_camera.model == "PINHOLE": + # fx, fy, cx, cy = colmap_camera.params + # d1 = d2 = d3 = d4 = 0 + + # K = np.array([[fx, 0, cx], [0, fy, cy], [0, 0, 1]]) + # dist = np.array([d1, d2, d3, d4], dtype=np.float32) + + # flags = cv2.CALIB_ZERO_TANGENT_DIST + # flags = flags | cv2.CALIB_USE_INTRINSIC_GUESS + # flags = flags | cv2.CALIB_FIX_PRINCIPAL_POINT + # flags = flags | cv2.CALIB_FIX_K1 + # flags = flags | cv2.CALIB_FIX_K2 + # flags = flags | cv2.CALIB_FIX_K3 + # flags = flags | cv2.CALIB_FIX_K4 + # flags = flags | cv2.CALIB_FIX_K5 + # flags = flags | cv2.CALIB_FIX_K6 + + # criteria = ( + # cv2.TERM_CRITERIA_EPS + cv2.TERM_CRITERIA_MAX_ITER, + # 30000, + # 0.0000001, + # ) - # Analyze results - analyze_rotation_estimate(estimate) + # ret = cv2.calibrateCamera( + # [wrld_pts.astype(np.float32)], + # [im_pts_uv.astype(np.float32)], + # (colmap_camera.width, colmap_camera.height), + # cameraMatrix=K.copy(), + # distCoeffs=dist.copy(), + # flags=flags, + # criteria=criteria, + # ) - # Compare to ground truth - error_rot = ( - Rotation.from_quat(estimate.quaternion) - * Rotation.from_quat(true_alignment).inv() - ) - error_angle = np.abs(error_rot.magnitude()) - print(f"\nError from ground truth: {np.degrees(error_angle):.2f}°") + # err, _, _, rvecs, tvecs = ret + + # R = np.identity(4) + # R[:3, :3] = cv2.Rodrigues(rvecs[0])[0] + # cam_quat = quaternion_from_matrix(R.T) + + ## Only optimize 3/4 components of the quaternion. + # static_quat_ind = np.argmax(np.abs(cam_quat)) + # dynamic_quat_ind = [i for i in range(4) if i != static_quat_ind] + ## static_quat_ind = 3 # Fixing the 'w' component + ## dynamic_quat_ind = [0, 1, 2] # Optimizing 'x', 'y', 'z' components + # dynamic_quat_ind = np.array(dynamic_quat_ind) + # cam_quat = np.asarray(cam_quat) + # cam_quat /= np.linalg.norm(cam_quat) + # x0 = cam_quat[dynamic_quat_ind].copy() # [x, y, z] + + # def get_cm(x): + # """ + # Create a camera model with updated quaternion and intrinsic parameters. + + # Parameters: + # - x: array-like, shape (N,) + # Optimization variables where the first 3 elements correspond to + # the dynamic quaternion components ('x', 'y', 'z'), optionally + # followed by intrinsic parameters ('fx', 'fy', etc.). + + # Returns: + # - cm: StandardCamera instance + # Updated camera model with new parameters. + # """ + # # Ensure 'x' has at least 3 elements for quaternion + # assert ( + # len(x) > 2 + # ), "Optimization variable 'x' must have at least 3 elements for quaternion." + + # # Validate 'x[:3]' are finite numbers + # assert np.all( + # np.isfinite(x[:3]) + # ), "Quaternion components contain non-finite values." + + # # Initialize quaternion with fixed 'w' component + # cam_quat_new = np.ones(4) + + # # Assign dynamic components from optimization variables + # cam_quat_new[dynamic_quat_ind] = x[:3] + + # # Normalize to ensure it's a unit quaternion + # norm = np.linalg.norm(cam_quat_new) + # assert norm > 1e-6, "Quaternion has zero or near-zero magnitude." + # cam_quat_new /= norm + + # # Extract intrinsic parameters + # if len(x) > 3: + # fx_ = x[3] + # fy_ = x[4] + # else: + # fx_ = fx + # fy_ = fy + + # if len(x) > 5: + # dist_ = x[5:] + # else: + # dist_ = dist + + # # Construct the intrinsic matrix + # K = np.array([[fx_, 0, cx], [0, fy_, cy], [0, 0, 1]]) + + # # Create the camera model + # cm = StandardCamera( + # colmap_camera.width, + # colmap_camera.height, + # K, + # dist_, + # [0, 0, 0], + # cam_quat_new, + # platform_pose_provider=nav_state_fixed, + # ) + # return cm + + # def error(x): + # try: + # cm = get_cm(x) + # projected_uv = cm.project(wrld_pts.T).T # Shape: (N, 2) + + # # Compute Euclidean distances + # err = np.sqrt(np.sum((im_pts_uv - projected_uv) ** 2, axis=1)) + + # # Apply Huber loss + # delta = 20 + # ind = err < delta + # err[ind] = err[ind] ** 2 + # err[~ind] = 2 * (err[~ind] - delta / 2) * delta + + # # Sort and trim the error + # err = sorted(err)[: len(err) - len(err) // 5] + + # # Compute mean error + # mean_err = np.sqrt(np.mean(err)) + + # # Add regularization term (e.g., L2 penalty) + # reg_strength = 1e-3 # Adjust as needed + # reg_term = reg_strength * np.linalg.norm(x[:3]) ** 2 + + # total_error = mean_err + reg_term + # return total_error + # except Exception as e: + # print(f"Error in error function: {e}") + # return np.inf # Assign a high error if computation fails + + ## Optional: Define a callback function to monitor optimization + # def callback(xk): + # try: + # cm = get_cm(xk) + # projected_uv = cm.project(wrld_pts.T).T + # err = np.sqrt(np.sum((im_pts_uv - projected_uv) ** 2, axis=1)) + # mean_err = np.mean(err) + # print(f"Current x: {xk}, Mean Error: {mean_err}") + # except Exception as e: + # print(f"Error in callback: {e}") + + # def plot_results1(x): + # cm = get_cm(x) + # err = np.sqrt(np.sum((im_pts_uv - cm.project(wrld_pts.T).T) ** 2, 1)) + # err = sorted(err) + # plt.plot(np.linspace(0, 100, len(err)), err) + + # print("Optimizing error for UV models.") + # x = x0.copy() + ## Example bounds for [x, y, z] components + # bounds = [ + # (-1.0, 1.0), # x + # (-1.0, 1.0), # y + # (-1.0, 1.0), + # ] # z + # print("First pass") + ## Perform optimization on [x, y, z] + # ret = minimize( + # error, + # x, + # method="L-BFGS-B", + # bounds=bounds, + # callback=None, # Optional: Monitor progress + # options={"disp": False, "maxiter": 30000, "ftol": 1e-7}, + # ) + # assert ret.success, "Minimization of UV error failed." + # x = np.hstack([ret.x, fx, fy]) + # print("Second pass") + # assert np.all(np.isfinite(x)), "Input quaternion with locked fx, fy, is not finite." + # ret = minimize(error, x, method="Powell") + # x = ret.x + # print("Third pass") + # assert np.all(np.isfinite(x)), "Input quaternion for BFGS is not finite." + # ret = minimize(error, x, method="BFGS") + + # print("Final pass") + # if True: + # x = np.hstack([ret.x, dist]) + # ret = minimize(error, x, method="Powell") + # x = ret.x + # ret = minimize(error, x, method="BFGS") + # x = ret.x + + # assert np.all(np.isfinite(x)), "Input quaternion for final model is not finite." + # cm_uv = get_cm(x) + # cm_uv.save_to_file("%s/%s.yaml" % (save_dir, uv_str)) if __name__ == "__main__": - example_usage() + pass diff --git a/kamera/postflight/colmap.py b/kamera/postflight/colmap.py index 3b88f61..26ce0f3 100644 --- a/kamera/postflight/colmap.py +++ b/kamera/postflight/colmap.py @@ -18,11 +18,8 @@ from kamera.colmap_processing.image_renderer import render_view from kamera.postflight.alignment import ( VisiblePoint, - weighted_horn_alignment_partial, - analyze_rotation_estimate, - register_camera_horn_ransac, - verify_alignment, iterative_alignment, + transfer_alignment, ) @@ -128,6 +125,9 @@ def prepare_calibration_data(self): image.cam_from_world.rotation.normalize() quat = image.cam_from_world.rotation.quat + # invert the w (rotation) component, + # so we get the camera to world rotation + quat[3] *= -1 sfm_pose = [pos, quat] @@ -144,10 +144,15 @@ def prepare_calibration_data(self): uncertainty = self.R.points3D[pt.point3D_id].error point_3d = self.R.points3D[pt.point3D_id].xyz visible = True - vpt = VisiblePoint(point_3d, point_2d, uncertainty, t, visible) + point_3d_id = pt.point3D_id + vpt = VisiblePoint( + point_3d, point_3d_id, point_2d, uncertainty, t, visible + ) points.append(vpt) points_per_image.append(points) camera_name = os.path.basename(os.path.dirname(image.name)) + # as a way to choose the first quaternion we check, choose the one + # that has the most number of 3D points registered if camera_name in best_cameras: if image.num_points3D > most_points[camera_name]: best_cameras[camera_name] = image.camera @@ -206,39 +211,45 @@ def calibrate_camera( camera_model = iterative_alignment( cam_sfm_quats, cam_ins_quats, observations, cam, self.nav_state_provider ) - # best_rotation = weighted_horn_alignment_partial( - # observations, - # cam_sfm_quats, - # cam_ins_quats, - # min_points_per_image=10, - # ransac_iters=100, - # error_threshold=error_threshold, - # ) - # analyze_rotation_estimate(best_rotation) - # best_quat = best_rotation.quaternion - # K = cam.calibration_matrix() - # if cam.model.name == "OPENCV": - # fx, fy, cx, cy, d1, d2, d3, d4 = cam.params - # elif cam.model.name == "SIMPLE_RADIAL": - # d1 = d2 = d3 = d4 = 0 - # elif cam.model.name == "PINHOLE": - # d1 = d2 = d3 = d4 = 0 - # else: - # raise SystemError(f"Unexpected camera model found: {cam.model.name}") - - # dist = np.array([d1, d2, d3, d4]) - # camera_model = StandardCamera( - # cam.width, - # cam.height, - # K, - # dist, - # [0, 0, 0], - # best_quat, - # platform_pose_provider=self.nav_state_provider, - # ) - return camera_model + def transfer_calibration( + self, + camera_name: str, + calibrated_camera_model: StandardCamera, + calibrated_modality: str, + error_threshold: float, + ) -> StandardCamera: + """ + Use the quaternion already solved of a colocated, calibrated camera + to bootstrap the calibration process. + """ + # Find all valid indices of current cameras + channel, modality = camera_name.split("_")[2:] + cam_idxs = [ + 1 if camera_name == os.path.basename(os.path.dirname(im)) else 0 + for im in self.ccd.img_fnames + ] + print(f"Number of images in camera {camera_name}.") + print(np.sum(cam_idxs)) + observations = [ + pts for i, pts in enumerate(self.ccd.points_per_image) if cam_idxs[i] == 1 + ] + if len(observations) < 10: + print(f"Only {len(observations)} seen for camera {camera_name}, skipping.") + + # Now we have to find the overlapping observations on a per-frame basis between + # the camera to calibrate, and the colocated, calibrated, camera. + for i, fname in enumerate(self.ccd.img_fnames): + if cam_idxs[i] == 1: + calibrated_fname = fname.replace(modality, calibrated_modality) + ii = self.ccd.img_fnames.index(calibrated_fname) + cam = self.ccd.best_cameras[camera_name] + # camera_model = transfer_alignment( + # cam, calibrated_cam, observations, self.nav_state_provider + # ) + return None # camera_model + def create_fname_to_time_channel_modality( self, img_fnames, basename_to_time ) -> Dict[float, Dict[str, str]]: diff --git a/kamera/postflight/scripts/calibration.py b/kamera/postflight/scripts/calibration.py index 0e58cad..4834c66 100644 --- a/kamera/postflight/scripts/calibration.py +++ b/kamera/postflight/scripts/calibration.py @@ -8,7 +8,7 @@ def main(): # REQUIREMENTS: Must already have built a reasonable 3-D model using Colmap # And have a flight directory populated by the kamera system - flight_dir = "" + flight_dir = "/home/local/KHQ/adam.romlein/noaa/data/2024_AOC_AK_Calibration/fl09" colmap_dir = os.path.join(flight_dir, "colmap") # Location to save KAMERA camera models. save_dir = os.path.join(flight_dir, "kamera_models") @@ -49,10 +49,20 @@ def main(): cc.prepare_calibration_data() ub.ensuredir(save_dir) cameras = ub.AutoDict() + camera_strs = list(cc.ccd.best_cameras.keys()) + modalities = [cs.split("_")[3] for cs in camera_strs] + joint_calibration = False + # can switch to UV / IR if possible that they are better aligned + main_modality = "rgb" + if "uv" in modalities and "rgb" in modalities: + # both UV and RGB are in this colmap 3D model, so we're going to + # jointly calibrate the 2 + joint_calibration = True for camera_str in cc.ccd.best_cameras.keys(): channel, modality = camera_str.split("_")[2:] - # if modality != "rgb": - # continue + # skip all modalities except the "main" ones + if joint_calibration and modality != main_modality: + continue print(f"Calibrating camera {camera_str}.") tic = time.time() camera_model = cc.calibrate_camera(camera_str, error_threshold=100) @@ -67,6 +77,33 @@ def main(): else: print(f"Calibrating camera {camera_str} failed.") + if joint_calibration: + for camera_str in cc.ccd.best_cameras.keys(): + channel, modality = camera_str.split("_")[2:] + # now calibrate all other modalities + if modality == main_modality: + continue + print(f"Calibrating camera {camera_str}.") + tic = time.time() + camera_model = cc.transfer_calibration( + camera_str, + cameras[channel][main_modality], + calibrated_modality=main_modality, + error_threshold=100, + ) + toc = time.time() + if camera_model is not None: + out_path = os.path.join(save_dir, f"{camera_str}_v2.yaml") + print(f"Saving camera model to {out_path}") + camera_model.save_to_file(out_path) + print( + f"Time to transfer camera calibration to {camera_str} was {(toc - tic):.3f}s" + ) + print(camera_model) + cameras[channel][modality] = camera_model + else: + print(f"Calibrating camera {camera_str} failed.") + aircraft, angle = camera_str.split("_")[0:2] gif_dir = os.path.join(save_dir, "registration_gifs_v2") ub.ensuredir(gif_dir) From 9aa974c7b27bf23ec1896b5feb209b828fbdeac9 Mon Sep 17 00:00:00 2001 From: Adam Romlein Date: Wed, 12 Mar 2025 10:00:48 -0400 Subject: [PATCH 09/20] Add a 'transfer_calibration' function for the UV calibration method, using existing RGB models. --- kamera/postflight/alignment.py | 533 +++++++++++------------ kamera/postflight/colmap.py | 23 +- kamera/postflight/scripts/calibration.py | 65 ++- 3 files changed, 308 insertions(+), 313 deletions(-) diff --git a/kamera/postflight/alignment.py b/kamera/postflight/alignment.py index a7fccc6..e4bc506 100644 --- a/kamera/postflight/alignment.py +++ b/kamera/postflight/alignment.py @@ -1,4 +1,5 @@ import random +import cv2 import numpy as np from dataclasses import dataclass from typing import List, NamedTuple, Optional, Tuple @@ -6,7 +7,7 @@ from scipy.spatial.transform import Rotation import pycolmap from kamera.colmap_processing.camera_models import StandardCamera -from kamera.sensor_models.nav_state import NavStateINSJson +from kamera.sensor_models.nav_state import NavStateINSJson, NavStateFixed @dataclass @@ -534,9 +535,6 @@ def cam_quat_error(cam_quat: np.ndarray) -> float: # Update uncertainty based on errors # check quaternion alignment over all frames for xys, xyzs, t in organized_points_per_frame: - xys = [] - xyzs = [] - xys = np.array(xys) xyzs = np.array(xyzs) # Error in meters. @@ -626,120 +624,95 @@ def func(x): def transfer_alignment( colmap_camera: pycolmap._core.Camera, - calibrated_camera: pycolmap._core.Camera, - nav_state_provider: NavStateINSJson, - points_per_image: List[List[VisiblePoint]], calibrated_camera_model: StandardCamera, + points_per_image: List[List[VisiblePoint]], + colocated_points_per_image: List[List[VisiblePoint]], ) -> StandardCamera: - # Both quaternions are of the form (x, y, z, w) and represent a coordinate - # system rotation. + im_pts = [] + colocated_im_pts = [] skipped = 0 total = 0 - im_pts_uv = [] - im_pts_rgb = [] - organized_points_per_frame = [] - for pts in points_per_image: - max_uncertainty = 1 - xy = [] - xyz = [] - xyz_ids = [] - for pt in pts: - if pt.uncertainty < max_uncertainty: - xy.append(pt.point_2d) - xyz.append(pt.point_3d) - xyz_ids.append(pt.point_3d_id) - # time is the same for all points, since it's a single frame - xy = np.array(xy) - xyz = np.array(xyz) - organized_points_per_frame.append((xy, xyz, xyz_ids, pts[0].time)) - return - - # Build up pairs of image coordinates between the two cameras from image - # pairs acquired from the same time. - # for pts in zip(points_per_image): - # xys1, xyzs1, xyz1_ids, t1 = pts - - # for _id in xyz1_ids: - # if calibrated_camera.has_point3D(_id): - - # xys2, xyzs2, t2 = colocated_pts - # base_name = get_base_name(image_uv.name) - - # try: - # t1 = basename_to_time[base_name] - # except KeyError: - # print(f"No time found for {base_name}.") - # continue - - # try: - # image_rgb = time_to_modality[t1]["rgb"] - # except KeyError: - # print(f"No rgb image found at {t1}.") - # continue - - # # Both 'uv_image' and 'image_rgb' are from the same time. - # pt_ids1 = image_uv.point3D_ids - # ind = pt_ids1 != -1 - # xys1 = dict(zip(pt_ids1[ind], image_uv.xys[ind])) - - # pt_ids2 = image_rgb.point3D_ids - # ind = pt_ids2 != -1 - # xys2 = dict(zip(pt_ids2[ind], image_rgb.xys[ind])) - - # match_ids = set(xys1.keys()).intersection(set(xys2.keys())) - # total += 1 - # if len(match_ids) < 1: - # # print("No match IDs found.") - # skipped += 1 - # continue - - # for match_id in match_ids: - # im_pts_uv.append(xys1[match_id]) - # im_pts_rgb.append(xys2[match_id]) - - # print( - # f"Matched {total-skipped}/{total} image pairs, resulting in " - # f"{len(im_pts_uv)} matching UV and RGB points." - # ) + for i, pts in enumerate(points_per_image): + pts = np.asarray(pts) + pt_3d_ids = np.asarray([pt.point_3d_id for pt in pts]) + colocated_pts = np.asarray(colocated_points_per_image[i]) + colocated_pt_3d_ids = np.asarray([pt.point_3d_id for pt in colocated_pts]) + + # Need to make a unique here, since there are some non-unique 3d IDs for a + # multiple 2D points. This gets complicated, since we need to retain the original + # indices, so we return the index obtained via np.unique + uniq_pt_3d_ids, uniq_idx = np.unique(pt_3d_ids, return_index=True) + uniq_colocated_pt_3d_ids, colocated_uniq_idx = np.unique( + colocated_pt_3d_ids, return_index=True + ) + + # Get correspondences from uncalibrated -> colocated camera + match_idx = np.isin( + uniq_pt_3d_ids, uniq_colocated_pt_3d_ids, assume_unique=True + ) + if len(match_idx) < 1: + print("No matching 3D points found!") + continue + temp_pts = [pt.point_2d for pt in pts[uniq_idx][match_idx]] + + # Since they're both unique, commutative, so repeat the process but in opposite + # to find colocated -> uncalibrated correspondences + colocated_match_idx = np.isin( + uniq_colocated_pt_3d_ids, uniq_pt_3d_ids, assume_unique=True + ) + temp_colocated_pts = [ + pt.point_2d for pt in colocated_pts[colocated_uniq_idx][colocated_match_idx] + ] + + im_pts += temp_pts + colocated_im_pts += temp_colocated_pts + + # Since both are equal, can take the total of either + total += np.sum(colocated_match_idx) + print( + f"Matched {i-skipped}/{i} image pairs, resulting in " + f"{total} matching 2D points." + ) + + im_pts = np.array(im_pts) + colocated_im_pts = np.array(colocated_im_pts) + + # Arbitrary cut off + minimum_pts_required = 10 + if ( + len(im_pts) < minimum_pts_required + or len(colocated_im_pts) < minimum_pts_required + ): + print("[ERROR] Not enough matching 2D image points were found for camera.") + return + + # Treat as co-located cameras (they are) and unproject out of RGB and into + # the other camera. + ray_pos, ray_dir = calibrated_camera_model.unproject(colocated_im_pts.T) + wrld_pts = ray_dir.T * 1e4 + assert np.all(np.isfinite(wrld_pts)), "World points contain non-finite values." - # im_pts_uv = np.array(im_pts_uv) - # im_pts_rgb = np.array(im_pts_rgb) - ## Arbitrary cut off - # minimum_pts_required = 10 - # if len(im_pts_rgb) < minimum_pts_required or len(im_pts_uv) < minimum_pts_required: - # print( - # "[ERROR] Not enough matching RGB/UV image points were found " - # f"for camera {uv_str}." - # ) - # continue - - # if False: - # plt.subplot(121) - # plt.plot(im_pts_uv[:, 0], im_pts_uv[:, 1], "ro") - # plt.subplot(122) - # plt.plot(im_pts_rgb[:, 0], im_pts_rgb[:, 1], "bo") - - ## Treat as co-located cameras (they are) and unproject out of RGB and into - ## the other camera. - # ray_pos, ray_dir = cm_rgb.unproject(im_pts_rgb.T) - # wrld_pts = ray_dir.T * 1e4 - # assert np.all(np.isfinite(wrld_pts)), "World points contain non-finite values." - - # colmap_camera = camera_from_camera_str[uv_str] - - # if colmap_camera.model == "OPENCV": - # fx, fy, cx, cy, d1, d2, d3, d4 = colmap_camera.params - # elif colmap_camera.model == "PINHOLE": - # fx, fy, cx, cy = colmap_camera.params - # d1 = d2 = d3 = d4 = 0 - - # K = np.array([[fx, 0, cx], [0, fy, cy], [0, 0, 1]]) - # dist = np.array([d1, d2, d3, d4], dtype=np.float32) - - # flags = cv2.CALIB_ZERO_TANGENT_DIST - # flags = flags | cv2.CALIB_USE_INTRINSIC_GUESS - # flags = flags | cv2.CALIB_FIX_PRINCIPAL_POINT + if colmap_camera.model == "OPENCV": + fx, fy, cx, cy, d1, d2, d3, d4 = colmap_camera.params + elif colmap_camera.model == "PINHOLE": + fx, fy, cx, cy = colmap_camera.params + d1 = d2 = d3 = d4 = 0 + + K = colmap_camera.calibration_matrix() + if colmap_camera.model.name == "OPENCV": + fx, fy, cx, cy, d1, d2, d3, d4 = colmap_camera.params + elif colmap_camera.model.name == "SIMPLE_RADIAL": + d1 = d2 = d3 = d4 = 0 + elif colmap_camera.model.name == "PINHOLE": + d1 = d2 = d3 = d4 = 0 + else: + raise SystemError(f"Unexpected camera model found: {colmap_camera.model.name}") + dist = np.array([d1, d2, d3, d4]) + + flags = cv2.CALIB_ZERO_TANGENT_DIST + flags = flags | cv2.CALIB_USE_INTRINSIC_GUESS + flags = flags | cv2.CALIB_FIX_PRINCIPAL_POINT # flags = flags | cv2.CALIB_FIX_K1 # flags = flags | cv2.CALIB_FIX_K2 # flags = flags | cv2.CALIB_FIX_K3 @@ -747,187 +720,175 @@ def transfer_alignment( # flags = flags | cv2.CALIB_FIX_K5 # flags = flags | cv2.CALIB_FIX_K6 - # criteria = ( - # cv2.TERM_CRITERIA_EPS + cv2.TERM_CRITERIA_MAX_ITER, - # 30000, - # 0.0000001, - # ) + criteria = ( + cv2.TERM_CRITERIA_EPS + cv2.TERM_CRITERIA_MAX_ITER, + 30000, + 0.0000001, + ) - # ret = cv2.calibrateCamera( - # [wrld_pts.astype(np.float32)], - # [im_pts_uv.astype(np.float32)], - # (colmap_camera.width, colmap_camera.height), - # cameraMatrix=K.copy(), - # distCoeffs=dist.copy(), - # flags=flags, - # criteria=criteria, - # ) + print(len(wrld_pts)) + print(len(im_pts)) + + ret = cv2.calibrateCamera( + [wrld_pts.astype(np.float32)], + [im_pts.astype(np.float32)], + (colmap_camera.width, colmap_camera.height), + cameraMatrix=K.copy(), + distCoeffs=dist.copy(), + flags=flags, + criteria=criteria, + ) - # err, _, _, rvecs, tvecs = ret + err, _, _, rvecs, tvecs = ret # R = np.identity(4) - # R[:3, :3] = cv2.Rodrigues(rvecs[0])[0] + R = cv2.Rodrigues(rvecs[0])[0] + cam_quat = Rotation.from_matrix(R.T).as_quat() # cam_quat = quaternion_from_matrix(R.T) ## Only optimize 3/4 components of the quaternion. - # static_quat_ind = np.argmax(np.abs(cam_quat)) - # dynamic_quat_ind = [i for i in range(4) if i != static_quat_ind] - ## static_quat_ind = 3 # Fixing the 'w' component - ## dynamic_quat_ind = [0, 1, 2] # Optimizing 'x', 'y', 'z' components - # dynamic_quat_ind = np.array(dynamic_quat_ind) - # cam_quat = np.asarray(cam_quat) - # cam_quat /= np.linalg.norm(cam_quat) - # x0 = cam_quat[dynamic_quat_ind].copy() # [x, y, z] - - # def get_cm(x): - # """ - # Create a camera model with updated quaternion and intrinsic parameters. - - # Parameters: - # - x: array-like, shape (N,) - # Optimization variables where the first 3 elements correspond to - # the dynamic quaternion components ('x', 'y', 'z'), optionally - # followed by intrinsic parameters ('fx', 'fy', etc.). - - # Returns: - # - cm: StandardCamera instance - # Updated camera model with new parameters. - # """ - # # Ensure 'x' has at least 3 elements for quaternion - # assert ( - # len(x) > 2 - # ), "Optimization variable 'x' must have at least 3 elements for quaternion." - - # # Validate 'x[:3]' are finite numbers - # assert np.all( - # np.isfinite(x[:3]) - # ), "Quaternion components contain non-finite values." - - # # Initialize quaternion with fixed 'w' component - # cam_quat_new = np.ones(4) - - # # Assign dynamic components from optimization variables - # cam_quat_new[dynamic_quat_ind] = x[:3] - - # # Normalize to ensure it's a unit quaternion - # norm = np.linalg.norm(cam_quat_new) - # assert norm > 1e-6, "Quaternion has zero or near-zero magnitude." - # cam_quat_new /= norm - - # # Extract intrinsic parameters - # if len(x) > 3: - # fx_ = x[3] - # fy_ = x[4] - # else: - # fx_ = fx - # fy_ = fy - - # if len(x) > 5: - # dist_ = x[5:] - # else: - # dist_ = dist - - # # Construct the intrinsic matrix - # K = np.array([[fx_, 0, cx], [0, fy_, cy], [0, 0, 1]]) - - # # Create the camera model - # cm = StandardCamera( - # colmap_camera.width, - # colmap_camera.height, - # K, - # dist_, - # [0, 0, 0], - # cam_quat_new, - # platform_pose_provider=nav_state_fixed, - # ) - # return cm - - # def error(x): - # try: - # cm = get_cm(x) - # projected_uv = cm.project(wrld_pts.T).T # Shape: (N, 2) - - # # Compute Euclidean distances - # err = np.sqrt(np.sum((im_pts_uv - projected_uv) ** 2, axis=1)) - - # # Apply Huber loss - # delta = 20 - # ind = err < delta - # err[ind] = err[ind] ** 2 - # err[~ind] = 2 * (err[~ind] - delta / 2) * delta - - # # Sort and trim the error - # err = sorted(err)[: len(err) - len(err) // 5] - - # # Compute mean error - # mean_err = np.sqrt(np.mean(err)) - - # # Add regularization term (e.g., L2 penalty) - # reg_strength = 1e-3 # Adjust as needed - # reg_term = reg_strength * np.linalg.norm(x[:3]) ** 2 - - # total_error = mean_err + reg_term - # return total_error - # except Exception as e: - # print(f"Error in error function: {e}") - # return np.inf # Assign a high error if computation fails - - ## Optional: Define a callback function to monitor optimization - # def callback(xk): - # try: - # cm = get_cm(xk) - # projected_uv = cm.project(wrld_pts.T).T - # err = np.sqrt(np.sum((im_pts_uv - projected_uv) ** 2, axis=1)) - # mean_err = np.mean(err) - # print(f"Current x: {xk}, Mean Error: {mean_err}") - # except Exception as e: - # print(f"Error in callback: {e}") - - # def plot_results1(x): - # cm = get_cm(x) - # err = np.sqrt(np.sum((im_pts_uv - cm.project(wrld_pts.T).T) ** 2, 1)) - # err = sorted(err) - # plt.plot(np.linspace(0, 100, len(err)), err) - - # print("Optimizing error for UV models.") - # x = x0.copy() - ## Example bounds for [x, y, z] components - # bounds = [ - # (-1.0, 1.0), # x - # (-1.0, 1.0), # y - # (-1.0, 1.0), - # ] # z - # print("First pass") - ## Perform optimization on [x, y, z] - # ret = minimize( - # error, - # x, - # method="L-BFGS-B", - # bounds=bounds, - # callback=None, # Optional: Monitor progress - # options={"disp": False, "maxiter": 30000, "ftol": 1e-7}, - # ) - # assert ret.success, "Minimization of UV error failed." - # x = np.hstack([ret.x, fx, fy]) - # print("Second pass") - # assert np.all(np.isfinite(x)), "Input quaternion with locked fx, fy, is not finite." - # ret = minimize(error, x, method="Powell") - # x = ret.x - # print("Third pass") - # assert np.all(np.isfinite(x)), "Input quaternion for BFGS is not finite." - # ret = minimize(error, x, method="BFGS") - - # print("Final pass") - # if True: - # x = np.hstack([ret.x, dist]) - # ret = minimize(error, x, method="Powell") - # x = ret.x - # ret = minimize(error, x, method="BFGS") - # x = ret.x - - # assert np.all(np.isfinite(x)), "Input quaternion for final model is not finite." - # cm_uv = get_cm(x) - # cm_uv.save_to_file("%s/%s.yaml" % (save_dir, uv_str)) + # static_quat_ind = 3 # Fixing the 'w' component + dynamic_quat_ind = [0, 1, 2] # Optimizing 'x', 'y', 'z' components + dynamic_quat_ind = np.array(dynamic_quat_ind) + cam_quat = np.asarray(cam_quat) + cam_quat /= np.linalg.norm(cam_quat) + x0 = cam_quat[dynamic_quat_ind].copy() # [x, y, z] + + nav_state_fixed = NavStateFixed(np.zeros(3), [0, 0, 0, 1]) + + def get_cm(x): + """ + Create a camera model with updated quaternion and intrinsic parameters. + + Parameters: + - x: array-like, shape (N,) + Optimization variables where the first 3 elements correspond to + the dynamic quaternion components ('x', 'y', 'z'), optionally + followed by intrinsic parameters ('fx', 'fy', etc.). + + Returns: + - cm: StandardCamera instance + Updated camera model with new parameters. + """ + # Ensure 'x' has at least 3 elements for quaternion + assert ( + len(x) > 2 + ), "Optimization variable 'x' must have at least 3 elements for quaternion." + + # Validate 'x[:3]' are finite numbers + assert np.all( + np.isfinite(x[:3]) + ), "Quaternion components contain non-finite values." + + # Initialize quaternion with fixed 'w' component + cam_quat_new = np.ones(4) + + # Assign dynamic components from optimization variables + cam_quat_new[dynamic_quat_ind] = x[:3] + + # Normalize to ensure it's a unit quaternion + norm = np.linalg.norm(cam_quat_new) + assert norm > 1e-6, "Quaternion has zero or near-zero magnitude." + cam_quat_new /= norm + + # Extract intrinsic parameters + if len(x) > 3: + fx_ = x[3] + fy_ = x[4] + else: + fx_ = fx + fy_ = fy + + if len(x) > 5: + dist_ = x[5:] + else: + dist_ = dist + + # Construct the intrinsic matrix + K = np.array([[fx_, 0, cx], [0, fy_, cy], [0, 0, 1]]) + + # Create the camera model + cm = StandardCamera( + colmap_camera.width, + colmap_camera.height, + K, + dist_, + [0, 0, 0], + cam_quat_new, + platform_pose_provider=nav_state_fixed, + ) + return cm + + def error(x): + try: + cm = get_cm(x) + projected = cm.project(wrld_pts.T).T # Shape: (N, 2) + + # Compute Euclidean distances + err = np.sqrt(np.sum((im_pts - projected) ** 2, axis=1)) + + # Apply Huber loss + delta = 20 + ind = err < delta + err[ind] = err[ind] ** 2 + err[~ind] = 2 * (err[~ind] - delta / 2) * delta + + # Sort and trim the error + err = sorted(err)[: len(err) - len(err) // 5] + + # Compute mean error + mean_err = np.sqrt(np.mean(err)) + + # Add regularization term (e.g., L2 penalty) + reg_strength = 1e-3 # Adjust as needed + reg_term = reg_strength * np.linalg.norm(x[:3]) ** 2 + + total_error = mean_err + reg_term + return total_error + except Exception as e: + print(f"Error in error function: {e}") + return np.inf # Assign a high error if computation fails + + print("Optimizing error for transfer models.") + x = x0.copy() + # Example bounds for [x, y, z] components + bounds = [ + (-1.0, 1.0), # x + (-1.0, 1.0), # y + (-1.0, 1.0), # z + ] + print("First pass") + # Perform optimization on [x, y, z] + ret = minimize( + error, + x, + method="L-BFGS-B", + bounds=bounds, + callback=None, # Optional: Monitor progress + options={"disp": False, "maxiter": 30000, "ftol": 1e-7}, + ) + assert ret.success, "Minimization of transfer calibration error failed." + x = np.hstack([ret.x, fx, fy]) + print("Second pass") + assert np.all(np.isfinite(x)), "Input quaternion with locked fx, fy, is not finite." + ret = minimize(error, x, method="Powell") + x = ret.x + print("Third pass") + assert np.all(np.isfinite(x)), "Input quaternion for BFGS is not finite." + ret = minimize(error, x, method="BFGS") + + print("Fourth pass") + x = np.hstack([ret.x, dist]) + ret = minimize(error, x, method="Powell") + x = ret.x + + print("Final pass") + ret = minimize(error, x, method="BFGS") + x = ret.x + + assert np.all(np.isfinite(x)), "Input quaternion for final model is not finite." + cm = get_cm(x) + return cm if __name__ == "__main__": diff --git a/kamera/postflight/colmap.py b/kamera/postflight/colmap.py index 26ce0f3..a6c13c2 100644 --- a/kamera/postflight/colmap.py +++ b/kamera/postflight/colmap.py @@ -235,20 +235,31 @@ def transfer_calibration( observations = [ pts for i, pts in enumerate(self.ccd.points_per_image) if cam_idxs[i] == 1 ] - if len(observations) < 10: - print(f"Only {len(observations)} seen for camera {camera_name}, skipping.") # Now we have to find the overlapping observations on a per-frame basis between # the camera to calibrate, and the colocated, calibrated, camera. + colocated_observations = [] + observations = [] for i, fname in enumerate(self.ccd.img_fnames): if cam_idxs[i] == 1: + # Replace with the modality of the already calibrated modality calibrated_fname = fname.replace(modality, calibrated_modality) ii = self.ccd.img_fnames.index(calibrated_fname) + colocated_observations.append(self.ccd.points_per_image[ii]) + observations.append(self.ccd.points_per_image[i]) + if len(observations) < 10 or len(colocated_observations) < 10: + print( + f"Only {len(observations)} seen for camera {camera_name}, and " + f" only {len(colocated_observations)} found for the calibrated camera, " + " skipping." + ) + return + cam = self.ccd.best_cameras[camera_name] - # camera_model = transfer_alignment( - # cam, calibrated_cam, observations, self.nav_state_provider - # ) - return None # camera_model + camera_model = transfer_alignment( + cam, calibrated_camera_model, observations, colocated_observations + ) + return camera_model def create_fname_to_time_channel_modality( self, img_fnames, basename_to_time diff --git a/kamera/postflight/scripts/calibration.py b/kamera/postflight/scripts/calibration.py index 4834c66..1032f35 100644 --- a/kamera/postflight/scripts/calibration.py +++ b/kamera/postflight/scripts/calibration.py @@ -2,6 +2,7 @@ import time import ubelt as ub +from kamera.colmap_processing.camera_models import load_from_file from kamera.postflight.colmap import ColmapCalibration, find_best_sparse_model @@ -14,6 +15,15 @@ def main(): save_dir = os.path.join(flight_dir, "kamera_models") # Location to find / build aligned model align_dir = os.path.join(colmap_dir, "aligned") + # This assumes that 2 modalities of cameras are within the 3-D model + joint_calibration = True + # Can switch to UV / IR if possible that they are better aligned + main_modality = "rgb" + # If camera models are already present, if true this will overwrite + force_calibrate = False + # Whether to calibrate IR models or not. A "colmap_ir" must be built + # in the same folder + calibrate_ir = True # Step 1: Make sure the model is aligned to the INS readings, if not, # find the best model and align it. @@ -51,32 +61,40 @@ def main(): cameras = ub.AutoDict() camera_strs = list(cc.ccd.best_cameras.keys()) modalities = [cs.split("_")[3] for cs in camera_strs] - joint_calibration = False - # can switch to UV / IR if possible that they are better aligned - main_modality = "rgb" - if "uv" in modalities and "rgb" in modalities: - # both UV and RGB are in this colmap 3D model, so we're going to - # jointly calibrate the 2 - joint_calibration = True + if len(modalities) < 1: + print( + "Warning: only 1 modality found in this 3D model, not joinly calibrating." + ) + joint_calibration = False for camera_str in cc.ccd.best_cameras.keys(): channel, modality = camera_str.split("_")[2:] # skip all modalities except the "main" ones if joint_calibration and modality != main_modality: continue - print(f"Calibrating camera {camera_str}.") - tic = time.time() - camera_model = cc.calibrate_camera(camera_str, error_threshold=100) - toc = time.time() - if camera_model is not None: - out_path = os.path.join(save_dir, f"{camera_str}_v2.yaml") - print(f"Saving camera model to {out_path}") - camera_model.save_to_file(out_path) - print(f"Time to calibrate camera {camera_str} was {(toc - tic):.3f}s") - print(camera_model) + out_path = os.path.join(save_dir, f"{camera_str}_v2.yaml") + # skip compute if we don't have to recompute + if os.path.exists(out_path) and not force_calibrate: + print( + f"Camera model path {out_path} exists and force_calibrate is turned off, loading model." + ) + camera_model = load_from_file(out_path) cameras[channel][modality] = camera_model else: - print(f"Calibrating camera {camera_str} failed.") + print(f"Calibrating camera {camera_str}.") + tic = time.time() + camera_model = cc.calibrate_camera(camera_str, error_threshold=100) + toc = time.time() + if camera_model is not None: + print(f"Saving camera model to {out_path}") + camera_model.save_to_file(out_path) + print(f"Time to calibrate camera {camera_str} was {(toc - tic):.3f}s") + print(camera_model) + cameras[channel][modality] = camera_model + else: + print(f"Calibrating camera {camera_str} failed.") + # If we have multiple cameras within one model, we can utilize the fact that these cameras + # are colocated to use 3D points obtained from one to project into the other if joint_calibration: for camera_str in cc.ccd.best_cameras.keys(): channel, modality = camera_str.split("_")[2:] @@ -84,14 +102,14 @@ def main(): if modality == main_modality: continue print(f"Calibrating camera {camera_str}.") - tic = time.time() + tic = time.perf_counter() camera_model = cc.transfer_calibration( camera_str, cameras[channel][main_modality], calibrated_modality=main_modality, error_threshold=100, ) - toc = time.time() + toc = time.perf_counter() if camera_model is not None: out_path = os.path.join(save_dir, f"{camera_str}_v2.yaml") print(f"Saving camera model to {out_path}") @@ -102,7 +120,12 @@ def main(): print(camera_model) cameras[channel][modality] = camera_model else: - print(f"Calibrating camera {camera_str} failed.") + print(f"Transferring calibration to camera {camera_str} failed.") + + # IR calibration generally happens in a separate model, since SIFT has a hard + # time matching between EO and long-wave IR + if calibrate_ir: + colmap_dir = os.path.join(flight_dir, "colmap") aircraft, angle = camera_str.split("_")[0:2] gif_dir = os.path.join(save_dir, "registration_gifs_v2") From 25b1d2d58b0e87c67dafe3bc9f32976360300a5c Mon Sep 17 00:00:00 2001 From: Adam Romlein Date: Wed, 12 Mar 2025 12:35:07 -0400 Subject: [PATCH 10/20] Add IR calibration and GIF generation --- kamera/postflight/colmap.py | 119 ++++++++++++------ kamera/postflight/scripts/calibration.py | 146 ++++++++++++++++------- 2 files changed, 186 insertions(+), 79 deletions(-) diff --git a/kamera/postflight/colmap.py b/kamera/postflight/colmap.py index a6c13c2..c738571 100644 --- a/kamera/postflight/colmap.py +++ b/kamera/postflight/colmap.py @@ -80,6 +80,20 @@ def get_channel(self, fname: str | os.PathLike) -> str: channel = base.split("_")[3] return channel + def get_view(self, fname: str | os.PathLike) -> str: + """Extract view (e.g. left_view, right_view, center_view) from + a given kamera filename""" + base = osp.basename(fname) + channel = base.split("_")[3] + view = "null" + if channel == "C": + view = "center_view" + elif channel == "L": + view = "left_view" + elif channel == "R": + view = "right_view" + return view + def get_basename_to_time(self, flight_dir: str | os.PathLike) -> dict: # Establish correspondence between real-world exposure times base of file # names. @@ -282,71 +296,98 @@ def create_fname_to_time_channel_modality( def write_gifs( self, gif_dir: str | os.PathLike, - colmap_dir: str | os.PathLike, - rgb_str: str, - camera_str: str, - cm_rgb: StandardCamera, - cm_uv: StandardCamera, + camera_name: str, + colocated_modality: str, + camera_model: StandardCamera, + colocated_camera_model: StandardCamera, ) -> None: - print(f"Writing a registration gif for cameras {rgb_str} " f"and {camera_str}.") - # Pick an image pair and register. + channel, modality = camera_name.split("_")[2:] + colocated_camera_name = camera_name.replace(modality, colocated_modality) + print( + f"Writing registration gifs for cameras {camera_name} " + f"and {colocated_camera_name}." + ) ub.ensuredir(gif_dir) img_fnames = self.ccd.img_fnames - for k in range(10): + # write 5 image pairs for each + for k in range(5): inds = list(range(len(img_fnames))) np.random.shuffle(inds) for i in range(len(img_fnames)): - uv_img = rgb_img = None - fname1 = img_fnames[inds[i]] - if osp.basename(osp.dirname(fname1)) != rgb_str: + colocated_img = img = None + fname = img_fnames[inds[i]] + if osp.basename(osp.dirname(fname)) != camera_name: continue - t1 = self.ccd.basename_to_time[self.get_base_name(fname1)] - channel = self.get_channel(fname1) # L/C/R + view = self.get_view(fname) try: - rgb_fname = self.ccd.fname_to_time_channel_modality[t1][channel][ - "rgb" - ] - abs_rgb_fname = os.path.join(colmap_dir, "images0", rgb_fname) - rgb_img = cv2.imread(abs_rgb_fname, cv2.IMREAD_COLOR)[:, :, ::-1] + bname = osp.basename(fname) + abs_fname = osp.join(self.flight_dir, view, bname) + img = cv2.imread(abs_fname, cv2.IMREAD_COLOR)[:, :, ::-1] except Exception as e: - print(f"No rgb image found at time {t1}") + print(f"No {modality} image found at path {abs_fname}") continue try: - uv_fname = self.ccd.fname_to_time_channel_modality[t1][channel][ - "uv" + # get colocated image from the same time + abs_colocated_bname = pathlib.Path( + abs_fname.replace(modality, colocated_modality) + ) + abs_colocated_fname = None + if not abs_colocated_bname.is_file(): + # can't find file, check other extensions + for ext in [".jpg", ".jpeg", ".png", ".tiff"]: + if abs_colocated_bname.with_suffix(ext).is_file(): + abs_colocated_fname = str( + abs_colocated_bname.with_suffix(ext) + ) + break + else: + abs_colocated_fname = str(abs_colocated_bname) + colocated_bname = osp.basename(abs_colocated_fname) + colocated_img = cv2.imread(abs_colocated_fname, cv2.IMREAD_COLOR)[ + :, :, ::-1 ] - abs_uv_fname = os.path.join(colmap_dir, "images0", uv_fname) - uv_img = cv2.imread(abs_uv_fname, cv2.IMREAD_COLOR)[:, :, ::-1] + # Once we find a matching pair, break break except Exception as e: - print(f"No uv image found at time {t1}") + print( + f"No {colocated_modality} image found at filepath {abs_colocated_fname}" + ) continue - if uv_img is None or rgb_img is None: + if img is None or colocated_img is None: print("Failed to find matching image pair, skipping.") continue - print(f"Writing {rgb_fname} and {uv_fname} to gif.") + print(f"Writing {bname} and {colocated_bname} to gif.") - # Warps the color image img1 into the uv camera model cm_uv - warped_rgb_img, mask = render_view( - cm_rgb, rgb_img, 0, cm_uv, 0, block_size=10 - ) - - ds_warped_rgb_img = PIL.Image.fromarray( - cv2.pyrDown(cv2.pyrDown(cv2.pyrDown(warped_rgb_img))) - ) - ds_uv_img = PIL.Image.fromarray( - cv2.pyrDown(cv2.pyrDown(cv2.pyrDown(uv_img))) + # warps the given colocated image into the view of the original camera model + warped_colocated_img, mask = render_view( + colocated_camera_model, colocated_img, 0, camera_model, 0, block_size=10 ) fname_out = osp.join( - gif_dir, f"{rgb_str}_to_{camera_str}_registration_{k}.gif" + gif_dir, + f"{camera_name}_to_{colocated_camera_name}_registration_{k}.gif", ) print(f"Writing gif to {fname_out}.") - ds_uv_img.save( + # ds_warped_rgb_img = PIL.Image.fromarray( + # cv2.pyrDown(cv2.pyrDown(cv2.pyrDown(warped_rgb_img))) + # ) + # ds_uv_img = PIL.Image.fromarray( + # cv2.pyrDown(cv2.pyrDown(cv2.pyrDown(colocated_img))) + # ) + # Make sure gifs are reasonable size + w, h, _ = img.shape + ratio = w / h + new_w = 1280 + new_h = int(new_w * ratio) + pil_img = PIL.Image.fromarray(img).resize((new_w, new_h)) + pil_colocated_img = PIL.Image.fromarray(warped_colocated_img).resize( + (new_w, new_h) + ) + pil_img.save( fname_out, save_all=True, - append_images=[ds_warped_rgb_img], + append_images=[pil_colocated_img], duration=350, loop=0, ) diff --git a/kamera/postflight/scripts/calibration.py b/kamera/postflight/scripts/calibration.py index 1032f35..f682358 100644 --- a/kamera/postflight/scripts/calibration.py +++ b/kamera/postflight/scripts/calibration.py @@ -6,27 +6,11 @@ from kamera.postflight.colmap import ColmapCalibration, find_best_sparse_model -def main(): - # REQUIREMENTS: Must already have built a reasonable 3-D model using Colmap - # And have a flight directory populated by the kamera system - flight_dir = "/home/local/KHQ/adam.romlein/noaa/data/2024_AOC_AK_Calibration/fl09" - colmap_dir = os.path.join(flight_dir, "colmap") - # Location to save KAMERA camera models. - save_dir = os.path.join(flight_dir, "kamera_models") - # Location to find / build aligned model - align_dir = os.path.join(colmap_dir, "aligned") - # This assumes that 2 modalities of cameras are within the 3-D model - joint_calibration = True - # Can switch to UV / IR if possible that they are better aligned - main_modality = "rgb" - # If camera models are already present, if true this will overwrite - force_calibrate = False - # Whether to calibrate IR models or not. A "colmap_ir" must be built - # in the same folder - calibrate_ir = True - - # Step 1: Make sure the model is aligned to the INS readings, if not, - # find the best model and align it. +def align_model( + flight_dir: os.PathLike | str, + colmap_dir: os.PathLike | str, + align_dir: os.PathLike | str, +) -> ColmapCalibration: if os.path.exists(align_dir) and len(os.listdir(align_dir)) == 1: print( f"The directory {align_dir} exists and is not empty," @@ -53,6 +37,31 @@ def main(): ub.ensuredir(aligned_sparse_dir) cc = ColmapCalibration(flight_dir, best_reconstruction_dir) cc.align_model(aligned_sparse_dir) + return cc + + +def main(): + # REQUIREMENTS: Must already have built a reasonable 3-D model using Colmap + # And have a flight directory populated by the kamera system + flight_dir = "/home/local/KHQ/adam.romlein/noaa/data/2024_AOC_AK_Calibration/fl09" + colmap_dir = os.path.join(flight_dir, "colmap") + # Location to save KAMERA camera models. + save_dir = os.path.join(flight_dir, "kamera_models") + # Location to find / build aligned model + align_dir = os.path.join(colmap_dir, "aligned") + # This assumes that 2 modalities of cameras are within the 3-D model + joint_calibration = True + # Can switch to UV / IR if possible that they are better aligned + main_modality = "rgb" + # If camera models are already present, if true this will overwrite + force_calibrate = False + # Whether to calibrate IR models or not. A "colmap_ir" must be built + # in the same folder + calibrate_ir = True + + # Step 1: Make sure the model is aligned to the INS readings, if not, + # find the best model and align it. + cc = align_model(flight_dir, colmap_dir, align_dir) # We now have an aligned 3-D model, so we can calibrate the cameras print("Preparing calibration data...") @@ -101,41 +110,98 @@ def main(): # now calibrate all other modalities if modality == main_modality: continue - print(f"Calibrating camera {camera_str}.") - tic = time.perf_counter() - camera_model = cc.transfer_calibration( - camera_str, - cameras[channel][main_modality], - calibrated_modality=main_modality, - error_threshold=100, - ) - toc = time.perf_counter() - if camera_model is not None: - out_path = os.path.join(save_dir, f"{camera_str}_v2.yaml") - print(f"Saving camera model to {out_path}") - camera_model.save_to_file(out_path) + out_path = os.path.join(save_dir, f"{camera_str}_v2.yaml") + if os.path.exists(out_path) and not force_calibrate: print( - f"Time to transfer camera calibration to {camera_str} was {(toc - tic):.3f}s" + f"Camera model path {out_path} exists and force_calibrate is turned off, loading model." ) - print(camera_model) + camera_model = load_from_file(out_path) cameras[channel][modality] = camera_model else: - print(f"Transferring calibration to camera {camera_str} failed.") + print(f"Calibrating camera {camera_str}.") + tic = time.perf_counter() + camera_model = cc.transfer_calibration( + camera_str, + cameras[channel][main_modality], + calibrated_modality=main_modality, + error_threshold=100, + ) + toc = time.perf_counter() + if camera_model is not None: + print(f"Saving camera model to {out_path}") + camera_model.save_to_file(out_path) + print( + f"Time to transfer camera calibration to {camera_str} was {(toc - tic):.3f}s" + ) + print(camera_model) + cameras[channel][modality] = camera_model + else: + print(f"Transferring calibration to camera {camera_str} failed.") # IR calibration generally happens in a separate model, since SIFT has a hard # time matching between EO and long-wave IR if calibrate_ir: - colmap_dir = os.path.join(flight_dir, "colmap") + ir_colmap_dir = os.path.join(flight_dir, "colmap_ir") + ir_align_dir = os.path.join(ir_colmap_dir, "aligned") + ir_cc = align_model(flight_dir, ir_colmap_dir, ir_align_dir) + print("Preparing IR calibration data...") + ir_cc.prepare_calibration_data() + camera_strs = list(ir_cc.ccd.best_cameras.keys()) + for camera_str in ir_cc.ccd.best_cameras.keys(): + channel, modality = camera_str.split("_")[2:] + out_path = os.path.join(save_dir, f"{camera_str}_v2.yaml") + if os.path.exists(out_path) and not force_calibrate: + print( + f"Camera model path {out_path} exists and force_calibrate is turned off, loading model." + ) + camera_model = load_from_file(out_path) + cameras[channel][modality] = camera_model + else: + print(f"Calibrating camera {camera_str}.") + tic = time.perf_counter() + camera_model = ir_cc.calibrate_camera(camera_str, error_threshold=100) + toc = time.perf_counter() + if camera_model is not None: + print(f"Saving camera model to {out_path}") + camera_model.save_to_file(out_path) + print( + f"Time to calibrate camera {camera_str} was {(toc - tic):.3f}s" + ) + print(camera_model) + cameras[channel][modality] = camera_model + else: + print(f"Calibrating camera {camera_str} failed.") aircraft, angle = camera_str.split("_")[0:2] gif_dir = os.path.join(save_dir, "registration_gifs_v2") ub.ensuredir(gif_dir) + + # Write UV GIFs for channel in cameras.keys(): rgb_model = cameras[channel]["rgb"] uv_model = cameras[channel]["uv"] - rgb_name = "_".join([aircraft, angle, channel, "rgb"]) uv_name = "_".join([aircraft, angle, channel, "uv"]) - cc.write_gifs(gif_dir, colmap_dir, rgb_name, uv_name, rgb_model, uv_model) + cc.write_gifs( + gif_dir, + camera_name=uv_name, + colocated_modality="rgb", + camera_model=uv_model, + colocated_camera_model=rgb_model, + ) + + # Write IR GIFs + if calibrate_ir: + for channel in cameras.keys(): + rgb_model = cameras[channel]["rgb"] + ir_model = cameras[channel]["ir"] + ir_name = "_".join([aircraft, angle, channel, "ir"]) + ir_cc.write_gifs( + gif_dir, + camera_name=ir_name, + colocated_modality="rgb", + camera_model=ir_model, + colocated_camera_model=rgb_model, + ) if __name__ == "__main__": From 8ba6a5c54194d04290ec5323be71c9a458d6322f Mon Sep 17 00:00:00 2001 From: Adam Romlein Date: Fri, 21 Mar 2025 15:58:42 -0400 Subject: [PATCH 11/20] Add manual refinement if give point pairs. Add pretty print --- kamera/postflight/alignment.py | 95 +++++++++++++++++++++++- kamera/postflight/colmap.py | 36 +++++---- kamera/postflight/scripts/calibration.py | 77 ++++++++++++++++++- 3 files changed, 186 insertions(+), 22 deletions(-) diff --git a/kamera/postflight/alignment.py b/kamera/postflight/alignment.py index e4bc506..ea6eefb 100644 --- a/kamera/postflight/alignment.py +++ b/kamera/postflight/alignment.py @@ -1,5 +1,6 @@ import random import cv2 +import copy import numpy as np from dataclasses import dataclass from typing import List, NamedTuple, Optional, Tuple @@ -8,6 +9,7 @@ import pycolmap from kamera.colmap_processing.camera_models import StandardCamera from kamera.sensor_models.nav_state import NavStateINSJson, NavStateFixed +from rich import print @dataclass @@ -479,7 +481,7 @@ def iterative_alignment( points_per_image: List[List[VisiblePoint]], colmap_camera: pycolmap._core.Camera, nav_state_provider: NavStateINSJson, -) -> StandardCamera: +) -> tuple[StandardCamera, float]: # Both quaternions are of the form (x, y, z, w) and represent a coordinate # system rotation. cam_quats = [ @@ -619,7 +621,9 @@ def func(x): platform_pose_provider=nav_state_provider, ) - return camera_model + final_error = cam_quat_error(best_quat) + + return camera_model, final_error def transfer_alignment( @@ -627,7 +631,27 @@ def transfer_alignment( calibrated_camera_model: StandardCamera, points_per_image: List[List[VisiblePoint]], colocated_points_per_image: List[List[VisiblePoint]], -) -> StandardCamera: +) -> tuple[StandardCamera, float]: + """If you have a 3D colmap sparse model that was generated using multiple, + colocated modalities, you can generate the camera model for the higher-resolution + camera first, then bootstrap the calibration process for the lower-resolution + modalities by transferring initial the transformation to the INS that was + already found by unprojecting the matching 3D features. + + Args: + colmap_camera (pycolmap._core.Camera): The camera to calibrate. + calibrated_camera_model (StandardCamera): The colocated, already calibrated camera. + points_per_image (List[List[VisiblePoint]]): The 2D and 3D correspondences found + in each image in the camera to calibrate. + colocated_points_per_image (List[List[VisiblePoint]]): The 2D and 3D correspondences + found in each image in the colocated, calibrated camera. + + Raises: + SystemError: An unsupported camera model was found in the colmap model. + + Returns: + StandardCamera: The refined camera model. + """ im_pts = [] colocated_im_pts = [] skipped = 0 @@ -713,6 +737,7 @@ def transfer_alignment( flags = cv2.CALIB_ZERO_TANGENT_DIST flags = flags | cv2.CALIB_USE_INTRINSIC_GUESS flags = flags | cv2.CALIB_FIX_PRINCIPAL_POINT + # Optionally, fix the K intrinsics # flags = flags | cv2.CALIB_FIX_K1 # flags = flags | cv2.CALIB_FIX_K2 # flags = flags | cv2.CALIB_FIX_K3 @@ -888,7 +913,69 @@ def error(x): assert np.all(np.isfinite(x)), "Input quaternion for final model is not finite." cm = get_cm(x) - return cm + final_error = error(x) + return cm, final_error + + +def manual_alignment( + camera_model: StandardCamera, + reference_camera_model: StandardCamera, + image_point_pairs: dict, +) -> tuple[StandardCamera, float]: + pts = np.array(image_point_pairs["rightPoints"]).astype(np.float32) + reference_pts = np.array(image_point_pairs["leftPoints"]).astype(np.float32) + + def get_new_cm(x): + tmp_cm = copy.deepcopy(camera_model) + cam_quat = x[:4] + cam_quat /= np.linalg.norm(cam_quat) + tmp_cm.update_intrinsics(cam_quat=cam_quat) + + if len(x) > 4: + tmp_cm.fx = x[4] + + if len(x) > 5: + tmp_cm.fy = x[5] + + return tmp_cm + + def proj_err(x): + tmp_cm = get_new_cm(x) + + wrld_pts = reference_camera_model.unproject(reference_pts.T)[1] + im_pts = tmp_cm.project(wrld_pts) + + err = np.sqrt(np.sum(np.sum((pts.T - im_pts) ** 2, 1))) + err /= len(wrld_pts) + return err + + min_err = np.inf + best_x = None + iterations = 10000 + for _ in range(iterations): + x = np.random.rand(4) * 2 - 1 + x /= np.linalg.norm(x) + err = proj_err(x) + if err < min_err: + min_err = err + best_x = x + + x = np.hstack([best_x, camera_model.fx, camera_model.fy]) + + x = minimize(proj_err, x).x + x = minimize(proj_err, x, method="Powell").x + x = minimize(proj_err, x, method="BFGS").x + x = minimize(proj_err, x).x + + tmp_cm = get_new_cm(x) + + final_err = proj_err(x) + print( + "[bold green] Mean error after manual alignment[/bold green]:", + final_err, + "pixels", + ) + return tmp_cm, final_err if __name__ == "__main__": diff --git a/kamera/postflight/colmap.py b/kamera/postflight/colmap.py index c738571..32aa0f6 100644 --- a/kamera/postflight/colmap.py +++ b/kamera/postflight/colmap.py @@ -8,6 +8,7 @@ import ubelt as ub from posixpath import basename from re import I +from rich import print from shapely import points import pycolmap as pc @@ -19,6 +20,7 @@ from kamera.postflight.alignment import ( VisiblePoint, iterative_alignment, + manual_alignment, transfer_alignment, ) @@ -202,9 +204,7 @@ def prepare_calibration_data(self): self.ccd = ccd return ccd - def calibrate_camera( - self, camera_name: str, error_threshold: float - ) -> StandardCamera: + def calibrate_camera(self, camera_name: str) -> tuple[StandardCamera, float]: sfm_quats = np.array([pose[1] for pose in self.ccd.sfm_poses]) ins_quats = np.array([pose[1] for pose in self.ccd.ins_poses]) # Find all valid indices of current camera @@ -222,18 +222,17 @@ def calibrate_camera( if len(observations) < 10: print(f"Only {len(observations)} seen for camera {camera_name}, skipping.") cam = self.ccd.best_cameras[camera_name] - camera_model = iterative_alignment( + camera_model, error = iterative_alignment( cam_sfm_quats, cam_ins_quats, observations, cam, self.nav_state_provider ) - return camera_model + return camera_model, error def transfer_calibration( self, camera_name: str, calibrated_camera_model: StandardCamera, calibrated_modality: str, - error_threshold: float, - ) -> StandardCamera: + ) -> tuple[StandardCamera, float]: """ Use the quaternion already solved of a colocated, calibrated camera to bootstrap the calibration process. @@ -270,10 +269,22 @@ def transfer_calibration( return cam = self.ccd.best_cameras[camera_name] - camera_model = transfer_alignment( + camera_model, error = transfer_alignment( cam, calibrated_camera_model, observations, colocated_observations ) - return camera_model + return camera_model, error + + def manual_calibration( + self, + camera_model: StandardCamera, + reference_camera_model: StandardCamera, + point_pairs: dict, + ) -> tuple[StandardCamera, float]: + print("Refining camera model using manually defined point pairs.") + refined_model, error = manual_alignment( + camera_model, reference_camera_model, point_pairs + ) + return refined_model, error def create_fname_to_time_channel_modality( self, img_fnames, basename_to_time @@ -300,6 +311,7 @@ def write_gifs( colocated_modality: str, camera_model: StandardCamera, colocated_camera_model: StandardCamera, + num_gifs: int = 5, ) -> None: channel, modality = camera_name.split("_")[2:] colocated_camera_name = camera_name.replace(modality, colocated_modality) @@ -310,8 +322,7 @@ def write_gifs( ub.ensuredir(gif_dir) img_fnames = self.ccd.img_fnames - # write 5 image pairs for each - for k in range(5): + for k in range(num_gifs): inds = list(range(len(img_fnames))) np.random.shuffle(inds) for i in range(len(img_fnames)): @@ -461,9 +472,6 @@ def write_image_locations( pos = ins_poses[i][0] fo.write("%s %0.8f %0.8f %0.8f\n" % (name, pos[0], pos[1], pos[2])) - def calibrate_ir(self): - pass - def find_best_sparse_model(sparse_dir: str | os.PathLike): if os.listdir(sparse_dir) == 0: diff --git a/kamera/postflight/scripts/calibration.py b/kamera/postflight/scripts/calibration.py index f682358..5412384 100644 --- a/kamera/postflight/scripts/calibration.py +++ b/kamera/postflight/scripts/calibration.py @@ -1,6 +1,9 @@ import os import time +import json +import pathlib import ubelt as ub +from rich import print from kamera.colmap_processing.camera_models import load_from_file from kamera.postflight.colmap import ColmapCalibration, find_best_sparse_model @@ -58,9 +61,12 @@ def main(): # Whether to calibrate IR models or not. A "colmap_ir" must be built # in the same folder calibrate_ir = True + # open the point clicking UI to refine IR calibration? + refine_ir = True # Step 1: Make sure the model is aligned to the INS readings, if not, # find the best model and align it. + print("[blue] Loading 3D RGB/UV Model.[/blue]") cc = align_model(flight_dir, colmap_dir, align_dir) # We now have an aligned 3-D model, so we can calibrate the cameras @@ -68,8 +74,11 @@ def main(): cc.prepare_calibration_data() ub.ensuredir(save_dir) cameras = ub.AutoDict() + errors = ub.AutoDict() camera_strs = list(cc.ccd.best_cameras.keys()) modalities = [cs.split("_")[3] for cs in camera_strs] + num_cameras_loaded = 0 + num_cameras_calibrated = 0 if len(modalities) < 1: print( "Warning: only 1 modality found in this 3D model, not joinly calibrating." @@ -88,10 +97,11 @@ def main(): ) camera_model = load_from_file(out_path) cameras[channel][modality] = camera_model + num_cameras_loaded += 1 else: print(f"Calibrating camera {camera_str}.") tic = time.time() - camera_model = cc.calibrate_camera(camera_str, error_threshold=100) + camera_model, error = cc.calibrate_camera(camera_str) toc = time.time() if camera_model is not None: print(f"Saving camera model to {out_path}") @@ -99,8 +109,10 @@ def main(): print(f"Time to calibrate camera {camera_str} was {(toc - tic):.3f}s") print(camera_model) cameras[channel][modality] = camera_model + errors[channel][modality] = error else: print(f"Calibrating camera {camera_str} failed.") + num_cameras_calibrated += 1 # If we have multiple cameras within one model, we can utilize the fact that these cameras # are colocated to use 3D points obtained from one to project into the other @@ -117,14 +129,14 @@ def main(): ) camera_model = load_from_file(out_path) cameras[channel][modality] = camera_model + num_cameras_loaded += 1 else: print(f"Calibrating camera {camera_str}.") tic = time.perf_counter() - camera_model = cc.transfer_calibration( + camera_model, error = cc.transfer_calibration( camera_str, cameras[channel][main_modality], calibrated_modality=main_modality, - error_threshold=100, ) toc = time.perf_counter() if camera_model is not None: @@ -135,6 +147,8 @@ def main(): ) print(camera_model) cameras[channel][modality] = camera_model + errors[channel][modality] = error + num_cameras_calibrated += 1 else: print(f"Transferring calibration to camera {camera_str} failed.") @@ -143,6 +157,7 @@ def main(): if calibrate_ir: ir_colmap_dir = os.path.join(flight_dir, "colmap_ir") ir_align_dir = os.path.join(ir_colmap_dir, "aligned") + print("[blue] Loading 3D IR Model.[/blue]") ir_cc = align_model(flight_dir, ir_colmap_dir, ir_align_dir) print("Preparing IR calibration data...") ir_cc.prepare_calibration_data() @@ -156,10 +171,13 @@ def main(): ) camera_model = load_from_file(out_path) cameras[channel][modality] = camera_model + num_cameras_loaded += 1 else: print(f"Calibrating camera {camera_str}.") tic = time.perf_counter() - camera_model = ir_cc.calibrate_camera(camera_str, error_threshold=100) + camera_model, error = ir_cc.calibrate_camera( + camera_str, error_threshold=100 + ) toc = time.perf_counter() if camera_model is not None: print(f"Saving camera model to {out_path}") @@ -169,9 +187,50 @@ def main(): ) print(camera_model) cameras[channel][modality] = camera_model + errors[channel][modality] = error + num_cameras_calibrated += 1 else: print(f"Calibrating camera {camera_str} failed.") + ir_cameras_refined = 0 + if refine_ir: + # need to define a points per modality/view pair + ir_points_json = pathlib.Path( + os.path.join( + flight_dir, + "manual_keypoints", + f"{channel}_ir_to_rgb_points.json", + ) + ) + if not ir_points_json.is_file(): + # check to see if there are numpy points saved + ir_points_txt = ir_points_json.with_suffix(".txt") + if ir_points_txt.is_file(): + with ir_points_txt.open() as f: + fpoints = f.readlines() + points = {"rightPoints": [], "leftPoints": []} + for line in fpoints: + vals = list(map(float, line.split(" "))) + points["rightPoints"].append(vals[:2]) + points["leftPoints"].append(vals[2:4]) + else: + print( + "[yellow]" + f"No matching points file was found! Please place your points file" + f" in [bold]{ir_points_txt}[/bold] if in text format, or [bold]{ir_points_json}[/bold] if in json format." + "[yellow]" + ) + continue + else: + with open(ir_points_json, "r") as f: + points = json.load(f) + refined_camera_model, error = ir_cc.manual_calibration( + camera_model, cameras[channel][main_modality], points + ) + cameras[channel][modality] = refined_camera_model + errors[channel][modality] = error + ir_cameras_refined += 1 + aircraft, angle = camera_str.split("_")[0:2] gif_dir = os.path.join(save_dir, "registration_gifs_v2") ub.ensuredir(gif_dir) @@ -187,6 +246,7 @@ def main(): colocated_modality="rgb", camera_model=uv_model, colocated_camera_model=rgb_model, + num_gifs=5, ) # Write IR GIFs @@ -201,8 +261,17 @@ def main(): colocated_modality="rgb", camera_model=ir_model, colocated_camera_model=rgb_model, + num_gifs=5, ) + print("=" * 80) + print("[bold] Quick Summary: ") + print(f"Number of cameras calibrated: {num_cameras_calibrated}.") + print(f"Number of cameras loaded from disk: {num_cameras_loaded}.") + print(f"Number of IR cameras refined {ir_cameras_refined}.") + print("Errors: ") + print(errors) + if __name__ == "__main__": main() From ac7f738a370e3b04a278f57709fb61cf30ac5911 Mon Sep 17 00:00:00 2001 From: Adam Romlein Date: Fri, 21 Mar 2025 15:59:45 -0400 Subject: [PATCH 12/20] Update points UI --- kamera/keypoint_server/__init__.py | 0 kamera/keypoint_server/app.py | 103 ++++++++ kamera/keypoint_server/keypoint.tpl | 365 ++++++++++++++++++++++++++++ kamera/keypoint_server/trame_app.py | 32 +++ 4 files changed, 500 insertions(+) create mode 100644 kamera/keypoint_server/__init__.py create mode 100644 kamera/keypoint_server/app.py create mode 100644 kamera/keypoint_server/keypoint.tpl create mode 100644 kamera/keypoint_server/trame_app.py diff --git a/kamera/keypoint_server/__init__.py b/kamera/keypoint_server/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/kamera/keypoint_server/app.py b/kamera/keypoint_server/app.py new file mode 100644 index 0000000..c088b2e --- /dev/null +++ b/kamera/keypoint_server/app.py @@ -0,0 +1,103 @@ +import json +import os +import argparse +from bottle import route, template, run, static_file, request, BaseRequest + +BaseRequest.MEMFILE_MAX = 6 * 2048 * 2048 + +image_dir = "" +left_img_file = "./kamera_calibration_fl09_C_20240612_204041.621432_rgb.jpg" +right_img_file = "./kamera_calibration_fl09_C_20240612_204041.621432_ir.png" + + +@route("/") +def index(): + return template("keypoint.tpl") + + +@route("/image-dir", method="POST") +def set_image_dir(): + global image_dir + + json = request.json + image_dir = json["image-dir"] + print(f"Set img dir to '{image_dir}'") + + +@route("/right-img-file", method="POST") +def set_right_img_file(): + global right_img_file + json = request.json + right_img_file = json["right-img-file"] + print(f"Set right img file to '{right_img_file}'") + + +@route("/left-img-file", method="POST") +def set_left_img_file(): + global left_img_file + json = request.json + left_img_file = json["left-img-file"] + print(f"Set left img file to '{left_img_file}'") + + +@route("/image/left") +def left_image(): + resp = static_file(left_img_file, root=image_dir) + resp.set_header("Cache-Control", "no-store") + return resp + + +@route("/image/right") +def right_image(): + resp = static_file(right_img_file, root=image_dir) + resp.set_header("Cache-Control", "no-store") + return resp + + +@route("/image/") +def image(fn): + return static_file(fn, root=image_dir) + + +@route("/points", method="POST") +def to_points(): + global points + json = request.json + points = [] + for z in zip(json["leftPoints"], json["rightPoints"]): + points.append(z[0] + z[1]) + + +@route("/save_points", method="POST") +def save_points(): + global points + data = request.json + with open("points.json", "w") as f: + json.dump(data, f) + + +@route("/points", method="GET") +def get_points(): + return {"points": points} + + +def run_keypoint_server( + host: str, + port: int, + image_root: str | os.PathLike, + left_img_fname: str | os.PathLike, + right_img_fname: str | os.PathLike, +) -> None: + global left_img_file, right_img_file, image_dir + left_img_file = left_img_fname + right_img_file = right_img_fname + image_dir = image_root + run(host=host, port=port) + + +if __name__ == "__main__": + parser = argparse.ArgumentParser() + parser.add_argument("--port", default=8080) + parser.add_argument("--host", default="localhost") + args = parser.parse_args() + run(host=args.host, port=args.port) diff --git a/kamera/keypoint_server/keypoint.tpl b/kamera/keypoint_server/keypoint.tpl new file mode 100644 index 0000000..03f3910 --- /dev/null +++ b/kamera/keypoint_server/keypoint.tpl @@ -0,0 +1,365 @@ + + + +
+ +
+ + + diff --git a/kamera/keypoint_server/trame_app.py b/kamera/keypoint_server/trame_app.py new file mode 100644 index 0000000..e465c8e --- /dev/null +++ b/kamera/keypoint_server/trame_app.py @@ -0,0 +1,32 @@ +import threading +from trame.app import get_server +from trame.ui.vuetify3 import VAppLayout +import trame.widgets.vuetify3 as v3 +from trame.widgets import iframe + +from kamera.keypoint_server.app import * # noqa + + +server = get_server(client_type="vue3") +state, ctrl = server.state, server.controller + + +with VAppLayout(server): + with v3.VContainer( + classes="pa-0 fill-height", + fluid=True, + ): + with v3.VContainer(classes="fill-height", fluid=True): + iframe.IFrame( + classes="fill-height", + style="width: 100%", + fluid=True, + src="http://localhost:8090/", + ) + +if __name__ == "__main__": + host = "localhost" + port = 8090 + t = threading.Thread(target=run_keypoint_server, args=(host, port, "", "", "")) + t.start() + server.start() From b88d0a1587fcb58c029a0e06c46a1eedfcffe05a Mon Sep 17 00:00:00 2001 From: Adam Romlein Date: Fri, 21 Mar 2025 16:00:00 -0400 Subject: [PATCH 13/20] Move UI --- .../keypoint_server/key_point_server.py | 81 ---- .../scripts/keypoint_server/keypoint.tpl | 357 ------------------ 2 files changed, 438 deletions(-) delete mode 100644 kamera/postflight/scripts/keypoint_server/key_point_server.py delete mode 100644 kamera/postflight/scripts/keypoint_server/keypoint.tpl diff --git a/kamera/postflight/scripts/keypoint_server/key_point_server.py b/kamera/postflight/scripts/keypoint_server/key_point_server.py deleted file mode 100644 index 014512e..0000000 --- a/kamera/postflight/scripts/keypoint_server/key_point_server.py +++ /dev/null @@ -1,81 +0,0 @@ -from bottle import route, template, run, static_file, request, BaseRequest -import os -import argparse - -BaseRequest.MEMFILE_MAX = 6 * 1024 * 1024 - -image_dir = "" -right_img_file = "kamera_calibration_fl09_L_20240612_204629.686820_ir.png" -left_img_file = "kamera_calibration_fl09_L_20240612_204629.686820_rgb.jpg" - - -@route("/") -def index(): - return template("keypoint.tpl") - - -@route("/image-dir", method="POST") -def set_image_dir(): - global image_dir - - json = request.json - image_dir = json["image-dir"] - print(f"Set img dir to '{image_dir}'") - - -@route("/right-img-file", method="POST") -def set_right_img_file(): - global right_img_file - json = request.json - right_img_file = json["right-img-file"] - print(f"Set right img file to '{right_img_file}'") - - -@route("/left-img-file", method="POST") -def set_left_img_file(): - global left_img_file - json = request.json - left_img_file = json["left-img-file"] - print(f"Set left img file to '{left_img_file}'") - - -@route("/image/left") -def left_image(): - resp = static_file(left_img_file, root=image_dir) - resp.set_header("Cache-Control", "no-store") - return resp - - -@route("/image/right") -def right_image(): - resp = static_file(right_img_file, root=image_dir) - resp.set_header("Cache-Control", "no-store") - return resp - - -@route("/image/") -def image(fn): - return static_file(fn, root=dirname) - - -@route("/points", method="POST") -def points(): - global points - json = request.json - points = [] - for z in zip(json["leftPoints"], json["rightPoints"]): - points.append(z[0] + z[1]) - - -@route("/points", method="GET") -def get_points(): - return {"points": points} - - -if __name__ == "__main__": - dirname = os.path.abspath(os.path.dirname(__file__)) - parser = argparse.ArgumentParser() - parser.add_argument("--port", default=8080) - parser.add_argument("--host", default="localhost") - args = parser.parse_args() - run(host=args.host, port=args.port) diff --git a/kamera/postflight/scripts/keypoint_server/keypoint.tpl b/kamera/postflight/scripts/keypoint_server/keypoint.tpl deleted file mode 100644 index 8d679dd..0000000 --- a/kamera/postflight/scripts/keypoint_server/keypoint.tpl +++ /dev/null @@ -1,357 +0,0 @@ - - - -
- -
- - - From 240374b69bf003559d15299f1cdccc052b865d8a Mon Sep 17 00:00:00 2001 From: Adam Romlein Date: Fri, 21 Mar 2025 16:14:53 -0400 Subject: [PATCH 14/20] Remove unnecessary files --- .../scripts/calibrate_from_colmap.py | 274 ---- .../scripts/calibrate_ir_from_rgb.py | 201 --- .../postflight/scripts/camera_calibration.py | 1213 ----------------- 3 files changed, 1688 deletions(-) delete mode 100644 kamera/postflight/scripts/calibrate_from_colmap.py delete mode 100644 kamera/postflight/scripts/calibrate_ir_from_rgb.py delete mode 100644 kamera/postflight/scripts/camera_calibration.py diff --git a/kamera/postflight/scripts/calibrate_from_colmap.py b/kamera/postflight/scripts/calibrate_from_colmap.py deleted file mode 100644 index 5d3c4cc..0000000 --- a/kamera/postflight/scripts/calibrate_from_colmap.py +++ /dev/null @@ -1,274 +0,0 @@ -#!/usr/bin/env python -""" -ckwg +31 -Copyright 2019 by Kitware, Inc. -All rights reserved. - -Redistribution and use in source and binary forms, with or without -modification, are permitted provided that the following conditions are met: - - * Redistributions of source code must retain the above copyright notice, - this list of conditions and the following disclaimer. - - * Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation - and/or other materials provided with the distribution. - - * Neither name of Kitware, Inc. nor the names of any contributors may be used - to endorse or promote products derived from this software without specific - prior written permission. - -THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS ``AS IS'' -AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHORS OR CONTRIBUTORS BE LIABLE FOR -ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL -DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR -SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER -CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, -OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE -OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - -============================================================================== - -Library handling projection operations of a standard camera model. - -Note: the image coordiante system has its origin at the center of the top left -pixel. - -""" -from __future__ import division, print_function -import numpy as np -from numpy import pi -import matplotlib.pyplot as plt -from mpl_toolkits.mplot3d import Axes3D -import cv2 -import time -import os -import glob -import matplotlib.pyplot as plt -import bisect -import json -from scipy.optimize import minimize - -# Custom package imports. -from sensor_models import ( - quaternion_multiply, - quaternion_from_matrix, - quaternion_from_euler, - quaternion_slerp, - quaternion_inverse, - quaternion_matrix - ) -from colmap_processing.camera_models import load_from_file, StandardCamera -from sensor_models.nav_state import NavStateINSBinary, NavStateINSJson - - -class ColmapImage(object): - def __init__(self, image_id, qw, qx, qy, qz, tx, ty, tz, cam_id, name, - pts): - self.image_id = image_id - self.qw = qw - self.qx = qx - self.qy = qy - self.qz = qz - self.tx = tx - self.ty = ty - self.tz = tz - self.cam_id = cam_id - self.name = name - self.pts = pts - - def get_camera_pose(self): - R = quaternion_matrix([self.qx,self.qy,self.qz,self.qw])[:3,:3] - return np.hstack([R,np.array([[self.tx,self.ty,self.tz]]).T]) - - def pos(self): - return np.dot(R.T,-t) - - -# Colmap text camera model directory. -flight_dir = '00' -colmap_dir = '00/colmap' -camera_model_dir = '/root/kamera/src/cfg/camera_models' - -# Read in the nav binary. -#nav_state_provider = NavStateINSBinary(nav_binary_fname) - -# Recover the mapping between filename and high-precision time. -image_globs = ['%s/CENT/*rgb.tif' % flight_dir, - '%s/LEFT/*rgb.tif' % flight_dir, - '%s/RIGHT/*rgb.tif' % flight_dir] -camera_model_fnames = ['%s/left_sys/rgb.yaml' % camera_model_dir, - '%s/center_sys/rgb.yaml' % camera_model_dir, - '%s/right_sys/rgb.yaml' % camera_model_dir] - -img_fnames = {} -fname_to_time = {} -camera_models = [] -for i in range(3): - image_glob = image_globs[i] - nav_dir = os.path.split(image_glob)[0] - nav_state_provider = NavStateINSJson('%s/*meta.json' % nav_dir) - - for img_fname in glob.glob(image_glob): - json_fname = img_fname - json_fname = json_fname.replace('rgb.tif', 'meta.json') - json_fname = json_fname.replace('ir.tif', 'meta.json') - json_fname = json_fname.replace('uv.tif', 'meta.json') - - try: - with open(json_fname) as json_file: - d = json.load(json_file) - - # Time that the image was taken. - img_fnames[d['evt']['time']] = img_fname - fname = os.path.splitext(os.path.split(img_fname)[1])[0] - fname_to_time[fname] = d['evt']['time'] - except OSError: - pass - - lat0 = nav_state_provider.lat0 - lon0 = nav_state_provider.lon0 - h0 = nav_state_provider.h0 - - camera_models.append(load_from_file(camera_model_fnames[i], - nav_state_provider)) - - - -if False: - camera_model_fnames = '%s/cameras.txt' % colmap_dir - camera_models = [] - with open(camera_model_fnames, 'r') as infile: - for line in infile: - if not line.startswith('#'): - p = np.array(line.split('\n')[0].split(' ')[2:], np.float) - width, height, fx, fy, cx, cy, k1, k2, k3, k4 = p - K = np.array([[fx,0,cx],[0,fy,cy],[0,0,1]]) - image_topic = None - camera_models.append(StandardCamera(width, height, K, - (k1,k2,k3,k4), (0,0,0), - (1,0,0,0), image_topic, - frame_id=None, - nav_state_provider=nav_state_provider)) - - -image_fname = '%s/output/images.txt' % colmap_dir -colmap_images = [] -with open(image_fname, 'r') as infile: - while True: - line = infile.readline() - if line == '': - break - - if not line.startswith('#'): - # IMAGE_ID, QW, QX, QY, QZ, TX, TY, TZ, CAMERA_ID, NAME - # POINTS2D[] as (X, Y, POINT3D_ID) - p = line.split('\n')[0].split(' ') - image_id, qw, qx, qy, qz, tx, ty, tz, cam_id, name = p - qw, qx, qy, qz, tx, ty, tz = [float(_) for _ in (qw, qx, qy, qz, tx, ty, tz)] - cam_id = int(cam_id) - - line = infile.readline() - p = line.split('\n')[0].split(' ') - pts = np.reshape(np.array([float(_) for _ in p]), (-1,3)) - - colmap_image = ColmapImage(image_id, qw, qx, qy, qz, tx, ty, tz, - cam_id, name, pts) - colmap_images.append(colmap_image) - - -points_fname = '%s/points3D.txt' % colmap_dir -points = [] -with open(points_fname, 'r') as infile: - for line in infile: - pass - - -nav_times = nav_state_provider.pose_time_series[:,0] - - -camera_model = camera_models[0] - - -def err_fun(cam_quat): - #cam_quat = np.hstack([0.5, cam_quat]) - cam_quat /= np.linalg.norm(cam_quat) - camera_model.update_intrinsics(cam_quat=cam_quat) - theta = 0 - for i in range(len(colmap_images)): - colmap_image = colmap_images[i] - fname = os.path.splitext(os.path.split(colmap_image.name)[1])[0] - t = fname_to_time[fname] - P1 = camera_models[0].get_camera_pose(t) - P2 = colmap_image.get_camera_pose() - R1 = np.identity(4); R1[:3,:3] = P1[:,:3] - R2 = np.identity(4); R2[:3,:3] = P2[:,:3] - q1 = quaternion_from_matrix(R1) - q2 = quaternion_from_matrix(R2) - dq = quaternion_multiply(q1, quaternion_inverse(q2)) - theta += 2*np.arccos(max([min([dq[3],1]),-1])) - - theta /= len(colmap_images) - print(cam_quat, theta) - return theta - -if False: - min_err = np.inf - for _ in range(10000): - cam_quat = random_quaternion() - err = err_fun(cam_quat) - if err < min_err: - min_err = err - best_cam_quat = cam_quat - else: - cam_quat = camera_model.cam_quat - -x = minimize(err_fun, cam_quat, tol=1-9).x - - -plt.plot(nav_state_provider.pose_time_series[:,3]) - -# ---------------------------------------------------------------------------- -fig = plt.figure() -ax = fig.add_subplot(111, projection='3d') -r = 5 -times = nav_times -times = [image_times[_.name] for _ in colmap_images] -times = np.sort(times) -pos = np.array([nav_state_provider.pose(t)[0] for t in times]).T - -plt.plot(pos[0], pos[1], pos[2], 'k-') -plt.plot(pos[0], pos[1], pos[2], 'ro') - -for t in times: - pos,quat = nav_state_provider.pose(t) - R = quaternion_matrix(quaternion_inverse(quat))[:3,:3] - - s = ['r-','g-','b-'] - for i in range(3): - plt.plot([pos[0],pos[0]+R[i][0]*r], [pos[1],pos[1]+R[i][1]*r], - [pos[2],pos[2]+R[i][2]*r], s[i], linewidth=3) - -plt.xlabel('Easting') -plt.ylabel('Northing') - - -fig = plt.figure() -ax = fig.add_subplot(111, projection='3d') -r = 5 -for i in range(len(colmap_images)): - colmap_image = colmap_images[i] - P = colmap_image.get_camera_pose() - R = np.identity(4); R[:3,:3] = P[:,:3] - pos = colmap_image.pos() - plt.plot([pos[0]], [pos[1]], [pos[2]], 'ro') - - s = ['r-','g-','b-'] - for i in range(3): - plt.plot([pos[0],pos[0]+R[i][0]*r], [pos[1],pos[1]+R[i][1]*r], - [pos[2],pos[2]+R[i][2]*r], s[i], linewidth=3) - -plt.xlabel('Easting') -plt.ylabel('Northing') diff --git a/kamera/postflight/scripts/calibrate_ir_from_rgb.py b/kamera/postflight/scripts/calibrate_ir_from_rgb.py deleted file mode 100644 index f3292f5..0000000 --- a/kamera/postflight/scripts/calibrate_ir_from_rgb.py +++ /dev/null @@ -1,201 +0,0 @@ -#!/usr/bin/env python -""" -ckwg +31 -Copyright 2019 by Kitware, Inc. -All rights reserved. - -Redistribution and use in source and binary forms, with or without -modification, are permitted provided that the following conditions are met: - - * Redistributions of source code must retain the above copyright notice, - this list of conditions and the following disclaimer. - - * Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation - and/or other materials provided with the distribution. - - * Neither name of Kitware, Inc. nor the names of any contributors may be used - to endorse or promote products derived from this software without specific - prior written permission. - -THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS ``AS IS'' -AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHORS OR CONTRIBUTORS BE LIABLE FOR -ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL -DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR -SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER -CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, -OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE -OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - -============================================================================== - -Library handling projection operations of a standard camera model. - -""" -from __future__ import division, print_function -import copy -import cv2 -import time -import os -import glob -import random -import json -import PIL -import numpy as np -import matplotlib.pyplot as plt -from numpy import pi -from mpl_toolkits.mplot3d import Axes3D -from scipy.optimize import minimize - -# Custom package imports. -from sensor_models import ( - quaternion_multiply, - quaternion_from_matrix, - quaternion_from_euler, - quaternion_slerp, - quaternion_inverse, - quaternion_matrix - ) -from colmap_processing.camera_models import load_from_file, StandardCamera -from colmap_processing.image_renderer import render_view - - -def calibrate_ir(rgb_camera_model_fname, ir_camera_model_fname, - image_point_pairs_fname): - image_pts = np.loadtxt(image_point_pairs_fname) - - rgb_camera = load_from_file(rgb_camera_model_fname) - ir_camera = load_from_file(ir_camera_model_fname) - - def get_new_cm(x): - tmp_cm = copy.deepcopy(ir_camera) - cam_quat = x[:4] - cam_quat /= np.linalg.norm(cam_quat) - tmp_cm.update_intrinsics(cam_quat=cam_quat) - - if len(x) > 4: - tmp_cm.fx = x[4] - - if len(x) > 5: - tmp_cm.fy = x[5] - - return tmp_cm - - def proj_err(x): - tmp_cm = get_new_cm(x) - - wrld_pts = rgb_camera.unproject(image_pts[:, 2:].T)[1] - im_pts = tmp_cm.project(wrld_pts) - - err = np.sqrt(np.sum(np.sum((image_pts[:, :2].T - im_pts)**2, 1))) - err /= len(wrld_pts) - print(err, x) - return err - - min_err = np.inf - best_x = None - for _ in range(10000): - x = np.random.rand(4)*2-1 - x /= np.linalg.norm(x) - err = proj_err(x) - if err < min_err: - min_err = err - best_x = x - - if True: - x = np.hstack([best_x, ir_camera.fx, ir_camera.fy]) - else: - x = best_x - - x = minimize(proj_err, x).x - x = minimize(proj_err, x, method='Powell').x - x = minimize(proj_err, x, method='BFGS').x - x = minimize(proj_err, x).x - - tmp_cm = get_new_cm(x) - - print('Final mean error:', proj_err(x), 'pixels') - tmp_cm.image_topic = '' - tmp_cm.frame_id = '' - tmp_cm.save_to_file(ir_camera_model_fname) - print('Saved updated camera model to', ir_camera_model_fname) - - -# Process three RGB cameras. -rgb_camera_model_fname = '' -ir_camera_model_fname = '' -image_point_pairs_fname = '' -calibrate_ir(rgb_camera_model_fname, ir_camera_model_fname, - image_point_pairs_fname) -# ---------------------------------- IR Gifs --------------------------------- - -# Location to save KAMERA camera models. -rgb_img_dir = '' -ir_img_dir = '' - -base_dir, base = os.path.split(ir_camera_model_fname) -out_dir = '%s/registration_gifs/%s' % (base_dir, os.path.splitext(base)[0]) -num_gifs = 50 - -try: - os.makedirs(out_dir) -except (IOError, OSError): - pass - - -def stretch_contrast(img, clip_limit=3, stretch_percentiles=[0.1, 99.9]): - img = img.astype(np.float32) - img -= np.percentile(img.ravel(), stretch_percentiles[0]) - img[img < 0] = 0 - img /= np.percentile(img.ravel(), stretch_percentiles[1])/255 - img[img > 255] = 255 - img = np.round(img).astype(np.uint8) - - hls = cv2.cvtColor(img, cv2.COLOR_RGB2HLS) - - clahe = cv2.createCLAHE(clipLimit=clip_limit, tileGridSize=(16, 16)) - hls[:, :, 1] = clahe.apply(hls[:, :, 1]) - - img = cv2.cvtColor(hls, cv2.COLOR_HLS2RGB) - return img - -cm_rgb = load_from_file(rgb_camera_model_fname) -cm_ir = load_from_file(ir_camera_model_fname) - -rgb_fnames = glob.glob('%s/*.jpg' % rgb_img_dir) -random.shuffle(rgb_fnames) -k = 0 - - -for rgb_fname in rgb_fnames[:num_gifs]: - if k == num_gifs: - break - - ir_fname = '%s/%sir.tif' % (ir_img_dir, os.path.split(rgb_fname[:-7])[1]) - img2 = cv2.imread(ir_fname, cv2.IMREAD_COLOR) - - if img2 is None: - continue - - img1 = cv2.imread(rgb_fname, cv2.IMREAD_COLOR) - - if img1 is None: - continue - - k += 1 - - img1 = img1[:, :, ::-1] - img2 = img2[:, :, ::-1] - - img1 = stretch_contrast(img1, clip_limit=3, stretch_percentiles=[0.1, 99.9]) - img2 = stretch_contrast(img2, clip_limit=3, stretch_percentiles=[0.1, 99.9]) - - img3, mask = render_view(cm_rgb, img1, 0, cm_ir, 0, block_size=10) - - img2_ = PIL.Image.fromarray(img2) - img3_ = PIL.Image.fromarray(img3) - fname_out = '%s/registration_%i.gif' % (out_dir, k+1) - img2_.save(fname_out, save_all=True, append_images=[img3_], - duration=250, loop=0) diff --git a/kamera/postflight/scripts/camera_calibration.py b/kamera/postflight/scripts/camera_calibration.py deleted file mode 100644 index 8917548..0000000 --- a/kamera/postflight/scripts/camera_calibration.py +++ /dev/null @@ -1,1213 +0,0 @@ -#!/usr/bin/env python -import os -import os.path as osp -import json -import cv2 -import PIL -import pathlib -import numpy as np -import matplotlib.pyplot as plt -import ubelt as ub -from random import shuffle -from scipy.optimize import minimize, fminbound -from matplotlib.backends.backend_pdf import PdfPages - -# Custom package imports. -from kamera.sensor_models import ( - quaternion_multiply, - quaternion_from_matrix, - quaternion_inverse, - ) -from kamera.sensor_models.nav_conversions import enu_to_llh -from kamera.sensor_models.nav_state import NavStateINSJson, NavStateFixed -from kamera.colmap_processing.camera_models import StandardCamera -from kamera.colmap_processing.colmap_interface import ( - read_images_binary, - read_points3D_binary, - read_cameras_binary, - qvec2rotmat, - ) -from kamera.colmap_processing.image_renderer import render_view - - -def get_base_name(fname): - """ Given an arbitrary filename (could be UV, IR, RGB, json), - extract the portion of the filename that is just the time, flight, - machine (C, L, R), and effort name. - """ - # get base - base = osp.basename(fname) - # get it without an extension and modality - modality_agnostic = "_".join(base.split("_")[:-1]) - return modality_agnostic - - -def get_modality(fname): - base = osp.basename(fname) - modality = base.split("_")[-1].split('.')[0] - return modality - - -def get_channel(fname): - base = osp.basename(fname) - channel = base.split("_")[3] - return channel - - -def get_basename_to_time(flight_dir) -> dict: - # Establish correspondence between real-world exposure times base of file - # names. - basename_to_time = {} - for json_fname in pathlib.Path(flight_dir).rglob('*_meta.json'): - try: - with open(json_fname) as json_file: - d = json.load(json_file) - # Time that the image was taken. - basename = get_base_name(json_fname) - basename_to_time[basename] = float(d['evt']['time']) - except (OSError, IOError): - pass - return basename_to_time - - -def process_images(colmap_images, basename_to_time, nav_state_provider): - """ - - Returns: - :param img_fnames: Image filename associated with each of the images in - 'colmap_images'. - :type img_fnames: list of str - - :param img_times: INS-reported time associated with the trigger of each - image in 'colmap_images'. - :type img_times: - - :param ins_poses: INS-reported pose, (x, y, z) position and (x, y, z, w) - quaternion, associated with the trigger of time of each image in - 'colmap_images'. - :type ins_poses: - - :param sfm_poses: Colmap-reported reported pose, (x, y, z) position and - (x, y, z, w) quaternion, associated with the trigger time of each image - in 'colmap_images'. - :type sfm_poses: - - """ - img_fnames = [] - img_times = [] - ins_poses = [] - sfm_poses = [] - llhs = [] - for image_num in colmap_images: - image = colmap_images[image_num] - base_name = get_base_name(image.name) - try: - t = basename_to_time[base_name] - - # Query the navigation state recorded by the INS for this time. - pose = nav_state_provider.pose(t) - llh = nav_state_provider.llh(t) - - # Query Colmaps pose for the camera. - R = qvec2rotmat(image.qvec) - pos = -np.dot(R.T, image.tvec) - - # The qvec used by Colmap is a (w, x, y, z) quaternion - # representing the rotation of a vector defined in the world - # coordinate system into the camera coordinate system. However, - # the 'camera_models' module assumes (x, y, z, w) quaternions - # representing a coordinate system rotation. Also, the quaternion - # used by 'camera_models' represents a coordinate system rotation - # versus the coordinate system transform of Colmap's convention, - # so we need an inverse. - - #quat = transformations.quaternion_inverse(image.qvec) - quat = image.qvec / np.linalg.norm(image.qvec) - quat[0] = -quat[0] - - quat = [quat[1], quat[2], quat[3], quat[0]] - - sfm_pose = [pos, quat] - - img_times.append(t) - ins_poses.append(pose) - img_fnames.append(image.name) - sfm_poses.append(sfm_pose) - llhs.append(llh) - except KeyError: - print('Couldn\'t find a _meta.json file associated with \'%s\'' % - base_name) - - ind = np.argsort(img_fnames) - img_fnames = [img_fnames[i] for i in ind] - img_times = [img_times[i] for i in ind] - ins_poses = [ins_poses[i] for i in ind] - sfm_poses = [sfm_poses[i] for i in ind] - llhs = [llhs[i] for i in ind] - - return img_fnames, img_times, ins_poses, sfm_poses, llhs - - -def write_image_locations(locations_fname, img_fnames, ins_poses): - with open(locations_fname, 'w') as fo: - for i in range(len(img_fnames)): - name = img_fnames[i] - pos = ins_poses[i][0] - fo.write('%s %0.8f %0.8f %0.8f\n' % (name, pos[0], pos[1], pos[2])) - - -def get_colmap_data(colmap_images, colmap_cameras, - points3d, basename_to_time) -> tuple: - # Load in all of the Colmap results into more-convenient structures. - points_per_image = {} - camera_from_camera_str = {} - for image_num in colmap_images: - image = colmap_images[image_num] - camera_str = osp.basename(osp.dirname(image.name)) - camera_from_camera_str[camera_str] = colmap_cameras[image.camera_id] - - xys = image.xys - pt_ids = image.point3D_ids - ind = pt_ids != -1 - pt_ids = pt_ids[ind] - xys = xys[ind] - xyzs = np.array([points3d[pt_id].xyz for pt_id in pt_ids]) - base_name = get_base_name(image.name) - try: - t = basename_to_time[base_name] - points_per_image[image.name] = (xys, xyzs, t) - except KeyError: - pass - return points_per_image, camera_from_camera_str - - -def perform_error_analysis(camera_model, points_per_image_, save_dir, camera_str): - """ - Perform error analysis and save all plots into a single PDF. - - Parameters: - - camera_model: The calibrated camera model. - - points_per_image_: List of tuples containing image points, corresponding 3D points, and timestamp. - - save_dir: Directory where the PDF will be saved. - - camera_str: String identifier for the camera (used in PDF filename). - """ - err_meters = [] - err_pixels = [] - err_pixels_per_frame = [] - err_angle = [] - ifov = np.mean(camera_model.ifov()) # Assuming 'ifov' stands for 'instantaneous field of view' - - for xys, xyzs, t in points_per_image_: - # Project 3D points to 2D image points - xys2 = camera_model.project(xyzs.T, t) - err_pixels_ = np.sqrt(np.sum((xys2 - xys.T)**2, axis=0)) - err_pixels_per_frame.append([t, err_pixels_.mean()]) - err_pixels.extend(err_pixels_.tolist()) - - # Unproject image points to camera rays - ray_pos, ray_dir = camera_model.unproject(xys.T, t) - - # Compute direction from camera to 3D points - ray_dir2 = xyzs.T - ray_pos - dist = np.linalg.norm(ray_dir2, axis=0) - ray_dir2 /= dist - - # Calculate angular deviation - dp = np.clip(np.sum(ray_dir * ray_dir2, axis=0), -1, 1) - theta = np.arccos(dp) - err_angle.extend(theta.tolist()) - - # Calculate orthogonal distance in meters - err_meters.extend((np.sin(theta) * dist).tolist()) - - # Convert lists to numpy arrays for easier manipulation - err_meters = np.array(err_meters) - err_pixels = np.array(err_pixels) - err_angle = np.array(err_angle) - err_pixels_per_frame = np.array(err_pixels_per_frame).T - - # Sort the errors - sorted_err_meters = np.sort(err_meters) - sorted_err_pixels = np.sort(err_pixels) - sorted_err_angle = np.sort(err_angle) - - # Initialize PdfPages object - pdf_filename = f"{save_dir}/error_analysis_{camera_str}.pdf" - with PdfPages(pdf_filename) as pdf: - # --- Plot 1: Histogram of Pixel Errors --- - plt.figure(figsize=(8, 6)) - plt.hist(sorted_err_pixels, bins=50, color='blue', alpha=0.7) - plt.title('Pixel Errors') - plt.xlabel('Error (pixels)') - plt.ylabel('Frequency') - plt.grid(True) - pdf.savefig() # Save the current figure into the PDF - plt.close() - - # --- Plot 2: Histogram of Meter Errors --- - plt.figure(figsize=(8, 6)) - plt.hist(sorted_err_meters, bins=50, color='green', alpha=0.7) - plt.title('Meter Errors') - plt.xlabel('Error (meters)') - plt.ylabel('Frequency') - plt.grid(True) - pdf.savefig() - plt.close() - - # --- Plot 3: Histogram of Angular Errors --- - plt.figure(figsize=(8, 6)) - plt.hist(np.degrees(sorted_err_angle), bins=50, color='red', alpha=0.7) - plt.title('Angular Errors') - plt.xlabel('Error (degrees)') - plt.ylabel('Frequency') - plt.grid(True) - pdf.savefig() - plt.close() - - # --- Plot 4: Pixel Errors per Frame --- - plt.figure(figsize=(10, 6)) - plt.plot(err_pixels_per_frame[0], err_pixels_per_frame[1], marker='o', linestyle='-', color='purple') - plt.title('Average Pixel Error per Frame') - plt.xlabel('Frame Index or Timestamp') - plt.ylabel('Average Pixel Error (pixels)') - plt.grid(True) - pdf.savefig() - plt.close() - - # --- Optional: Additional Plots --- - # If you have more plots to include, add them here following the same pattern. - - print(f"Error analysis plots have been saved to {pdf_filename}") - - -def calibrate_rgb(rgb_camera_strs, img_fnames, ins_poses, sfm_poses, - points_per_image, camera_from_camera_str, - nav_state_provider, save_dir): - for camera_str in rgb_camera_strs: - ins_quat_ = [] - sfm_quat_ = [] - points_per_image_ = [] - for i in range(len(img_fnames)): - fname = img_fnames[i] - if osp.basename(osp.dirname(fname)) == camera_str: - ins_quat_.append(ins_poses[i][1]) - sfm_quat_.append(sfm_poses[i][1]) - points_per_image_.append(points_per_image[fname]) - - # Both quaternions are of the form (x, y, z, w) and represent a coordinate - # system rotation. - #q_sfm = quaternion_inverse(q_cam)*quaternion_inverse(q_ins) - cam_quats = [quaternion_inverse(quaternion_multiply(sfm_quat_[k], - ins_quat_[k])) - for k in range(len(ins_quat_))] - - colmap_camera = camera_from_camera_str[camera_str] - - if colmap_camera.model == 'OPENCV': - fx, fy, cx, cy, d1, d2, d3, d4 = colmap_camera.params - elif colmap_camera.model == 'PINHOLE': - fx, fy, cx, cy = colmap_camera.params - d1 = d2 = d3 = d4 = 0 - - K = K = np.array([[fx, 0, cx], [0, fy, cy], [0, 0, 1]]) - dist = np.array([d1, d2, d3, d4]) - - def cam_quat_error(cam_quat) -> float: - cam_quat = cam_quat/np.linalg.norm(cam_quat) - camera_model = StandardCamera(colmap_camera.width, - colmap_camera.height, - K, dist, [0, 0, 0], cam_quat, - platform_pose_provider=nav_state_provider) - - err = [] - for xys, xyzs, t in points_per_image_: - if False: - # Reprojection error. - xys2 = camera_model.project(xyzs.T, t) - err_ = np.sqrt(np.sum((xys2 - xys.T)**2, axis=0)) - else: - # Error in meters. - - # Rays coming out of the camera in the direction of the imaged points. - ray_pos, ray_dir = camera_model.unproject(xys.T, t) - - # Direction coming out of the camera pointing at the actual 3-D points' - # locatinos. - ray_dir2 = xyzs.T - ray_pos - d = np.sqrt(np.sum((ray_dir2)**2, axis=0)) - ray_dir2 /= d - - dp = np.minimum(np.sum(ray_dir*ray_dir2, axis=0), 1) - dp = np.maximum(dp, -1) - theta = np.arccos(dp) - err_ = np.sin(theta)*d - #err.append(np.percentile(err_, 90)) - err.append(np.mean(err_)) - - err = np.array(err) - #err = err[err < np.percentile(err, 90)] - - err = np.mean(err) - #print('RMS reproject error for quat', cam_quat, ': %0.8f' % err) - return err - - print("Iterating through %s quaternion guesses." % len(cam_quats)) - shuffle(cam_quats) - best_quat = None - best_err = np.inf - for i in range(len(cam_quats)): - if True: - cam_quat = cam_quats[i] - else: - cam_quat = np.random.rand(4)*2-1 - - err = cam_quat_error(cam_quat) - if err < best_err: - best_err = err - best_quat = cam_quat - - if best_err < 10: - break - - print("Best error: ", best_err) - print("Best quat: ") - print(cam_quat) - - print("Minimizing error over camera quaternions") - - ret = minimize(cam_quat_error, best_quat) - best_quat = ret.x/np.linalg.norm(ret.x) - ret = minimize(cam_quat_error, best_quat, method='BFGS') - best_quat = ret.x/np.linalg.norm(ret.x) - ret = minimize(cam_quat_error, best_quat, method='Powell') - best_quat = ret.x/np.linalg.norm(ret.x) - - # Sequential 1-D optimizations. - for i in range(4): - def set_x(x): - quat = best_quat.copy() - quat = quat/np.linalg.norm(quat) - while abs(quat[i] - x) > 1e-6: - quat[i] = x - quat = quat/np.linalg.norm(quat) - - return quat - - def func(x): - return cam_quat_error(set_x(x)) - - x = np.linspace(-1, 1, 100); x = sorted(np.hstack([x, best_quat[i]])) - y = [func(x_) for x_ in x] - x = fminbound(func, x[np.argmin(y) - 1], x[np.argmin(y) + 1], xtol=1e-8) - best_quat = set_x(x) - - camera_model = StandardCamera(colmap_camera.width, colmap_camera.height, - K, dist, [0, 0, 0], best_quat, - platform_pose_provider=nav_state_provider) - - ub.ensuredir(save_dir) - - camera_model.save_to_file('%s/%s.yaml' % (save_dir, camera_str)) - - perform_error_analysis(camera_model, - points_per_image_, - save_dir, - camera_str) - - -def create_time_modality_mapping(colmap_images, basename_to_time): - print("Creating mapping between RGB and UV images...") - time_to_modality = ub.AutoDict() - for image in colmap_images.values(): - base_name = get_base_name(image.name) - try: - t = basename_to_time[base_name] - except Exception as e: - print(e) - print(f"No ins time found for image {base_name}.") - continue - modality = get_modality(image.name) - time_to_modality[t][modality] = image - return time_to_modality - - -def create_fname_to_time_channel_modality(img_fnames, basename_to_time): - print("Creating mapping between RGB and UV images...") - time_to_modality = ub.AutoDict() - for fname in img_fnames: - base_name = get_base_name(fname) - try: - t = basename_to_time[base_name] - except Exception as e: - print(e) - print(f"No ins time found for image {base_name}.") - continue - modality = get_modality(fname) - channel = get_channel(fname) - time_to_modality[t][channel][modality] = fname - return time_to_modality - - -def write_gifs(gif_dir, colmap_dir, img_fnames, - fname_to_time_channel_modality, - basename_to_time, rgb_str, camera_str, - cm_rgb, cm_uv): - print(f"Writing a registration gif for cameras {rgb_str} " - f"and {camera_str}.") - # Pick an image pair and register. - ub.ensuredir(gif_dir) - - for k in range(10): - inds = list(range(len(img_fnames))) - shuffle(inds) - for i in range(len(img_fnames)): - uv_img = rgb_img = None - fname1 = img_fnames[inds[i]] - if osp.basename(osp.dirname(fname1)) != rgb_str: - continue - t1 = basename_to_time[get_base_name(fname1)] - channel = get_channel(fname1) # L/C/R - try: - rgb_fname = fname_to_time_channel_modality[t1][channel]["rgb"] - abs_rgb_fname = os.path.join(colmap_dir, 'images0', rgb_fname) - rgb_img = cv2.imread(abs_rgb_fname, cv2.IMREAD_COLOR)[:, :, ::-1] - except Exception as e: - print(f"No rgb image found at time {t1}") - continue - try: - uv_fname = fname_to_time_channel_modality[t1][channel]["uv"] - abs_uv_fname = os.path.join(colmap_dir, 'images0', uv_fname) - uv_img = cv2.imread(abs_uv_fname, cv2.IMREAD_COLOR)[:, :, ::-1] - break - except Exception as e: - print(f"No uv image found at time {t1}") - continue - - if uv_img is None or rgb_img is None: - print("Failed to find matching image pair, skipping.") - continue - print(f"Writing {rgb_fname} and {uv_fname} to gif.") - - # Warps the color image img1 into the uv camera model cm_uv - warped_rgb_img, mask = render_view(cm_rgb, rgb_img, 0, - cm_uv, 0, block_size=10) - - ds_warped_rgb_img = PIL.Image.fromarray(cv2.pyrDown( - cv2.pyrDown(cv2.pyrDown(warped_rgb_img)))) - ds_uv_img = PIL.Image.fromarray(cv2.pyrDown( - cv2.pyrDown(cv2.pyrDown(uv_img)))) - fname_out = osp.join(gif_dir, - f"{rgb_str}_to_{camera_str}_registration_{k+1}.gif") - print(f"Writing gif to {fname_out}.") - ds_uv_img.save(fname_out, save_all=True, - append_images=[ds_warped_rgb_img], - duration=350, loop=0) - - -def calibrate_uv(uv_camera_strs, img_fnames, colmap_images, - camera_from_camera_str, save_dir, - basename_to_time, time_to_modality, - fname_to_time_channel_modality, - colmap_dir, points_per_image): - nav_state_fixed = NavStateFixed(np.zeros(3), [0, 0, 0, 1]) - skipped = 0 - total = 0 - for uv_str in uv_camera_strs: - print(f"Matching images to camera {uv_str}.") - rgb_str = uv_str.replace('uv', 'rgb') - cm_rgb = StandardCamera.load_from_file(osp.join(save_dir, rgb_str + '.yaml'), - platform_pose_provider=nav_state_fixed) - im_pts_uv = [] - im_pts_rgb = [] - - # Build up pairs of image coordinates between the two cameras from image - # pairs acquired from the same time. - image_nums = sorted(list(colmap_images.keys())) - for image_num in image_nums: - #print('%i/%i' % (image_num + 1, image_nums[-1])) - image = colmap_images[image_num] - im_str = osp.basename(osp.dirname(image.name)) - if im_str != uv_str: - #print(f"{im_str} does not match {camera_str}, skipping.") - continue - - # now we know it's uv - image_uv = image - base_name = get_base_name(image_uv.name) - - try: - t1 = basename_to_time[base_name] - except KeyError: - print(f"No time found for {base_name}.") - continue - - try: - image_rgb = time_to_modality[t1]["rgb"] - except KeyError: - print(f"No rgb image found at {t1}.") - continue - - # Both 'uv_image' and 'image_rgb' are from the same time. - pt_ids1 = image_uv.point3D_ids - ind = pt_ids1 != -1 - xys1 = dict(zip(pt_ids1[ind], image_uv.xys[ind])) - - pt_ids2 = image_rgb.point3D_ids - ind = pt_ids2 != -1 - xys2 = dict(zip(pt_ids2[ind], image_rgb.xys[ind])) - - match_ids = set(xys1.keys()).intersection(set(xys2.keys())) - total += 1 - if len(match_ids) < 1: - #print("No match IDs found.") - skipped += 1 - continue - - for match_id in match_ids: - im_pts_uv.append(xys1[match_id]) - im_pts_rgb.append(xys2[match_id]) - - print(f"Matched {total-skipped}/{total} image pairs, resulting in " - f"{len(im_pts_uv)} matching UV and RGB points.") - - im_pts_uv = np.array(im_pts_uv) - im_pts_rgb = np.array(im_pts_rgb) - # Arbitrary cut off - minimum_pts_required = 10 - if len(im_pts_rgb) < minimum_pts_required or \ - len(im_pts_uv) < minimum_pts_required: - print("[ERROR] Not enough matching RGB/UV image points were found " - f"for camera {uv_str}.") - continue - - if False: - plt.subplot(121) - plt.plot(im_pts_uv[:, 0], im_pts_uv[:, 1], 'ro') - plt.subplot(122) - plt.plot(im_pts_rgb[:, 0], im_pts_rgb[:, 1], 'bo') - - # Treat as co-located cameras (they are) and unproject out of RGB and into - # the other camera. - ray_pos, ray_dir = cm_rgb.unproject(im_pts_rgb.T) - wrld_pts = ray_dir.T*1e4 - assert np.all(np.isfinite(wrld_pts)), "World points contain non-finite values." - - colmap_camera = camera_from_camera_str[uv_str] - - if colmap_camera.model == 'OPENCV': - fx, fy, cx, cy, d1, d2, d3, d4 = colmap_camera.params - elif colmap_camera.model == 'PINHOLE': - fx, fy, cx, cy = colmap_camera.params - d1 = d2 = d3 = d4 = 0 - - K = np.array([[fx, 0, cx], [0, fy, cy], [0, 0, 1]]) - dist = np.array([d1, d2, d3, d4], dtype=np.float32) - - flags = cv2.CALIB_ZERO_TANGENT_DIST - flags = flags | cv2.CALIB_USE_INTRINSIC_GUESS - flags = flags | cv2.CALIB_FIX_PRINCIPAL_POINT - flags = flags | cv2.CALIB_FIX_K1 - flags = flags | cv2.CALIB_FIX_K2 - flags = flags | cv2.CALIB_FIX_K3 - flags = flags | cv2.CALIB_FIX_K4 - flags = flags | cv2.CALIB_FIX_K5 - flags = flags | cv2.CALIB_FIX_K6 - - criteria = (cv2.TERM_CRITERIA_EPS + cv2.TERM_CRITERIA_MAX_ITER, 30000, - 0.0000001) - - ret = cv2.calibrateCamera([wrld_pts.astype(np.float32)], - [im_pts_uv.astype(np.float32)], - (colmap_camera.width, colmap_camera.height), - cameraMatrix=K.copy(), distCoeffs=dist.copy(), - flags=flags, criteria=criteria) - - err, _, _, rvecs, tvecs = ret - - R = np.identity(4) - R[:3, :3] = cv2.Rodrigues(rvecs[0])[0] - cam_quat = quaternion_from_matrix(R.T) - - # Only optimize 3/4 components of the quaternion. - static_quat_ind = np.argmax(np.abs(cam_quat)) - dynamic_quat_ind = [ i for i in range(4) if i != static_quat_ind ] - #static_quat_ind = 3 # Fixing the 'w' component - #dynamic_quat_ind = [0, 1, 2] # Optimizing 'x', 'y', 'z' components - dynamic_quat_ind = np.array(dynamic_quat_ind) - cam_quat = np.asarray(cam_quat) - cam_quat /= np.linalg.norm(cam_quat) - x0 = cam_quat[dynamic_quat_ind].copy() # [x, y, z] - - def get_cm(x): - """ - Create a camera model with updated quaternion and intrinsic parameters. - - Parameters: - - x: array-like, shape (N,) - Optimization variables where the first 3 elements correspond to - the dynamic quaternion components ('x', 'y', 'z'), optionally - followed by intrinsic parameters ('fx', 'fy', etc.). - - Returns: - - cm: StandardCamera instance - Updated camera model with new parameters. - """ - # Ensure 'x' has at least 3 elements for quaternion - assert len(x) > 2, "Optimization variable 'x' must have at least 3 elements for quaternion." - - # Validate 'x[:3]' are finite numbers - assert np.all(np.isfinite(x[:3])), "Quaternion components contain non-finite values." - - # Initialize quaternion with fixed 'w' component - cam_quat_new = np.ones(4) - - # Assign dynamic components from optimization variables - cam_quat_new[dynamic_quat_ind] = x[:3] - - # Normalize to ensure it's a unit quaternion - norm = np.linalg.norm(cam_quat_new) - assert norm > 1e-6, "Quaternion has zero or near-zero magnitude." - cam_quat_new /= norm - - # Extract intrinsic parameters - if len(x) > 3: - fx_ = x[3] - fy_ = x[4] - else: - fx_ = fx - fy_ = fy - - if len(x) > 5: - dist_ = x[5:] - else: - dist_ = dist - - # Construct the intrinsic matrix - K = np.array([[fx_, 0, cx], [0, fy_, cy], [0, 0, 1]]) - - # Create the camera model - cm = StandardCamera( - colmap_camera.width, - colmap_camera.height, - K, - dist_, - [0, 0, 0], - cam_quat_new, - platform_pose_provider=nav_state_fixed - ) - return cm - - def error(x): - try: - cm = get_cm(x) - projected_uv = cm.project(wrld_pts.T).T # Shape: (N, 2) - - # Compute Euclidean distances - err = np.sqrt(np.sum((im_pts_uv - projected_uv) ** 2, axis=1)) - - # Apply Huber loss - delta = 20 - ind = err < delta - err[ind] = err[ind] ** 2 - err[~ind] = 2 * (err[~ind] - delta / 2) * delta - - # Sort and trim the error - err = sorted(err)[:len(err) - len(err) // 5] - - # Compute mean error - mean_err = np.sqrt(np.mean(err)) - - # Add regularization term (e.g., L2 penalty) - reg_strength = 1e-3 # Adjust as needed - reg_term = reg_strength * np.linalg.norm(x[:3])**2 - - total_error = mean_err + reg_term - return total_error - except Exception as e: - print(f"Error in error function: {e}") - return np.inf # Assign a high error if computation fails - - # Optional: Define a callback function to monitor optimization - def callback(xk): - try: - cm = get_cm(xk) - projected_uv = cm.project(wrld_pts.T).T - err = np.sqrt(np.sum((im_pts_uv - projected_uv) ** 2, axis=1)) - mean_err = np.mean(err) - print(f"Current x: {xk}, Mean Error: {mean_err}") - except Exception as e: - print(f"Error in callback: {e}") - - def plot_results1(x): - cm = get_cm(x) - err = np.sqrt(np.sum((im_pts_uv - cm.project(wrld_pts.T).T)**2, 1)) - err = sorted(err) - plt.plot(np.linspace(0, 100, len(err)), err) - - print("Optimizing error for UV models.") - x = x0.copy() - # Example bounds for [x, y, z] components - bounds = [(-1.0, 1.0), # x - (-1.0, 1.0), # y - (-1.0, 1.0)] # z - print("First pass") - # Perform optimization on [x, y, z] - ret = minimize( - error, - x, - method='L-BFGS-B', - bounds=bounds, - callback=None, # Optional: Monitor progress - options={'disp': False, 'maxiter': 30000, 'ftol': 1e-7} - ) - assert ret.success, "Minimization of UV error failed." - x = np.hstack([ret.x, fx, fy]) - print("Second pass") - assert np.all(np.isfinite(x)), "Input quaternion with locked fx, fy, is not finite." - ret = minimize(error, x, method='Powell') - x = ret.x - print("Third pass") - assert np.all(np.isfinite(x)), "Input quaternion for BFGS is not finite." - ret = minimize(error, x, method='BFGS') - - print("Final pass") - if True: - x = np.hstack([ret.x, dist]) - ret = minimize(error, x, method='Powell'); x = ret.x - ret = minimize(error, x, method='BFGS'); x = ret.x - - assert np.all(np.isfinite(x)), "Input quaternion for final model is not finite." - cm_uv = get_cm(x) - cm_uv.save_to_file('%s/%s.yaml' % (save_dir, uv_str)) - - perform_error_analysis_and_save_pdf(cm_uv, cm_rgb, points_per_image, - save_dir, - uv_str, rgb_str) - gif_dir = osp.join(save_dir, 'registration_gifs') - write_gifs(gif_dir, colmap_dir, img_fnames, - fname_to_time_channel_modality, - basename_to_time, rgb_str, uv_str, - cm_rgb, cm_uv) - - -def perform_error_analysis_and_save_pdf(camera_model_uv, camera_model_rgb, - points_per_image, - save_dir, - uv_str, - rgb_str): - """ - Perform error analysis for both UV and RGB models and save all plots into a single PDF. - - Parameters: - - camera_model_uv: Calibrated UV camera model. - - camera_model_rgb: Calibrated RGB camera model. - - points_per_image_uv: List of tuples containing (image points, corresponding 3D points, timestamp) for UV. - - points_per_image_rgb: List of tuples containing (image points, corresponding 3D points, timestamp) for RGB. - - save_dir: Directory where the PDF will be saved. - - uv_str: String identifier for the UV camera. - - rgb_str: String identifier for the RGB camera. - """ - - # Initialize error lists for UV - err_meters_uv = [] - err_pixels_uv = [] - err_pixels_per_frame_uv = [] - err_angle_uv = [] - im_pts_uv = [] - im_pts_rgb = [] - - # Mean IFOV for UV (assuming similar to RGB) - ifov_uv = np.mean(camera_model_uv.ifov()) - - #import ipdb; ipdb.set_trace() - # Error analysis for UV - for fname, (xys, xyzs, t) in points_per_image.items(): - im_str = osp.basename(osp.dirname(fname)) - if im_str != uv_str: - continue - im_pts_uv.extend(xys) - # Project 3D points to 2D image points using UV model - xys2 = camera_model_uv.project(xyzs.T, t) - err_pixels_ = np.sqrt(np.sum((xys2 - xys.T)**2, axis=0)) - err_pixels_per_frame_uv.append([t, err_pixels_.mean()]) - err_pixels_uv.extend(err_pixels_.tolist()) - - # Unproject image points to camera rays - ray_pos, ray_dir = camera_model_uv.unproject(xys.T, t) - - # Compute direction from camera to 3D points - ray_dir2 = xyzs.T - ray_pos - dist = np.linalg.norm(ray_dir2, axis=0) - ray_dir2 /= dist - - # Calculate angular deviation - dp = np.clip(np.sum(ray_dir * ray_dir2, axis=0), -1, 1) - theta = np.arccos(dp) - err_angle_uv.extend(theta.tolist()) - - # Calculate orthogonal distance in meters - err_meters_uv.extend((np.sin(theta) * dist).tolist()) - - # Initialize error lists for RGB - err_meters_rgb = [] - err_pixels_rgb = [] - err_pixels_per_frame_rgb = [] - err_angle_rgb = [] - - # Mean IFOV for RGB - ifov_rgb = np.mean(camera_model_rgb.ifov()) - - # Error analysis for RGB - for fname, (xys, xyzs, t) in points_per_image.items(): - im_str = osp.basename(osp.dirname(fname)) - if im_str != rgb_str: - continue - im_pts_rgb.extend(xys) - # Project 3D points to 2D image points using RGB model - xys2 = camera_model_rgb.project(xyzs.T, t) - err_pixels_ = np.sqrt(np.sum((xys2 - xys.T)**2, axis=0)) - err_pixels_per_frame_rgb.append([t, err_pixels_.mean()]) - err_pixels_rgb.extend(err_pixels_.tolist()) - - # Unproject image points to camera rays - ray_pos, ray_dir = camera_model_rgb.unproject(xys.T, t) - - # Compute direction from camera to 3D points - ray_dir2 = xyzs.T - ray_pos - dist = np.linalg.norm(ray_dir2, axis=0) - ray_dir2 /= dist - - # Calculate angular deviation - dp = np.clip(np.sum(ray_dir * ray_dir2, axis=0), -1, 1) - theta = np.arccos(dp) - err_angle_rgb.extend(theta.tolist()) - - # Calculate orthogonal distance in meters - err_meters_rgb.extend((np.sin(theta) * dist).tolist()) - - # Convert lists to numpy arrays for easier manipulation - err_meters_uv = np.array(err_meters_uv) - err_pixels_uv = np.array(err_pixels_uv) - err_angle_uv = np.array(err_angle_uv) - err_pixels_per_frame_uv = np.array(err_pixels_per_frame_uv).T - - err_meters_rgb = np.array(err_meters_rgb) - err_pixels_rgb = np.array(err_pixels_rgb) - err_angle_rgb = np.array(err_angle_rgb) - err_pixels_per_frame_rgb = np.array(err_pixels_per_frame_rgb).T - - # Sort the errors - sorted_err_meters_uv = np.sort(err_meters_uv) - sorted_err_pixels_uv = np.sort(err_pixels_uv) - sorted_err_angle_uv = np.sort(err_angle_uv) - - sorted_err_meters_rgb = np.sort(err_meters_rgb) - sorted_err_pixels_rgb = np.sort(err_pixels_rgb) - sorted_err_angle_rgb = np.sort(err_angle_rgb) - - im_pts_uv = np.asarray(im_pts_uv) - im_pts_rgb = np.asarray(im_pts_rgb) - - # Initialize PdfPages object - pdf_filename = f"{save_dir}/error_analysis_{uv_str}_{rgb_str}.pdf" - with PdfPages(pdf_filename) as pdf: - # --- Plot 1: Summary Statistics for UV --- - plt.figure(figsize=(11.69, 8.27)) # A4 size in inches - plt.axis('off') # Hide axes - - summary_text_uv = f""" - Error Analysis Summary for UV Camera: {uv_str} - - Pixel Errors: - - Mean: {np.mean(err_pixels_uv):.2f} pixels - - Median: {np.median(err_pixels_uv):.2f} pixels - - Max: {np.max(err_pixels_uv):.2f} pixels - - Meter Errors: - - Mean: {np.mean(err_meters_uv):.2f} meters - - Median: {np.median(err_meters_uv):.2f} meters - - Max: {np.max(err_meters_uv):.2f} meters - - Angular Errors: - - Mean: {np.degrees(np.mean(err_angle_uv)):.2f} degrees - - Median: {np.degrees(np.median(err_angle_uv)):.2f} degrees - - Max: {np.degrees(np.max(err_angle_uv)):.2f} degrees - """ - - plt.text(0.5, 0.5, summary_text_uv, fontsize=20, ha='center', va='center', wrap=True) - plt.title('Error Analysis Summary for UV Camera', fontsize=24) - pdf.savefig() - plt.close() - - # --- Plot 2: Histogram of Pixel Errors for UV --- - plt.figure(figsize=(11.69, 8.27)) - plt.hist(sorted_err_pixels_uv, bins=50, color='blue', alpha=0.7) - plt.title('UV Camera - Pixel Errors', fontsize=24) - plt.xlabel('Error (pixels)', fontsize=20) - plt.ylabel('Frequency', fontsize=20) - plt.grid(True) - pdf.savefig() - plt.close() - - # --- Plot 3: Histogram of Meter Errors for UV --- - plt.figure(figsize=(11.69, 8.27)) - plt.hist(sorted_err_meters_uv, bins=50, color='green', alpha=0.7) - plt.title('UV Camera - Meter Errors', fontsize=24) - plt.xlabel('Error (meters)', fontsize=20) - plt.ylabel('Frequency', fontsize=20) - plt.grid(True) - pdf.savefig() - plt.close() - - # --- Plot 4: Histogram of Angular Errors for UV --- - plt.figure(figsize=(11.69, 8.27)) - plt.hist(np.degrees(sorted_err_angle_uv), bins=50, color='red', alpha=0.7) - plt.title('UV Camera - Angular Errors', fontsize=24) - plt.xlabel('Error (degrees)', fontsize=20) - plt.ylabel('Frequency', fontsize=20) - plt.grid(True) - pdf.savefig() - plt.close() - - # --- Plot 5: Average Pixel Error per Frame for UV --- - plt.figure(figsize=(11.69, 8.27)) - plt.plot(err_pixels_per_frame_uv[0], err_pixels_per_frame_uv[1], marker='o', linestyle='-', color='purple') - plt.title('UV Camera - Average Pixel Error per Frame', fontsize=24) - plt.xlabel('Frame Index or Timestamp', fontsize=20) - plt.ylabel('Average Pixel Error (pixels)', fontsize=20) - plt.grid(True) - pdf.savefig() - plt.close() - - # --- Plot 6: Scatter Plot of UV and RGB Points --- - plt.figure(figsize=(11.69, 8.27)) - plt.subplot(1, 2, 1) - plt.scatter(im_pts_uv[:, 0], im_pts_uv[:, 1], c='blue', marker='o', alpha=0.5, label='UV Observed') - plt.title('UV Camera - Observed UV Points', fontsize=24) - plt.xlabel('U', fontsize=20) - plt.ylabel('V', fontsize=20) - plt.legend() - plt.grid(True) - - plt.subplot(1, 2, 2) - plt.scatter(im_pts_rgb[:, 0], im_pts_rgb[:, 1], c='green', marker='x', alpha=0.5, label='RGB Observed') - plt.title('RGB Camera - Observed RGB Points', fontsize=24) - plt.xlabel('R', fontsize=20) - plt.ylabel('G', fontsize=20) - plt.legend() - plt.grid(True) - - plt.suptitle('Scatter Plots of Observed Points', fontsize=28) - plt.tight_layout(rect=[0, 0.03, 1, 0.95]) - pdf.savefig() - plt.close() - - # --- Plot 7: Reprojection Error Histograms for Both UV and RGB --- - plt.figure(figsize=(11.69, 8.27)) - plt.subplot(1, 2, 1) - plt.hist(sorted_err_pixels_uv, bins=50, color='blue', alpha=0.7, label='UV Pixel Errors') - plt.hist(sorted_err_pixels_rgb, bins=50, color='red', alpha=0.5, label='RGB Pixel Errors') - plt.title('Reprojection Pixel Errors', fontsize=24) - plt.xlabel('Error (pixels)', fontsize=20) - plt.ylabel('Frequency', fontsize=20) - plt.legend() - plt.grid(True) - - plt.subplot(1, 2, 2) - plt.hist(np.degrees(sorted_err_angle_uv), bins=50, color='blue', alpha=0.7, label='UV Angular Errors') - plt.hist(np.degrees(sorted_err_angle_rgb), bins=50, color='red', alpha=0.5, label='RGB Angular Errors') - plt.title('Reprojection Angular Errors', fontsize=24) - plt.xlabel('Error (degrees)', fontsize=20) - plt.ylabel('Frequency', fontsize=20) - plt.legend() - plt.grid(True) - - plt.suptitle('Reprojection Error Histograms for UV and RGB Cameras', fontsize=28) - plt.tight_layout(rect=[0, 0.03, 1, 0.95]) - pdf.savefig() - plt.close() - - -def process_aligned_results(aligned_sparse_recon_subdir, colmap_dir, save_dir, - nav_state_provider, basename_to_time): - # --------------------------------------------------------------------------- - # Sanity check, pick the coordinates for a point in the 3-D model and - # convert them to latitude and longitude. - enu = np.array((640.446167, 822.111633, -9.576390)) - print(enu_to_llh(enu[0], enu[1], enu[2], nav_state_provider.lat0, - nav_state_provider.lon0, nav_state_provider.h0)) - - # Read in the Colmap details of all images. - images_bin_fname = osp.join(colmap_dir, - aligned_sparse_recon_subdir, - 'images.bin') - colmap_images = read_images_binary(images_bin_fname) - points_bin_fname = osp.join(colmap_dir, - aligned_sparse_recon_subdir, - 'points3D.bin') - points3d = read_points3D_binary(points_bin_fname) - camera_bin_fname = osp.join(colmap_dir, - aligned_sparse_recon_subdir, - 'cameras.bin') - colmap_cameras = read_cameras_binary(camera_bin_fname) - - """ - # For sanity checking that the original unadjusted results line up and the - # code itself is sound. - images_bin_fname = '%s/%s/images.bin' % (colmap_dir, sparse_recon_subdir) - colmap_images = read_images_binary(images_bin_fname) - points_bin_fname = '%s/%s/points3D.bin' % (colmap_dir, sparse_recon_subdir) - points3d = read_points3D_binary(points_bin_fname) - camera_bin_fname = '%s/%s/cameras.bin' % (colmap_dir, sparse_recon_subdir) - colmap_cameras = read_cameras_binary(camera_bin_fname) - """ - - if False: - pts_3d = [] - for pt_id in points3d: - pts_3d.append(points3d[pt_id].xyz) - - pts_3d = np.array(pts_3d).T - plt.plot(pts_3d[0], pts_3d[1], 'ro') - - - points_per_image, camera_from_camera_str = get_colmap_data(colmap_images, - colmap_cameras, - points3d, - basename_to_time) - - img_fnames, img_times, ins_poses, sfm_poses, llhs = process_images(colmap_images, - basename_to_time, - nav_state_provider) - - if False: - # Loop over all images and apply the camera model to project 3-D points - # into the image and compare to the measured versions to calculate - # reprojection error. - err = [] - for i in range(len(img_fnames)): - print('%i/%i' % (i + 1, len(img_fnames))) - fname = img_fnames[i] - sfm_pose = sfm_poses[i] - camera_str = osp.basename(osp.dirname(fname)) - - colmap_camera = camera_from_camera_str[camera_str] - - if colmap_camera.model == 'OPENCV': - fx, fy, cx, cy, d1, d2, d3, d4 = colmap_camera.params - elif colmap_camera.model == 'PINHOLE': - fx, fy, cx, cy = colmap_camera.params - d1 = d2 = d3 = d4 = 0 - - K = K = np.array([[fx, 0, cx], [0, fy, cy], [0, 0, 1]]) - dist = np.array([d1, d2, d3, d4]) - - cm = StandardCamera(colmap_camera.width, colmap_camera.height, K, dist, - [0, 0, 0], [0, 0, 0, 1], - platform_pose_provider=NavStateFixed(*sfm_pose)) - xy, xyz, t = points_per_image[fname] - err_ = np.sqrt(np.sum((xy - cm.project(xyz.T, t).T)**2, axis=1)) - err = err + err_.tolist() - - print("Errors: ") - print(np.mean(err)) - print(np.median(err)) - #plt.hist(err, 1000) - - - camera_strs = set([osp.basename(osp.dirname(fname)) for fname in img_fnames]) - rgb_camera_strs = set([ cam for cam in camera_strs if 'rgb' in cam ]) - uv_camera_strs = set([ cam for cam in camera_strs if 'uv' in cam ]) - - print("Calibrating RGB cameras.") - calibrate_rgb(rgb_camera_strs, img_fnames, ins_poses, sfm_poses, - points_per_image, camera_from_camera_str, - nav_state_provider, save_dir) - - time_to_modality = create_time_modality_mapping(colmap_images, basename_to_time) - fname_to_time_channel_modality = create_fname_to_time_channel_modality( - img_fnames, basename_to_time) - - print("Calibrating UV cameras.") - calibrate_uv(uv_camera_strs, img_fnames, colmap_images, - camera_from_camera_str, save_dir, - basename_to_time, time_to_modality, - fname_to_time_channel_modality, - colmap_dir, points_per_image) - print("Finished calibration!") - - -def main(): - # ---------------------------- Define Paths ---------------------------------- - # KAMERA flight directory where each sub-directory contains meta.json files. - flight_dir = '/home/local/KHQ/adam.romlein/noaa/data/2024_AOC_AK_Calibration/fl09' - - # You should have a colmap directory where all of the Colmap-generated files - # reside. - colmap_dir = '/home/local/KHQ/adam.romlein/noaa/data/2024_AOC_AK_Calibration/colmap' - - # Sub-directory containing the images.bin and cameras.bin. Set to '' if in the - # top-level Colmap directory. - sparse_recon_subdir = 'sparse/1' - aligned_sparse_recon_subdir = 'aligned/1' - - # Location to save KAMERA camera models. - save_dir = osp.join(flight_dir, 'kamera_models') - # ---------------------------------------------------------------------------- - - basename_to_time = get_basename_to_time(flight_dir) - - json_glob = pathlib.Path(flight_dir).rglob('*_meta.json') - try: - next(json_glob) - except StopIteration: - raise SystemExit("No meta jsons were found, please check your filepaths.") - nav_state_provider = NavStateINSJson(json_glob) - - # We take the INS-reported position (converted from latitude, longitude, and - # altitude into easting/northing/up coordinates) and assign it to each image. - print('Latiude of ENU coordinate system:', nav_state_provider.lat0, 'degrees') - print('Longitude of ENU coordinate system:', nav_state_provider.lon0, - 'degrees') - print('Height above the WGS84 ellipsoid of the ENU coordinate system:', - nav_state_provider.h0, 'meters') - - # ---------------------------------------------------------------------------- - # Assemble the list of filenames with paths relative to the 'images0' directory - # that we point Colmap to as the raw image directory. This may be a directory - # of images, or it might be a directory of subdirectories, each of which - # contains images from one camera. - - # Colmap then uses this pairing to solve for a similarity transform to best- - # match the SfM poses it recovered into these positions. All Colmap coordinates - # in this aligned version of its reconstruction will then be in easting/ - # northing/up meters coordinates - align_fname = os.path.join(colmap_dir, 'image_locations.txt') - print(align_fname) - if osp.exists(align_fname) and osp.exists(osp.join(colmap_dir, - aligned_sparse_recon_subdir)): - print(f"{align_fname} and {aligned_sparse_recon_subdir} exists," - " assuming model is aligned.") - else: - # Read in the Colmap details of all images. - images_bin_fname = osp.join(colmap_dir, sparse_recon_subdir, 'images.bin') - colmap_images = read_images_binary(images_bin_fname) - - img_fnames, img_times, ins_poses, sfm_poses, llhs = process_images(colmap_images, - basename_to_time, - nav_state_provider) - write_image_locations(align_fname, img_fnames, ins_poses) - ub.ensuredir(osp.join(colmap_dir, aligned_sparse_recon_subdir)) - print('Now run\nkamera/src/kitware-ros-pkg/postflight_scripts/scripts/' - 'colmap/model_aligner.sh %s %s %s %s' % (colmap_dir.replace('/host_filesystem', ''), - sparse_recon_subdir, - 'image_locations.txt', - aligned_sparse_recon_subdir)) - return - - process_aligned_results(aligned_sparse_recon_subdir, colmap_dir, - save_dir, nav_state_provider, - basename_to_time) - -if __name__ == "__main__": - main() From ee8b770ed44d49c0dadccf8dff70217e4479e625 Mon Sep 17 00:00:00 2001 From: Adam Romlein Date: Mon, 31 Mar 2025 10:59:43 -0400 Subject: [PATCH 15/20] Updates for calibration UI --- kamera/colmap_processing/vtk_util.py | 610 +++++++++++++++------------ 1 file changed, 332 insertions(+), 278 deletions(-) diff --git a/kamera/colmap_processing/vtk_util.py b/kamera/colmap_processing/vtk_util.py index 084c88d..5b1f49e 100644 --- a/kamera/colmap_processing/vtk_util.py +++ b/kamera/colmap_processing/vtk_util.py @@ -1,141 +1,165 @@ -#! /usr/bin/python -""" -ckwg +31 -Copyright 2018 by Kitware, Inc. -All rights reserved. - -Redistribution and use in source and binary forms, with or without -modification, are permitted provided that the following conditions are met: - - * Redistributions of source code must retain the above copyright notice, - this list of conditions and the following disclaimer. - - * Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation - and/or other materials provided with the distribution. - - * Neither name of Kitware, Inc. nor the names of any contributors may be used - to endorse or promote products derived from this software without specific - prior written permission. - -THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS ``AS IS'' -AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHORS OR CONTRIBUTORS BE LIABLE FOR -ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL -DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR -SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER -CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, -OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE -OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - -============================================================================== - -""" from __future__ import division, print_function +import copy +import cv2 +import os +import vtk +import matplotlib.pyplot as plt import numpy as np -import copy, os, cv2, vtk from vtk.util import numpy_support -import matplotlib.pyplot as plt -# from matplotlib.patches import Polygon -# from matplotlib.collections import PatchCollection -# from mpl_toolkits.mplot3d import Axes3D +from scipy.spatial.transform import Rotation -from colmap_processing.camera_models import StandardCamera, \ - quaternion_from_matrix -from colmap_processing.platform_pose import PlatformPoseFixed +from kamera.colmap_processing.camera_models import StandardCamera +from kamera.colmap_processing.platform_pose import PlatformPoseFixed class Camera(object): - def __init__(self, res_x, res_y, vfov, pos, rmat): - """Create camera. + def __init__( + self, + camera: vtk.vtkCamera, + res_x: int, + res_y: int, + vfov: float, + pos: list[float], + rmat: np.ndarray, + ) -> None: + self.res_x = res_x + self.res_y = res_y + self.vfov = vfov + self.pos = pos + self.rmat = Rotation.from_matrix(rmat) + self.dist = None + self._kmat = None + self.camera = camera + + self.sync() - When pan and tilt are zero, the camera points north. + @property + def focal_length(self): + """Return the unitless focal length.""" + return 1 / (2 * np.tan(self.vfov / 180 * np.pi / 2)) * self.res_y - :param res_x: Horizontal resolution of the image. - :type res_x: int + @property + def kmat(self): + """Camera calibration matrix.""" + if self._kmat is not None: + return self._kmat + else: + return np.array( + [ + [self.focal_length, 0, self.res_x / 2], + [0, self.focal_length, self.res_y / 2], + [0, 0, 1], + ] + ) + + @kmat.setter + def kmat(self, val): + self._kmat = val + + def vtk_rotation_2_cm(self, R: np.ndarray) -> Rotation: + # a rotation consisting of the np.column_stack((right, true_up, forward)) + # vectors of a VTK camera + # VTK uses left-handed convention, so we have to flip the rotation matrix + # for it to be proper in scipy + R[:, 0] *= -1 + + # z flip it back using scipy + rot = Rotation.from_matrix(R) + z_flip = Rotation.from_euler("z", 180, degrees=True) + original = rot * z_flip + return original + + def cm_rotation_to_vtk(self, R: Rotation) -> np.ndarray: + # a rotation consisting of the np.column_stack((right, true_up, forward)) + # vectors of a StandardCamera model (right-handed orientation) + z_flip = Rotation.from_euler("z", 180, degrees=True) + original = R * z_flip + vtkR = original.as_matrix() + vtkR[:, 0] *= -1 + return vtkR + + def compute_camera_rotation( + self, position: np.ndarray, focal_point: np.ndarray, view_up: np.ndarray + ) -> Rotation: + """ + Compute the camera rotation matrix from VTK parameters. + + Parameters: + position : array-like + The camera position in world coordinates. + focal_point : array-like + The point in space the camera is looking at. + view_up : array-like + The view up vector (e.g., (0.3230, -0.4076, 0.8541)). + + Returns: + R : 3x3 numpy.ndarray + The rotation matrix from the camera coordinate system to the world coordinate system. + """ + position = np.array(position, dtype=np.float64) + focal_point = np.array(focal_point, dtype=np.float64) + view_up = np.array(view_up, dtype=np.float64) - :param res_y: Vertical resolution of the image. - :type res_y: int + # Compute the forward vector (camera's viewing direction) + forward = focal_point - position + forward = forward / np.linalg.norm(forward) - :param vfov: Vertical field of view (degrees). - :type vfov: float + # Compute the right vector (perpendicular to both forward and view up) + right = np.cross(forward, view_up) + right = right / np.linalg.norm(right) - :param pos: Position of the camera within the world. - :type pos: 3-array of float + # Compute the true up vector + true_up = np.cross(right, forward) - :param pan: Pan of the camera (degrees). When pan and tilt are zero, - the camera points along world y axis (i.e., north). - :type pan: float + # Construct the rotation matrix. + # with VTK -> CV convention, forward is positive + R = np.column_stack((right, true_up, forward)) - :param tilt: Tilt of the camera (degrees). When pan and tilt are zero, - the camera points along world y axis (i.e., north). - :type tilt: float + # VTK uses left-handed convention, so we have to flip the rotation matrix + # for it to be proper in scipy + if np.linalg.det(R) < 0: + R[:, 0] *= -1 - """ - self._res_x = res_x - self._res_y = res_y - self._vfov = vfov - self._pos = pos - self._rmat = rmat - self._model_reader = None + # flip it back using scipy + rot = Rotation.from_matrix(R) + q_flip = Rotation.from_euler("z", 180, degrees=True) + original = rot * q_flip - self._update_vtk_camera() - - @property - def focal_length(self): - """Return the unitless focal length. + return original + def get_yaw_pitch(self): """ - return 1/(2*np.tan(self.vfov/180*np.pi/2))*self.res_y - - @property - def res_x(self): - return self._res_x - - @res_x.setter - def res_x(self, val): - self._res_x = val - self._update_vtk_camera() - - @property - def res_y(self): - return self._res_y - - @res_y.setter - def res_y(self, val): - self._res_y = val + Computes the current yaw and pitch of a vtkCamera based on its position and focal point. - @property - def vfov(self): - return self._vfov + Assumes a coordinate system with Z as up. - @vfov.setter - def vfov(self, val): - self._vfov = val + Parameters: + camera: vtk.vtkCamera instance. - @property - def pos(self): - return self._pos + Returns: + yaw, pitch: Tuple of angles in degrees. + - yaw: Angle between the projection of the view direction onto the XY plane and the X-axis. + - pitch: Angle between the view direction and the XY plane. + """ + # Get camera position and focal point + pos = np.array(self.camera.GetPosition()) + focal = np.array(self.camera.GetFocalPoint()) - @pos.setter - def pos(self, val): - self._pos = val + # Compute the normalized view direction vector + view_dir = focal - pos + view_dir = view_dir / np.linalg.norm(view_dir) - @property - def rmat(self): - """Orientation rotation matrix. + # Yaw: angle in the XY plane. Use arctan2 to get the full [-180,180] range. + yaw = np.degrees(np.arctan2(view_dir[1], view_dir[0])) - """ - return self._rmat + # Pitch: angle between the view direction and the XY plane. + # When the camera is looking horizontally, view_dir[2] is zero (pitch = 0). + pitch = np.degrees(np.arcsin(view_dir[2])) - @property - def kmat(self): - """Camera calibration matrix. + return yaw, pitch - """ - return np.array([[self.focal_length, 0, self.res_x/2], - [0, self.focal_length, self.res_y/2], [0, 0, 1]]) + def set_focal_point(self, pos: list[float]): + self.camera.SetFocalPoint(pos) def ifov_image(self, downsample=1): """Return angle subtended by each pixel. @@ -146,10 +170,10 @@ def ifov_image(self, downsample=1): """ inv_kmat = np.linalg.inv(self.kmat) - res_x = self.res_x//downsample - res_y = self.res_y//downsample - X,Y = np.meshgrid(np.arange(res_x), np.arange(res_y)) - xy1 = np.ones((3,res_x*res_y)) + res_x = self.res_x // downsample + res_y = self.res_y // downsample + X, Y = np.meshgrid(np.arange(res_x), np.arange(res_y)) + xy1 = np.ones((3, res_x * res_y)) xy1[0] = X.ravel() xy1[1] = Y.ravel() @@ -164,44 +188,46 @@ def ifov_image(self, downsample=1): xy2 = np.dot(inv_kmat, xy2) xy3 = np.dot(inv_kmat, xy3) - #Normalize + # Normalize xy1 /= np.sqrt(np.sum(xy1**2, 0)) xy2 /= np.sqrt(np.sum(xy2**2, 0)) xy3 /= np.sqrt(np.sum(xy3**2, 0)) - ifov_x = np.arccos(np.maximum(np.minimum(np.sum(xy1*xy2, 0), 1), -1)) - ifov_y = np.arccos(np.maximum(np.minimum(np.sum(xy1*xy3, 0), 1), -1)) + ifov_x = np.arccos(np.maximum(np.minimum(np.sum(xy1 * xy2, 0), 1), -1)) + ifov_y = np.arccos(np.maximum(np.minimum(np.sum(xy1 * xy3, 0), 1), -1)) ifov = np.sqrt(ifov_x**2 + ifov_y**2) - ifov.shape = (self.res_y,self.res_x) + ifov.shape = (self.res_y, self.res_x) return ifov - def _update_vtk_camera(self): - camera = vtk.vtkCamera() - - # Set vertical field of view in degrees. - camera.SetViewAngle(self.vfov) - - # Define a level camera looking along the world y-axis (i.e., north). - R = self.rmat - focal_point = copy.deepcopy(self.pos) - focal_point += R[2] - camera.SetPosition(self.pos) - camera.SetFocalPoint(focal_point) - camera.SetViewUp(-R[1]) - - #camera.ParallelProjectionOn() - #camera.SetParallelScale(10) - camera.SetClippingRange(10,200) - - #camera.Pitch(-5) - #camera.OrthogonalizeViewUp() - - self.vtk_camera = camera - - def render_image(self, model_reader, clipping_range=[2,100], diffuse=0.6, - ambient=0.6, specular=0.1, light_color=[1.0, 1.0, 1.0], - light_pos=[0,0,1000]): + def sync(self): + self.pos = self.camera.GetPosition() + self.vfov = self.camera.GetViewAngle() + + view_angle = self.vfov # vertical FOV (degrees) + view_angle_rad = np.deg2rad(view_angle) + + # get focal lengths + fy = (self.res_y / 2.0) / np.tan(view_angle_rad / 2.0) + fx = fy * (self.res_x / self.res_y) + + # retain original cx, cy + cx = self.kmat[0, 2] + cy = self.kmat[1, 2] + + K = np.array([[fx, 0, cx], [0, fy, cy], [0, 0, 1]]) + self.kmat = K + + def render_image( + self, + model_reader, + clipping_range=[2, 100], + diffuse=0.6, + ambient=0.6, + specular=0.1, + light_color=[1.0, 1.0, 1.0], + light_pos=[0, 0, 1000], + ): """Render a view of the loaded model. :param model_reader: World mesh model reader. @@ -226,7 +252,7 @@ def render_image(self, model_reader, clipping_range=[2,100], diffuse=0.6, mapper.SetInputConnection(model_reader.GetOutputPort()) # Actor - actor =vtk.vtkActor() + actor = vtk.vtkActor() actor.SetMapper(mapper) # Set lighting properties @@ -236,9 +262,8 @@ def render_image(self, model_reader, clipping_range=[2,100], diffuse=0.6, # Renderer renderer = vtk.vtkRenderer() - self._update_vtk_camera() - self.vtk_camera.SetClippingRange(clipping_range[0],clipping_range[1]) - renderer.SetActiveCamera(self.vtk_camera) + self.camera.SetClippingRange(clipping_range[0], clipping_range[1]) + renderer.SetActiveCamera(self.camera) renderer.AddActor(actor) light = vtk.vtkLight() @@ -248,6 +273,7 @@ def render_image(self, model_reader, clipping_range=[2,100], diffuse=0.6, # RenderWindow renderWindow = vtk.vtkRenderWindow() + renderWindow.SetOffScreenRendering(1) renderWindow.AddRenderer(renderer) renderWindow.SetSize(self.res_x, self.res_y) @@ -257,8 +283,10 @@ def render_image(self, model_reader, clipping_range=[2,100], diffuse=0.6, rgbfilter.SetInputBufferTypeToRGB() rgbfilter.Update() dims = rgbfilter.GetOutput().GetDimensions() - npdims = [dims[1],dims[0],3] - image = numpy_support.vtk_to_numpy(rgbfilter.GetOutput().GetPointData().GetScalars()).reshape(npdims) + npdims = [dims[1], dims[0], 3] + image = numpy_support.vtk_to_numpy( + rgbfilter.GetOutput().GetPointData().GetScalars() + ).reshape(npdims) image = np.flipud(image) del renderer, renderWindow, rgbfilter @@ -268,27 +296,24 @@ def render_image(self, model_reader, clipping_range=[2,100], diffuse=0.6, def project(self, wrld_pt): if wrld_pt.ndim == 2: if wrld_pt.shape[0] == 3: - wrld_pt = np.vstack([wrld_pt,np.ones(wrld_pt.shape[1])]) + wrld_pt = np.vstack([wrld_pt, np.ones(wrld_pt.shape[1])]) else: - raise Exception('Not implemented') + raise Exception("Not implemented") im_pt = np.dot(self.get_camera_matrix(), wrld_pt) - return im_pt[:2]/im_pt[2] + return im_pt[:2] / im_pt[2] def unproject(self, im_pt): pass def get_camera_matrix(self): - """Return camera projection matrix that maps world to image. - - """ + """Return camera projection matrix that maps world to image.""" T = -np.dot(self.rmat, self.pos) - P = np.dot(self.kmat, np.hstack([self.rmat,np.atleast_2d(T).T])) + P = np.dot(self.kmat, np.hstack([self.rmat, np.atleast_2d(T).T])) return P - def unproject_view(self, model_reader, clipping_range=[2,100], - return_image=False): + def unproject_view(self, model_reader, clipping_range=[2, 100], return_image=False): """Return the coordinates of intersection of each pixel with the world. :param model_reader: World mesh model output. @@ -300,19 +325,19 @@ def unproject_view(self, model_reader, clipping_range=[2,100], mapper.SetInputConnection(model_reader.GetOutputPort()) # Actor - actor =vtk.vtkActor() + actor = vtk.vtkActor() actor.SetMapper(mapper) # Renderer renderer = vtk.vtkRenderer() - self._update_vtk_camera() - self.vtk_camera.SetClippingRange(clipping_range[0],clipping_range[1]) - renderer.SetActiveCamera(self.vtk_camera) + self.camera.SetClippingRange(clipping_range[0], clipping_range[1]) + renderer.SetActiveCamera(self.camera) renderer.AddActor(actor) # RenderWindow renderWindow = vtk.vtkRenderWindow() renderWindow.AddRenderer(renderer) + renderWindow.SetOffScreenRendering(1) renderWindow.SetSize(self.res_x, self.res_y) # Read Z Buffer @@ -323,8 +348,10 @@ def unproject_view(self, model_reader, clipping_range=[2,100], # transform zbuffer to numpy array dims = zfilter.GetOutput().GetDimensions() - npdims = [dims[1],dims[0]] - array = numpy_support.vtk_to_numpy(zfilter.GetOutput().GetPointData().GetScalars()).reshape(npdims) + npdims = [dims[1], dims[0]] + array = numpy_support.vtk_to_numpy( + zfilter.GetOutput().GetPointData().GetScalars() + ).reshape(npdims) array = np.flipud(array) if return_image: @@ -337,22 +364,20 @@ def unproject_view(self, model_reader, clipping_range=[2,100], del renderer, renderWindow, zfilter # Convert ZBuffer to range. - near, far = self.vtk_camera.GetClippingRange() - b = near*far/(near - far) - a = -b/near - depth = b/(array - a) - - X, Y = np.meshgrid(np.arange(depth.shape[1]), - np.arange(depth.shape[0])) - xy = np.vstack([X.ravel(), Y.ravel(), - np.ones(depth.shape[0]*depth.shape[1])]) - inv = np.linalg.inv(np.dot(self.kmat, self.rmat)) + near, far = self.camera.GetClippingRange() + b = near * far / (near - far) + a = -b / near + depth = b / (array - a) + + X, Y = np.meshgrid(np.arange(depth.shape[1]), np.arange(depth.shape[0])) + xy = np.vstack([X.ravel(), Y.ravel(), np.ones(depth.shape[0] * depth.shape[1])]) + inv = np.linalg.inv(np.dot(self.kmat, self.rmat.as_matrix())) ray_dir = np.dot(inv, xy) # Z-buffer is the distance the ray travels projected onto the optical # axis. The rays already have unit length when projected along the # optical axis. - xyz = ray_dir*depth.ravel() + np.atleast_2d(self.pos).T + xyz = ray_dir * depth.ravel() + np.atleast_2d(self.pos).T X = np.reshape(xyz[0], (self.res_y, self.res_x)) Y = np.reshape(xyz[1], (self.res_y, self.res_x)) @@ -362,7 +387,9 @@ def unproject_view(self, model_reader, clipping_range=[2,100], # Render image dims = rgbfilter.GetOutput().GetDimensions() npdims = [dims[1], dims[0], 3] - image = numpy_support.vtk_to_numpy(rgbfilter.GetOutput().GetPointData().GetScalars()).reshape(npdims) + image = numpy_support.vtk_to_numpy( + rgbfilter.GetOutput().GetPointData().GetScalars() + ).reshape(npdims) del rgbfilter image = np.flipud(image) return X, Y, Z, depth, image @@ -370,15 +397,32 @@ def unproject_view(self, model_reader, clipping_range=[2,100], return X, Y, Z, depth def to_standard_camera(self): - quat = quaternion_from_matrix(self.rmat.T) - platform_pose_provider = PlatformPoseFixed(self.pos, quat) - cm = StandardCamera(self.res_x, self._res_y, self.kmat, np.zeros(5), - [0, 0, 0], [0, 0, 0, 1], platform_pose_provider) + self.sync() + # Get the current position, focal point, and view up vector + # of the camera to compute the corresponding CV rotation matrix + pos = np.array(self.camera.GetPosition()) + focal = np.array(self.camera.GetFocalPoint()) + view = np.array(self.camera.GetViewUp()) + rot = self.compute_camera_rotation(pos, focal, view) + quat = rot.as_quat() + # make the external pose the same as the camera's pose + platform_pose_provider = PlatformPoseFixed( + np.array([0, 0, 0]), np.array([0, 0, 0, 1]) + ) + cm = StandardCamera( + self.res_x, + self.res_y, + self.kmat, + self.dist, + pos, + quat, + platform_pose_provider, + ) return cm class CameraPanTilt(Camera): - def __init__(self, res_x, res_y, vfov, pos, pan, tilt): + def __init__(self, camera, res_x, res_y, vfov, pos, pan, tilt): """Create camera. When pan and tilt are zero, the camera points north. @@ -406,137 +450,144 @@ def __init__(self, res_x, res_y, vfov, pos, pan, tilt): """ self._pan = pan self._tilt = tilt - self.set_rmat_from_pan_tilt() - super(CameraPanTilt, self).__init__(res_x, res_y, vfov, pos, - self._rmat) + self.set_rmat_from_pan_tilt(pan, tilt) + super(CameraPanTilt, self).__init__(camera, res_x, res_y, vfov, pos, self._rmat) @property def pan(self): - """Pan in degrees. - - """ + """Pan in degrees.""" return self._pan @pan.setter def pan(self, val): self._pan = val - self.set_rmat_from_pan_tilt() + self.set_rmat_from_pan_tilt(self._pan, self.tilt) @property def tilt(self): - """Tilt in degrees. - - """ + """Tilt in degrees.""" return self._tilt @tilt.setter def tilt(self, val): self._tilt = val - self.set_rmat_from_pan_tilt() - - def set_rmat_from_pan_tilt(self): - """Orientation rotation matrix. - - """ - tilt = self.tilt - pan = self.pan + self.set_rmat_from_pan_tilt(self.pan, self.tilt) - theta = tilt/180*np.pi + def set_rmat_from_pan_tilt(self, pan: float, tilt: float) -> Rotation: + """Return the orientation matrix given pan and tilt in degrees.""" + theta = np.deg2rad(tilt) c = np.cos(theta) s = np.sin(theta) - rx = np.array([[1,0,0],[0,c,-s],[0,s,c]]) + rx = np.array([[1, 0, 0], [0, c, -s], [0, s, c]]) - theta = pan/180*np.pi + theta = np.rad2deg(pan) c = np.cos(-theta) s = np.sin(-theta) - rz = np.array([[c,-s,0],[s,c,0],[0,0,1]]) + rz = np.array([[c, -s, 0], [s, c, 0], [0, 0, 1]]) - r1 = np.dot(rx, np.array([[1,0,0],[0,0,-1],[0,1,0]]).T).T + r1 = np.dot(rx, np.array([[1, 0, 0], [0, 0, -1], [0, 1, 0]]).T).T r = np.dot(rz, r1.T).T - self._rmat = r - - -def render_distored_image(width, height, K, dist, cam_pos, R, model_reader, - return_depth=True, monitor_resolution=(1000, 1000), - clipping_range=[1, 2000], fill_holes=True): - """Render a view from a camera with distortion. - - """ + self.rmat = Rotation.from_matrix(r) + + +def render_distorted_image( + width, + height, + K, + dist, + cam_pos, + R, + model_reader, + return_depth=True, + monitor_resolution=(1000, 1000), + clipping_range=[1, 2000], + fill_holes=True, +): + """Render a view from a camera with distortion.""" render_resolution = list(monitor_resolution) if monitor_resolution[0] != monitor_resolution[1]: - raise Exception('There is a bug when the monitor resolution isn\'t ' - 'square. Your actual monitor doesn\'t need to be ' - 'square, just pick the largest square resolution that ' - 'fits inside your monitor.') + raise Exception( + "There is a bug when the monitor resolution isn't " + "square. Your actual monitor doesn't need to be " + "square, just pick the largest square resolution that " + "fits inside your monitor." + ) # Generate points along the border of the distorted camera. num_points = 1000 - perimeter = 2*(height + width) - ds = num_points/float(perimeter) - xn = np.max([2, int(ds*width)]) - yn = np.max([2, int(ds*height)]) + perimeter = 2 * (height + width) + ds = num_points / float(perimeter) + xn = np.max([2, int(ds * width)]) + yn = np.max([2, int(ds * height)]) x = np.linspace(0, width, xn) y = np.linspace(0, height, yn)[1:-1] - pts = np.vstack([np.hstack([x, np.full(len(y), width, dtype=np.float64), - x[::-1], np.zeros(len(y))]), - np.hstack([np.zeros(xn), y, - np.full(xn, height, dtype=np.float64), - y[::-1]])]).T + pts = np.vstack( + [ + np.hstack( + [x, np.full(len(y), width, dtype=np.float64), x[::-1], np.zeros(len(y))] + ), + np.hstack( + [np.zeros(xn), y, np.full(xn, height, dtype=np.float64), y[::-1]] + ), + ] + ).T # Unproject these rays. - ray_dir = np.ones((len(pts), 3), dtype=np.float) + ray_dir = np.ones((len(pts), 3), dtype=np.float64) ray_dir0 = cv2.undistortPoints(np.expand_dims(pts, 0), K, dist, R=None) ray_dir[:, :2] = np.squeeze(ray_dir0) K_ = np.identity(3) - points2 = cv2.projectPoints(ray_dir, np.zeros(3, dtype=np.float32), - np.zeros(3, dtype=np.float32), K_, None)[0] + points2 = cv2.projectPoints( + ray_dir, np.zeros(3, dtype=np.float32), np.zeros(3, dtype=np.float32), K_, None + )[0] points2 = np.squeeze(points2, 1).T # points2 are now in the distortion-free camera. if False: plt.plot(points2[0], points2[1]) - plt.plot([0, render_resolution[0], render_resolution[0], 0, 0], - [0, 0, render_resolution[1], render_resolution[1], 0]) + plt.plot( + [0, render_resolution[0], render_resolution[0], 0, 0], + [0, 0, render_resolution[1], render_resolution[1], 0], + ) r1 = np.abs(points2[0]).max() r2 = np.abs(points2[1]).max() - s1 = render_resolution[0]/2/r1 - s2 = render_resolution[1]/2/r2 - K_[0, 0] = K_[1, 1] = min([s1, s2])*0.98 + s1 = render_resolution[0] / 2 / r1 + s2 = render_resolution[1] / 2 / r2 + K_[0, 0] = K_[1, 1] = min([s1, s2]) * 0.98 if s1 > s2: - render_resolution[0] = int(np.ceil(render_resolution[1]*r1/r2)) + render_resolution[0] = int(np.ceil(render_resolution[1] * r1 / r2)) else: - render_resolution[1] = int(np.ceil(render_resolution[0]*r2/r1)) - - K_[0, 2] = render_resolution[0]/2 - K_[1, 2] = render_resolution[1]/2 - - vfov = np.arctan(render_resolution[1]/2/K_[1, 1])*2*180/np.pi - vtk_camera = Camera(render_resolution[0], render_resolution[1], vfov, - cam_pos, R) - - img = vtk_camera.render_image(model_reader, clipping_range=clipping_range, - diffuse=0.6, ambient=0.6, specular=0.1, - light_color=[1.0, 1.0, 1.0], - light_pos=[0, 0, 1000]) - - #img = cv2.resize(img, tuple(render_resolution)) + render_resolution[1] = int(np.ceil(render_resolution[0] * r2 / r1)) + + K_[0, 2] = render_resolution[0] / 2 + K_[1, 2] = render_resolution[1] / 2 + + vfov = np.arctan(render_resolution[1] / 2 / K_[1, 1]) * 2 * 180 / np.pi + camera = vtk.vtkCamera() + vtk_camera = Camera( + camera, render_resolution[0], render_resolution[1], vfov, cam_pos, R + ) + + img = vtk_camera.render_image( + model_reader, + clipping_range=clipping_range, + diffuse=0.6, + ambient=0.6, + specular=0.1, + light_color=[1.0, 1.0, 1.0], + light_pos=[0, 0, 1000], + ) if return_depth or fill_holes: - ret = vtk_camera.unproject_view(model_reader, - clipping_range=clipping_range) + ret = vtk_camera.unproject_view(model_reader, clipping_range=clipping_range) E, N, U, depth = ret - #depth = cv2.resize(depth, tuple(render_resolution)) - - #plt.figure(); plt.imshow(img) - - #plt.figure(); plt.imshow(real_image) # Warp the rendered view back to the original, possibly distorted, camera # view. @@ -544,16 +595,21 @@ def render_distored_image(width, height, K, dist, cam_pos, R, model_reader, # These are the pixel coordinates for the centers of all the pixels in the # image of size img.shape, which we will scale up to the pixel coordinates # for those same locations in the image of size (height, width). - x = (np.arange(img.shape[1]) + 0.5)*width/img.shape[1] - y = (np.arange(img.shape[0]) + 0.5)*height/img.shape[0] + x = (np.arange(img.shape[1]) + 0.5) * width / img.shape[1] + y = (np.arange(img.shape[0]) + 0.5) * height / img.shape[0] X, Y = np.meshgrid(x, y) points = np.vstack([X.ravel(), Y.ravel()]) ray_dir = cv2.undistortPoints(np.expand_dims(points.T, 0), K, dist, None) ray_dir = np.squeeze(ray_dir).astype(np.float32).T ray_dir = np.vstack([ray_dir, np.ones(ray_dir.shape[1])]) - points2 = cv2.projectPoints(ray_dir.T, np.zeros(3, dtype=np.float32), - np.zeros(3, dtype=np.float32), K_, None)[0] + points2 = cv2.projectPoints( + ray_dir.T, + np.zeros(3, dtype=np.float32), + np.zeros(3, dtype=np.float32), + K_, + None, + )[0] points2 = np.squeeze(points2, 1).T X2 = np.reshape(points2[0], X.shape).astype(np.float32) Y2 = np.reshape(points2[1], Y.shape).astype(np.float32) @@ -575,9 +631,9 @@ def render_distored_image(width, height, K, dist, cam_pos, R, model_reader, # Holes that extend to the edge of the image won't be filled via # inpainting. - - output = cv2.connectedComponentsWithStats(hole_mask.astype(np.uint8), - 8, cv2.CV_32S) + output = cv2.connectedComponentsWithStats( + hole_mask.astype(np.uint8), 8, cv2.CV_32S + ) labels = output[1] # Remove components that touch outer boundary. @@ -596,8 +652,7 @@ def render_distored_image(width, height, K, dist, cam_pos, R, model_reader, X = cv2.inpaint(X.astype(np.float32), mask, 3, cv2.INPAINT_NS) Y = cv2.inpaint(Y.astype(np.float32), mask, 3, cv2.INPAINT_NS) Z = cv2.inpaint(Z.astype(np.float32), mask, 3, cv2.INPAINT_NS) - depth = cv2.inpaint(depth.astype(np.float32), mask, 3, - cv2.INPAINT_NS) + depth = cv2.inpaint(depth.astype(np.float32), mask, 3, cv2.INPAINT_NS) if return_depth: return img, depth, X, Y, Z @@ -610,18 +665,17 @@ def load_world_model(fname): """ :param fname: Path to .stl or .ply file. :type fname: str - """ ext = os.path.splitext(fname)[-1] - if ext == '.stl': + if ext == ".stl": model_reader = vtk.vtkSTLReader() - elif ext == '.ply': + elif ext == ".ply": model_reader = vtk.vtkPLYReader() - elif ext == '.obj': + elif ext == ".obj": model_reader = vtk.vtkOBJReader() else: - raise Exception('Unhandled model extension: \'%s\'' % ext) + raise Exception("Unhandled model extension: '%s'" % ext) model_reader.SetFileName(fname) model_reader.Update() @@ -637,15 +691,15 @@ def get_azel_from_ray_dir(ray_dir, cam_pos): ray_dir /= np.atleast_2d(np.sqrt(np.sum(ray_dir**2, 1))).T azel = np.zeros((2, ray_dir.shape[1])) azel[0] = np.arctan2(ray_dir[0], ray_dir[1]) - azel[1] = np.arctan(ray_dir[2]/np.sqrt(ray_dir[0]**2 + ray_dir[1]**2)) + azel[1] = np.arctan(ray_dir[2] / np.sqrt(ray_dir[0] ** 2 + ray_dir[1] ** 2)) return azel def get_ray_dir_from_azel(azel): azel = np.atleast_2d(azel) - azel.shape = (2,-1) + azel.shape = (2, -1) ray_dir = np.zeros((3, azel.shape[1])) - ray_dir[0] = np.sin(azel[0])*np.cos(azel[1]) - ray_dir[1] = np.cos(azel[0])*np.cos(azel[1]) + ray_dir[0] = np.sin(azel[0]) * np.cos(azel[1]) + ray_dir[1] = np.cos(azel[0]) * np.cos(azel[1]) ray_dir[2] = np.sin(azel[1]) return ray_dir From d8db3d64d8dd2ccfe83a77e080ea503a9b3e6cec Mon Sep 17 00:00:00 2001 From: Adam Romlein Date: Mon, 31 Mar 2025 11:00:32 -0400 Subject: [PATCH 16/20] Update keypoint UI, move camera models more to Rotation --- kamera/colmap_processing/camera_models.py | 72 +++++++++++++++++------ kamera/keypoint_server/app.py | 16 +++-- 2 files changed, 66 insertions(+), 22 deletions(-) diff --git a/kamera/colmap_processing/camera_models.py b/kamera/colmap_processing/camera_models.py index 4a45afc..dc745ae 100644 --- a/kamera/colmap_processing/camera_models.py +++ b/kamera/colmap_processing/camera_models.py @@ -5,6 +5,7 @@ import time import yaml from scipy.interpolate import RectBivariateSpline +from scipy.spatial.transform import Rotation import PIL from math import sqrt @@ -278,6 +279,7 @@ def __init__(self, width, height, platform_pose_provider=None): self._platform_pose_provider = platform_pose_provider self._depth_map = None + self.model_type = "standard" @property def width(self): @@ -613,11 +615,11 @@ def ifov(self, t=None): cx = self.width / 2 cy = self.height / 2 ray1 = self.unproject([cx, cy], t)[1] - ray1 /= np.sqrt(np.sum(ray1 ** 2, 0)) + ray1 /= np.sqrt(np.sum(ray1**2, 0)) ray2 = self.unproject([cx, cy + 1], t)[1] - ray2 /= np.sqrt(np.sum(ray2 ** 2, 0)) + ray2 /= np.sqrt(np.sum(ray2**2, 0)) ray3 = self.unproject([cx + 1, cy], t)[1] - ray3 /= np.sqrt(np.sum(ray3 ** 2, 0)) + ray3 /= np.sqrt(np.sum(ray3**2, 0)) ifovx = np.arccos(np.dot(ray1.ravel(), ray3.ravel())) ifovy = np.arccos(np.dot(ray1.ravel(), ray2.ravel())) @@ -643,21 +645,21 @@ def fov(self, t=None): cy = self.height / 2 ray1 = self.unproject([cx, 0], t)[1] - ray1 /= np.sqrt(np.sum(ray1 ** 2, 0)) + ray1 /= np.sqrt(np.sum(ray1**2, 0)) ray2 = self.unproject([cx, self.height], t)[1] - ray2 /= np.sqrt(np.sum(ray2 ** 2, 0)) + ray2 /= np.sqrt(np.sum(ray2**2, 0)) fov_v = np.arccos(np.dot(ray1.ravel(), ray2.ravel())) * 180 / np.pi ray1 = self.unproject([0, cy], t)[1] - ray1 /= np.sqrt(np.sum(ray1 ** 2, 0)) + ray1 /= np.sqrt(np.sum(ray1**2, 0)) ray2 = self.unproject([self.width, cy], t)[1] - ray2 /= np.sqrt(np.sum(ray2 ** 2, 0)) + ray2 /= np.sqrt(np.sum(ray2**2, 0)) fov_h = np.arccos(np.dot(ray1.ravel(), ray2.ravel())) * 180 / np.pi ray1 = self.unproject([0, 0], t)[1] - ray1 /= np.sqrt(np.sum(ray1 ** 2, 0)) + ray1 /= np.sqrt(np.sum(ray1**2, 0)) ray2 = self.unproject([self.width, self.height], t)[1] - ray2 /= np.sqrt(np.sum(ray2 ** 2, 0)) + ray2 /= np.sqrt(np.sum(ray2**2, 0)) fov_d = np.arccos(np.dot(ray1.ravel(), ray2.ravel())) * 180 / np.pi return fov_h, fov_v, fov_d @@ -727,9 +729,10 @@ def __init__( self._cam_quat = np.array(cam_quat, dtype=np.float64) self._cam_quat /= np.linalg.norm(self._cam_quat) self._min_ray_cos = None + self.model_type = "standard" def __str__(self): - string = ["model_type: standard\n"] + string = [f"model_type: {self.model_type}\n"] string.append(super(StandardCamera, self).__str__()) string.append("\n") string.append("".join(["fx: ", repr(self._K[0, 0]), "\n"])) @@ -815,7 +818,7 @@ def save_to_file(self, filename): "".join( [ "# The type of camera model.\n", - "model_type: standard\n\n", + f"model_type: {self.model_type}\n\n", "# Image dimensions\n", ] ) @@ -875,6 +878,29 @@ def save_to_file(self, filename): ) ) + def save_to_krtd(self, filename): + """Write a single camera in ASCII KRTD format to the file object. + + Args: + camera (list[np.ndarray]): A length-4 of type (K, R, t, d) + fout (str | os.PathLike): _description_ + """ + K = self.K + R = Rotation.from_quat(self.cam_quat).as_matrix() + t = self.cam_pos + d = self.dist + t = np.reshape(np.array(t), 3) + with open(filename, "w") as fout: + fout.write("%.12g %.12g %.12g\n" % tuple(K.tolist()[0])) + fout.write("%.12g %.12g %.12g\n" % tuple(K.tolist()[1])) + fout.write("%.12g %.12g %.12g\n\n" % tuple(K.tolist()[2])) + fout.write("%.12g %.12g %.12g\n" % tuple(R.tolist()[0])) + fout.write("%.12g %.12g %.12g\n" % tuple(R.tolist()[1])) + fout.write("%.12g %.12g %.12g\n\n" % tuple(R.tolist()[2])) + fout.write("%.12g %.12g %.12g\n\n" % tuple(t.tolist())) + for v in d: + fout.write("%.12g " % v) + @property def K(self): return self._K @@ -966,6 +992,10 @@ def dist(self, value): def cam_pos(self): return self._cam_pos + @cam_pos.setter + def cam_pos(self, value): + self._cam_pos = value + @property def cam_quat(self): return self._cam_quat @@ -1081,8 +1111,6 @@ def unproject(self, points, t=None, normalize_ray_dir=True): t = time.time() ins_pos, ins_quat = self.platform_pose_provider.pose(t) - # print('ins_pos', ins_pos) - # print('ins_quat', ins_quat) # Unproject rays into the camera coordinate system. ray_dir = np.ones((3, points.shape[1]), dtype=points.dtype) @@ -1091,8 +1119,9 @@ def unproject(self, points, t=None, normalize_ray_dir=True): ) ray_dir[:2] = np.squeeze(ray_dir0, 1).T + R_cam_to_world = Rotation.from_quat(self._cam_quat).as_matrix() # Rotate rays into the navigation coordinate system. - ray_dir = np.dot(quaternion_matrix(self._cam_quat)[:3, :3], ray_dir) + ray_dir = np.dot(R_cam_to_world, ray_dir) # Translate ray positions into their navigation coordinate system # definition. @@ -1102,7 +1131,7 @@ def unproject(self, points, t=None, normalize_ray_dir=True): ray_pos[2] = self._cam_pos[2] # Rotate and translate rays into the world coordinate system. - R_ins_to_world = quaternion_matrix(ins_quat)[:3, :3] + R_ins_to_world = Rotation.from_quat(ins_quat).as_matrix() ray_dir = np.dot(R_ins_to_world, ray_dir) ray_pos = np.dot(R_ins_to_world, ray_pos) + np.atleast_2d(ins_pos).T @@ -1413,6 +1442,7 @@ def __init__( platform_pose_provider=platform_pose_provider, ) self._depth_map = depth_map + self.model_type = "depth" @classmethod def load_from_file(cls, filename, platform_pose_provider=None): @@ -1439,7 +1469,15 @@ def load_from_file(cls, filename, platform_pose_provider=None): cam_quat = calib["camera_quaternion"] cam_pos = calib["camera_position"] - return cls(width, height, K, dist, cam_pos, cam_quat, platform_pose_provider) + depth_map_fname = "%s_depth_map.tif" % os.path.splitext(filename)[0] + try: + depth_map = np.asarray(PIL.Image.open(depth_map_fname)) + except OSError: + depth_map = None + + return cls( + width, height, K, dist, cam_pos, cam_quat, depth_map, platform_pose_provider + ) def save_to_file(self, filename, save_depth_viz=True): """See base class Camera documentation.""" @@ -1517,7 +1555,7 @@ def save_to_file(self, filename, save_depth_viz=True): if save_depth_viz: depth_viz_fname = ( - "%s/depth_vizualization.png" % os.path.split(filename)[0] + "%s/depth_vizualization.png" % os.path.splitext(filename)[0] ) self.save_depth_viz(depth_viz_fname) diff --git a/kamera/keypoint_server/app.py b/kamera/keypoint_server/app.py index c088b2e..9b36381 100644 --- a/kamera/keypoint_server/app.py +++ b/kamera/keypoint_server/app.py @@ -1,17 +1,21 @@ +import argparse +import bottle import json import os -import argparse +import pathlib from bottle import route, template, run, static_file, request, BaseRequest BaseRequest.MEMFILE_MAX = 6 * 2048 * 2048 image_dir = "" -left_img_file = "./kamera_calibration_fl09_C_20240612_204041.621432_rgb.jpg" -right_img_file = "./kamera_calibration_fl09_C_20240612_204041.621432_ir.png" +left_img_file = "./original.png" +right_img_file = "./reference.png" @route("/") def index(): + dir = os.path.dirname(__file__) + bottle.TEMPLATE_PATH.insert(0, dir) return template("keypoint.tpl") @@ -42,14 +46,16 @@ def set_left_img_file(): @route("/image/left") def left_image(): - resp = static_file(left_img_file, root=image_dir) + left_img = pathlib.Path(left_img_file) + resp = static_file(left_img.name, root=left_img.parent) resp.set_header("Cache-Control", "no-store") return resp @route("/image/right") def right_image(): - resp = static_file(right_img_file, root=image_dir) + right_img = pathlib.Path(right_img_file) + resp = static_file(right_img.name, root=right_img.parent) resp.set_header("Cache-Control", "no-store") return resp From a2d72105dde6a4d885a030ef151b50b9eaa1c8c3 Mon Sep 17 00:00:00 2001 From: Adam Romlein Date: Mon, 31 Mar 2025 11:00:53 -0400 Subject: [PATCH 17/20] Ignore egg --- .gitignore | 1 + 1 file changed, 1 insertion(+) diff --git a/.gitignore b/.gitignore index 82b8e5c..ef19327 100644 --- a/.gitignore +++ b/.gitignore @@ -6,3 +6,4 @@ build devel provision/ansible/.password .catkin_tools +kamera.egg-info From fa4641ed5a48742c2e50449643adeb54d0fe9b27 Mon Sep 17 00:00:00 2001 From: Adam Romlein Date: Fri, 20 Jun 2025 13:49:24 -0400 Subject: [PATCH 18/20] Minor bugfixes to the calibration process --- kamera/postflight/alignment.py | 30 +++++++---------- kamera/postflight/colmap.py | 43 +++++++++++++++--------- kamera/postflight/scripts/calibration.py | 11 +++--- 3 files changed, 45 insertions(+), 39 deletions(-) diff --git a/kamera/postflight/alignment.py b/kamera/postflight/alignment.py index ea6eefb..bfcb492 100644 --- a/kamera/postflight/alignment.py +++ b/kamera/postflight/alignment.py @@ -717,33 +717,30 @@ def transfer_alignment( wrld_pts = ray_dir.T * 1e4 assert np.all(np.isfinite(wrld_pts)), "World points contain non-finite values." - if colmap_camera.model == "OPENCV": - fx, fy, cx, cy, d1, d2, d3, d4 = colmap_camera.params - elif colmap_camera.model == "PINHOLE": - fx, fy, cx, cy = colmap_camera.params - d1 = d2 = d3 = d4 = 0 - K = colmap_camera.calibration_matrix() if colmap_camera.model.name == "OPENCV": fx, fy, cx, cy, d1, d2, d3, d4 = colmap_camera.params elif colmap_camera.model.name == "SIMPLE_RADIAL": - d1 = d2 = d3 = d4 = 0 - elif colmap_camera.model.name == "PINHOLE": + f, cx, cy, d1 = colmap_camera.params + fx = fy = f + d2 = d3 = d4 = 0 + elif colmap_camera.model == "PINHOLE": + fx, fy, cx, cy = colmap_camera.params d1 = d2 = d3 = d4 = 0 else: raise SystemError(f"Unexpected camera model found: {colmap_camera.model.name}") - dist = np.array([d1, d2, d3, d4]) + dist = np.array([d1, d2, d3, d4, 0]) flags = cv2.CALIB_ZERO_TANGENT_DIST flags = flags | cv2.CALIB_USE_INTRINSIC_GUESS flags = flags | cv2.CALIB_FIX_PRINCIPAL_POINT # Optionally, fix the K intrinsics - # flags = flags | cv2.CALIB_FIX_K1 - # flags = flags | cv2.CALIB_FIX_K2 - # flags = flags | cv2.CALIB_FIX_K3 - # flags = flags | cv2.CALIB_FIX_K4 - # flags = flags | cv2.CALIB_FIX_K5 - # flags = flags | cv2.CALIB_FIX_K6 + flags = flags | cv2.CALIB_FIX_K1 + flags = flags | cv2.CALIB_FIX_K2 + flags = flags | cv2.CALIB_FIX_K3 + flags = flags | cv2.CALIB_FIX_K4 + flags = flags | cv2.CALIB_FIX_K5 + flags = flags | cv2.CALIB_FIX_K6 criteria = ( cv2.TERM_CRITERIA_EPS + cv2.TERM_CRITERIA_MAX_ITER, @@ -751,9 +748,6 @@ def transfer_alignment( 0.0000001, ) - print(len(wrld_pts)) - print(len(im_pts)) - ret = cv2.calibrateCamera( [wrld_pts.astype(np.float32)], [im_pts.astype(np.float32)], diff --git a/kamera/postflight/colmap.py b/kamera/postflight/colmap.py index 32aa0f6..3bd2b16 100644 --- a/kamera/postflight/colmap.py +++ b/kamera/postflight/colmap.py @@ -40,12 +40,15 @@ class ColmapCalibrationData: class ColmapCalibration(object): def __init__( - self, flight_dir: str | os.PathLike, colmap_dir: str | os.PathLike + self, flight_dir: str | os.PathLike, + recon_dir: str | os.PathLike, + colmap_dir: str | os.PathLike ) -> None: self.flight_dir = flight_dir + self.recon_dir = recon_dir self.colmap_dir = colmap_dir # contains the images, 3D points, and cameras of the colmap database - self.R = pc.Reconstruction(self.colmap_dir) + self.R = pc.Reconstruction(self.recon_dir) self.ccd = ColmapCalibrationData self.nav_state_provider = self.load_nav_state_provider() print(self.R.summary()) @@ -86,13 +89,13 @@ def get_view(self, fname: str | os.PathLike) -> str: """Extract view (e.g. left_view, right_view, center_view) from a given kamera filename""" base = osp.basename(fname) - channel = base.split("_")[3] + channel = base.split("_") view = "null" - if channel == "C": + if "C" in channel: view = "center_view" - elif channel == "L": + elif "L" in channel: view = "left_view" - elif channel == "R": + elif "R" in channel: view = "right_view" return view @@ -320,7 +323,7 @@ def write_gifs( f"and {colocated_camera_name}." ) ub.ensuredir(gif_dir) - + img_fnames = self.ccd.img_fnames for k in range(num_gifs): inds = list(range(len(img_fnames))) @@ -330,10 +333,9 @@ def write_gifs( fname = img_fnames[inds[i]] if osp.basename(osp.dirname(fname)) != camera_name: continue - view = self.get_view(fname) try: bname = osp.basename(fname) - abs_fname = osp.join(self.flight_dir, view, bname) + abs_fname = osp.join(self.colmap_dir, "images0", camera_name, bname) img = cv2.imread(abs_fname, cv2.IMREAD_COLOR)[:, :, ::-1] except Exception as e: print(f"No {modality} image found at path {abs_fname}") @@ -404,12 +406,12 @@ def write_gifs( ) def align_model(self, output_dir: str | os.PathLike) -> None: - img_fnames = [im.name for im in self.R.images().values()] + img_fnames = [im.name for im in self.R.images.values()] points = [] ins_poses = [] for image_name in img_fnames: base_name = self.get_base_name(image_name) - t = self.basename_to_time[base_name] + t = self.ccd.basename_to_time[base_name] # Query the navigation state recorded by the INS for this time. pose = self.nav_state_provider.pose(t) ins_poses.append(pose) @@ -483,12 +485,18 @@ def find_best_sparse_model(sparse_dir: str | os.PathLike): best_model = "" most_images_aligned = 0 for subdir in all_models: - R = pc.Reconstruction(subdir) + dir = os.path.join(sparse_dir, subdir) + try: + R = pc.Reconstruction(dir) + except Exception as e: + print(e) + continue num_images = len(R.images.keys()) - print(f"Number of images in {subdir}: {num_images}") + print(f"Number of images in {dir}: {num_images}") if num_images > most_images_aligned: - best_model = subdir - print(f"Selecting {subdir} as the best model.") + most_images_aligned = num_images + best_model = dir + print(f"Selecting {best_model} as the best model.") return best_model @@ -497,7 +505,10 @@ def main(): colmap_dir = ( "/home/local/KHQ/adam.romlein/noaa/data/2024_AOC_AK_Calibration/fl09/colmap_ir" ) - cc = ColmapCalibration(flight_dir, colmap_dir) + recon_dir = ( + "/home/local/KHQ/adam.romlein/noaa/data/2024_AOC_AK_Calibration/fl09/colmap_ir/aligned/0" + ) + cc = ColmapCalibration(flight_dir, recon_dir, colmap_dir) cc.calibrate_ir() diff --git a/kamera/postflight/scripts/calibration.py b/kamera/postflight/scripts/calibration.py index 5412384..acb09ab 100644 --- a/kamera/postflight/scripts/calibration.py +++ b/kamera/postflight/scripts/calibration.py @@ -20,7 +20,7 @@ def align_model( " assuming model is aligned." ) aligned_sparse_dir = os.path.join(align_dir, os.listdir(align_dir)[0]) - cc = ColmapCalibration(flight_dir, aligned_sparse_dir) + cc = ColmapCalibration(flight_dir, aligned_sparse_dir, colmap_dir) elif os.path.exists(align_dir) and len(os.listdir(align_dir) > 1): raise SystemError( f"{len(os.listdir(align_dir))} aligned models are present, only 1 should exist in {align_dir}." @@ -38,7 +38,8 @@ def align_model( # Step 2: Align and save this model aligned_sparse_dir = os.path.join(align_dir, sparse_idx) ub.ensuredir(aligned_sparse_dir) - cc = ColmapCalibration(flight_dir, best_reconstruction_dir) + cc = ColmapCalibration(flight_dir, best_reconstruction_dir, colmap_dir) + cc.prepare_calibration_data() cc.align_model(aligned_sparse_dir) return cc @@ -46,7 +47,7 @@ def align_model( def main(): # REQUIREMENTS: Must already have built a reasonable 3-D model using Colmap # And have a flight directory populated by the kamera system - flight_dir = "/home/local/KHQ/adam.romlein/noaa/data/2024_AOC_AK_Calibration/fl09" + flight_dir = "/home/local/KHQ/adam.romlein/noaa/data/052025_Calibration/" colmap_dir = os.path.join(flight_dir, "colmap") # Location to save KAMERA camera models. save_dir = os.path.join(flight_dir, "kamera_models") @@ -62,7 +63,7 @@ def main(): # in the same folder calibrate_ir = True # open the point clicking UI to refine IR calibration? - refine_ir = True + refine_ir = False # Step 1: Make sure the model is aligned to the INS readings, if not, # find the best model and align it. @@ -154,6 +155,7 @@ def main(): # IR calibration generally happens in a separate model, since SIFT has a hard # time matching between EO and long-wave IR + ir_cameras_refined = 0 if calibrate_ir: ir_colmap_dir = os.path.join(flight_dir, "colmap_ir") ir_align_dir = os.path.join(ir_colmap_dir, "aligned") @@ -192,7 +194,6 @@ def main(): else: print(f"Calibrating camera {camera_str} failed.") - ir_cameras_refined = 0 if refine_ir: # need to define a points per modality/view pair ir_points_json = pathlib.Path( From 154491d0f63bef05070ed232c7d705245cc109c5 Mon Sep 17 00:00:00 2001 From: romleiaj Date: Mon, 29 Dec 2025 11:25:38 -0500 Subject: [PATCH 19/20] Migrate to UV / conda env from poetry for GDAL, update docker images and README accordingly. --- .gitignore | 3 + README.md | 61 +- docker/core.dockerfile | 6 +- docker/gui.dockerfile | 5 +- docker/kamerapy.dockerfile | 14 +- environment.yml | 45 ++ poetry.lock | 1414 ------------------------------------ pyproject.toml | 113 ++- requirements.txt | 18 - setup.py | 19 +- 10 files changed, 217 insertions(+), 1481 deletions(-) create mode 100644 environment.yml delete mode 100644 poetry.lock delete mode 100644 requirements.txt diff --git a/.gitignore b/.gitignore index ef19327..7b23ff9 100644 --- a/.gitignore +++ b/.gitignore @@ -7,3 +7,6 @@ devel provision/ansible/.password .catkin_tools kamera.egg-info +# uv lock file (optional, but can be committed for reproducible builds) +uv.lock +**.DS_Store diff --git a/README.md b/README.md index 09aa463..214a69c 100644 --- a/README.md +++ b/README.md @@ -22,20 +22,69 @@ KAMERA, or the **K**nowledge-guided Image **A**cquisition **M**anag**ER** and ** ## Installation +### Recommended: Micromamba (Cross-Platform) + +For best cross-platform support, especially for GDAL and pycolmap: + +1. **Install micromamba**: + ```bash + # Linux/macOS + curl -Ls https://micro.mamba.pm/api/micromamba/linux-64/latest | tar -xvj bin/micromamba + + # Windows: See https://mamba.readthedocs.io/en/latest/installation/micromamba-installation.html + ``` + +2. **Create environment** (uses conda-forge only): + ```bash + git clone https://github.com/Kitware/kamera.git + cd kamera + micromamba env create -f environment.yml + micromamba activate kamera + pip install -e . + ``` + + This automatically handles GDAL and pycolmap cross-platform without any platform-specific setup. + +### Alternative: Pip/uv Installation + +If you prefer pip-only installation (Linux/MacOS only): + +1. **Install uv** (fast Python package manager): + ```bash + # Linux/macOS + curl -LsSf https://astral.sh/uv/install.sh | sh + ``` + +2. **Install the package**: + ```bash + git clone https://github.com/Kitware/kamera.git + cd kamera + uv pip install -e . + ``` + + **Platform-specific notes:** + - **Linux**: GDAL via system packages: `sudo apt-get install libgdal-dev python3-gdal` + - **macOS**: Install GDAL: `brew install gdal` + +3. **Lint code** (optional): + ```bash + uv pip install ruff + ruff check . + ``` + +### Docker Images + ```bash -git clone https://github.com/Kitware/kamera.git -cd kamera -# For the pure post-processing and generating flight summary, you can install -# the requirements in requirements.txt, or use the provided dockerfile +# For the pure post-processing and generating flight summary make postflight -# Builds the core docker images for use in the onboard sytems +# Builds the core docker images for use in the onboard systems make nuvo # if using VIAME for the DL detectors make viame # if using the real-time GUI make gui ``` -Note that these images take up a large amount of disk space, especially the VIAME image which is 30Gb, and it can take several hours to builds. The core images are faster and lighter weight. +Note that these images take up a large amount of disk space, especially the VIAME image which is 30Gb, and it can take several hours to build. The core images are faster and lighter weight. ## Partners and Acknowledgements KAMERA was developed in collaboration with: diff --git a/docker/core.dockerfile b/docker/core.dockerfile index 0a95cef..5a3ad35 100644 --- a/docker/core.dockerfile +++ b/docker/core.dockerfile @@ -5,10 +5,14 @@ FROM kamera/base/core-deps:latest COPY . /root/kamera WORKDIR /root/kamera +# Install uv for Python package management +COPY --from=ghcr.io/astral-sh/uv:latest /uv /usr/local/bin/uv + # use the exec form of run because we need bash syntax RUN [ "/bin/bash", "-c", "source /entry/project.sh && catkin build -s backend"] # python package is currently only supported for python3.10+, not on ubuntu20.04 -# RUN [ "/bin/bash", "-c", "pip install ."] +# When Python 3.10+ is available, uncomment: +# RUN [ "/bin/bash", "-c", "uv pip install --system -e ."] diff --git a/docker/gui.dockerfile b/docker/gui.dockerfile index 02be9e3..b3e8b8e 100644 --- a/docker/gui.dockerfile +++ b/docker/gui.dockerfile @@ -37,9 +37,12 @@ RUN find /home/user -not -user user -execdir chown user {} \+ # use the exec form of run because we need bash syntax USER user +# Install uv for Python package management +COPY --from=ghcr.io/astral-sh/uv:latest /uv /usr/local/bin/uv + RUN [ "/bin/bash", "-c", "source /entry/project.sh && catkin build wxpython_gui "] RUN [ "/bin/bash", "-c", "source /entry/project.sh && catkin build ins_driver "] -RUN [ "/bin/bash", "-c", "pip install -e ."] +RUN [ "/bin/bash", "-c", "uv pip install --system -e ."] USER root RUN find /home/user -not -user user -execdir chown user {} \+ USER user diff --git a/docker/kamerapy.dockerfile b/docker/kamerapy.dockerfile index e00f1bf..2691ef3 100644 --- a/docker/kamerapy.dockerfile +++ b/docker/kamerapy.dockerfile @@ -8,13 +8,19 @@ RUN apt-get update && apt-get install -yq \ libxext6 \ redis \ dnsutils \ - gdal-bin + gdal-bin \ + curl \ + && rm -rf /var/lib/apt/lists/* -RUN pip install --upgrade pip -RUN pip install setuptools==57.0.0 +# Install uv +COPY --from=ghcr.io/astral-sh/uv:latest /uv /usr/local/bin/uv COPY ./ /src/kamera WORKDIR /src/kamera -RUN pip install -e . + +# Install kamera package using uv +# Note: GDAL is handled via system package (python3-gdal) on Linux +# For Windows, use: uv pip install -e .[windows] +RUN uv pip install --system -e . ENTRYPOINT ["bash"] diff --git a/environment.yml b/environment.yml new file mode 100644 index 0000000..918af0b --- /dev/null +++ b/environment.yml @@ -0,0 +1,45 @@ +name: kamera +channels: + - conda-forge +dependencies: + # Python version + - python>=3.10,<3.12 + + # Core scientific computing + - numpy>=2.1.1 + - scipy>=1.14.1 + - matplotlib>=3.9.2 + + # Image processing + - opencv>=4.10.0 + - pillow>=10.4.0 + + # Geospatial libraries (conda-forge is best for cross-platform support) + - gdal>=3.9.2 # Cross-platform GDAL with all drivers + - shapely>=2.0.6 + + # Computer vision / 3D reconstruction + - pycolmap>=3.13.0 # Pre-built binaries work cross-platform + # Note: If you encounter Qt5/Qt6 conflicts, run: ./fix_qt_conflict.sh + # or manually remove Qt6: micromamba remove qt-main qt6-* -n kamera + + # Utilities + - pyyaml>=6.0.2 + - rich>=13.9.1 + + # Pip-only packages (install via pip after conda) + # These packages are not available in conda-forge or are better maintained on PyPI + - pip + - pip: + - pygeodesy>=24.9.29 + - pyshp>=2.3.1 + - simplekml>=1.3.6 + - transformations>=2024.5.24 + - scriptconfig>=0.8.0 + - ubelt>=1.3.6 + - exifread>=3.0.0 + - ipdb>=0.13.13 + - bottle>=0.13.2 + # After creating this environment, install the kamera package itself: + # pip install -e . (from the project root directory) + diff --git a/poetry.lock b/poetry.lock deleted file mode 100644 index a2d0a89..0000000 --- a/poetry.lock +++ /dev/null @@ -1,1414 +0,0 @@ -# This file is automatically @generated by Poetry 1.8.3 and should not be changed by hand. - -[[package]] -name = "asttokens" -version = "2.4.1" -description = "Annotate AST trees with source code positions" -optional = false -python-versions = "*" -files = [ - {file = "asttokens-2.4.1-py2.py3-none-any.whl", hash = "sha256:051ed49c3dcae8913ea7cd08e46a606dba30b79993209636c4875bc1d637bc24"}, - {file = "asttokens-2.4.1.tar.gz", hash = "sha256:b03869718ba9a6eb027e134bfdf69f38a236d681c83c160d510768af11254ba0"}, -] - -[package.dependencies] -six = ">=1.12.0" - -[package.extras] -astroid = ["astroid (>=1,<2)", "astroid (>=2,<4)"] -test = ["astroid (>=1,<2)", "astroid (>=2,<4)", "pytest"] - -[[package]] -name = "bottle" -version = "0.13.2" -description = "Fast and simple WSGI-framework for small web-applications." -optional = false -python-versions = "*" -files = [ - {file = "bottle-0.13.2-py2.py3-none-any.whl", hash = "sha256:27569ab8d1332fbba3e400b3baab2227ab4efb4882ff147af05a7c00ed73409c"}, - {file = "bottle-0.13.2.tar.gz", hash = "sha256:e53803b9d298c7d343d00ba7d27b0059415f04b9f6f40b8d58b5bf914ba9d348"}, -] - -[[package]] -name = "colorama" -version = "0.4.6" -description = "Cross-platform colored terminal text." -optional = false -python-versions = "!=3.0.*,!=3.1.*,!=3.2.*,!=3.3.*,!=3.4.*,!=3.5.*,!=3.6.*,>=2.7" -files = [ - {file = "colorama-0.4.6-py2.py3-none-any.whl", hash = "sha256:4f1d9991f5acc0ca119f9d443620b77f9d6b33703e51011c16baf57afb285fc6"}, - {file = "colorama-0.4.6.tar.gz", hash = "sha256:08695f5cb7ed6e0531a20572697297273c47b8cae5a63ffc6d6ed5c201be6e44"}, -] - -[[package]] -name = "contourpy" -version = "1.3.0" -description = "Python library for calculating contours of 2D quadrilateral grids" -optional = false -python-versions = ">=3.9" -files = [ - {file = "contourpy-1.3.0-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:880ea32e5c774634f9fcd46504bf9f080a41ad855f4fef54f5380f5133d343c7"}, - {file = "contourpy-1.3.0-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:76c905ef940a4474a6289c71d53122a4f77766eef23c03cd57016ce19d0f7b42"}, - {file = "contourpy-1.3.0-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:92f8557cbb07415a4d6fa191f20fd9d2d9eb9c0b61d1b2f52a8926e43c6e9af7"}, - {file = "contourpy-1.3.0-cp310-cp310-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:36f965570cff02b874773c49bfe85562b47030805d7d8360748f3eca570f4cab"}, - {file = "contourpy-1.3.0-cp310-cp310-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:cacd81e2d4b6f89c9f8a5b69b86490152ff39afc58a95af002a398273e5ce589"}, - {file = "contourpy-1.3.0-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:69375194457ad0fad3a839b9e29aa0b0ed53bb54db1bfb6c3ae43d111c31ce41"}, - {file = "contourpy-1.3.0-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:7a52040312b1a858b5e31ef28c2e865376a386c60c0e248370bbea2d3f3b760d"}, - {file = "contourpy-1.3.0-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:3faeb2998e4fcb256542e8a926d08da08977f7f5e62cf733f3c211c2a5586223"}, - {file = "contourpy-1.3.0-cp310-cp310-win32.whl", hash = "sha256:36e0cff201bcb17a0a8ecc7f454fe078437fa6bda730e695a92f2d9932bd507f"}, - {file = "contourpy-1.3.0-cp310-cp310-win_amd64.whl", hash = "sha256:87ddffef1dbe5e669b5c2440b643d3fdd8622a348fe1983fad7a0f0ccb1cd67b"}, - {file = "contourpy-1.3.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:0fa4c02abe6c446ba70d96ece336e621efa4aecae43eaa9b030ae5fb92b309ad"}, - {file = "contourpy-1.3.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:834e0cfe17ba12f79963861e0f908556b2cedd52e1f75e6578801febcc6a9f49"}, - {file = "contourpy-1.3.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:dbc4c3217eee163fa3984fd1567632b48d6dfd29216da3ded3d7b844a8014a66"}, - {file = "contourpy-1.3.0-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:4865cd1d419e0c7a7bf6de1777b185eebdc51470800a9f42b9e9decf17762081"}, - {file = "contourpy-1.3.0-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:303c252947ab4b14c08afeb52375b26781ccd6a5ccd81abcdfc1fafd14cf93c1"}, - {file = "contourpy-1.3.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:637f674226be46f6ba372fd29d9523dd977a291f66ab2a74fbeb5530bb3f445d"}, - {file = "contourpy-1.3.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:76a896b2f195b57db25d6b44e7e03f221d32fe318d03ede41f8b4d9ba1bff53c"}, - {file = "contourpy-1.3.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:e1fd23e9d01591bab45546c089ae89d926917a66dceb3abcf01f6105d927e2cb"}, - {file = "contourpy-1.3.0-cp311-cp311-win32.whl", hash = "sha256:d402880b84df3bec6eab53cd0cf802cae6a2ef9537e70cf75e91618a3801c20c"}, - {file = "contourpy-1.3.0-cp311-cp311-win_amd64.whl", hash = "sha256:6cb6cc968059db9c62cb35fbf70248f40994dfcd7aa10444bbf8b3faeb7c2d67"}, - {file = "contourpy-1.3.0-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:570ef7cf892f0afbe5b2ee410c507ce12e15a5fa91017a0009f79f7d93a1268f"}, - {file = "contourpy-1.3.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:da84c537cb8b97d153e9fb208c221c45605f73147bd4cadd23bdae915042aad6"}, - {file = "contourpy-1.3.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:0be4d8425bfa755e0fd76ee1e019636ccc7c29f77a7c86b4328a9eb6a26d0639"}, - {file = "contourpy-1.3.0-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:9c0da700bf58f6e0b65312d0a5e695179a71d0163957fa381bb3c1f72972537c"}, - {file = "contourpy-1.3.0-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:eb8b141bb00fa977d9122636b16aa67d37fd40a3d8b52dd837e536d64b9a4d06"}, - {file = "contourpy-1.3.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:3634b5385c6716c258d0419c46d05c8aa7dc8cb70326c9a4fb66b69ad2b52e09"}, - {file = "contourpy-1.3.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:0dce35502151b6bd35027ac39ba6e5a44be13a68f55735c3612c568cac3805fd"}, - {file = "contourpy-1.3.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:aea348f053c645100612b333adc5983d87be69acdc6d77d3169c090d3b01dc35"}, - {file = "contourpy-1.3.0-cp312-cp312-win32.whl", hash = "sha256:90f73a5116ad1ba7174341ef3ea5c3150ddf20b024b98fb0c3b29034752c8aeb"}, - {file = "contourpy-1.3.0-cp312-cp312-win_amd64.whl", hash = "sha256:b11b39aea6be6764f84360fce6c82211a9db32a7c7de8fa6dd5397cf1d079c3b"}, - {file = "contourpy-1.3.0-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:3e1c7fa44aaae40a2247e2e8e0627f4bea3dd257014764aa644f319a5f8600e3"}, - {file = "contourpy-1.3.0-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:364174c2a76057feef647c802652f00953b575723062560498dc7930fc9b1cb7"}, - {file = "contourpy-1.3.0-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:32b238b3b3b649e09ce9aaf51f0c261d38644bdfa35cbaf7b263457850957a84"}, - {file = "contourpy-1.3.0-cp313-cp313-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:d51fca85f9f7ad0b65b4b9fe800406d0d77017d7270d31ec3fb1cc07358fdea0"}, - {file = "contourpy-1.3.0-cp313-cp313-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:732896af21716b29ab3e988d4ce14bc5133733b85956316fb0c56355f398099b"}, - {file = "contourpy-1.3.0-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:d73f659398a0904e125280836ae6f88ba9b178b2fed6884f3b1f95b989d2c8da"}, - {file = "contourpy-1.3.0-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:c6c7c2408b7048082932cf4e641fa3b8ca848259212f51c8c59c45aa7ac18f14"}, - {file = "contourpy-1.3.0-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:f317576606de89da6b7e0861cf6061f6146ead3528acabff9236458a6ba467f8"}, - {file = "contourpy-1.3.0-cp313-cp313-win32.whl", hash = "sha256:31cd3a85dbdf1fc002280c65caa7e2b5f65e4a973fcdf70dd2fdcb9868069294"}, - {file = "contourpy-1.3.0-cp313-cp313-win_amd64.whl", hash = "sha256:4553c421929ec95fb07b3aaca0fae668b2eb5a5203d1217ca7c34c063c53d087"}, - {file = "contourpy-1.3.0-cp313-cp313t-macosx_10_13_x86_64.whl", hash = "sha256:345af746d7766821d05d72cb8f3845dfd08dd137101a2cb9b24de277d716def8"}, - {file = "contourpy-1.3.0-cp313-cp313t-macosx_11_0_arm64.whl", hash = "sha256:3bb3808858a9dc68f6f03d319acd5f1b8a337e6cdda197f02f4b8ff67ad2057b"}, - {file = "contourpy-1.3.0-cp313-cp313t-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:420d39daa61aab1221567b42eecb01112908b2cab7f1b4106a52caaec8d36973"}, - {file = "contourpy-1.3.0-cp313-cp313t-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:4d63ee447261e963af02642ffcb864e5a2ee4cbfd78080657a9880b8b1868e18"}, - {file = "contourpy-1.3.0-cp313-cp313t-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:167d6c890815e1dac9536dca00828b445d5d0df4d6a8c6adb4a7ec3166812fa8"}, - {file = "contourpy-1.3.0-cp313-cp313t-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:710a26b3dc80c0e4febf04555de66f5fd17e9cf7170a7b08000601a10570bda6"}, - {file = "contourpy-1.3.0-cp313-cp313t-musllinux_1_2_aarch64.whl", hash = "sha256:75ee7cb1a14c617f34a51d11fa7524173e56551646828353c4af859c56b766e2"}, - {file = "contourpy-1.3.0-cp313-cp313t-musllinux_1_2_x86_64.whl", hash = "sha256:33c92cdae89ec5135d036e7218e69b0bb2851206077251f04a6c4e0e21f03927"}, - {file = "contourpy-1.3.0-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:a11077e395f67ffc2c44ec2418cfebed032cd6da3022a94fc227b6faf8e2acb8"}, - {file = "contourpy-1.3.0-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:e8134301d7e204c88ed7ab50028ba06c683000040ede1d617298611f9dc6240c"}, - {file = "contourpy-1.3.0-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e12968fdfd5bb45ffdf6192a590bd8ddd3ba9e58360b29683c6bb71a7b41edca"}, - {file = "contourpy-1.3.0-cp39-cp39-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:fd2a0fc506eccaaa7595b7e1418951f213cf8255be2600f1ea1b61e46a60c55f"}, - {file = "contourpy-1.3.0-cp39-cp39-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:4cfb5c62ce023dfc410d6059c936dcf96442ba40814aefbfa575425a3a7f19dc"}, - {file = "contourpy-1.3.0-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:68a32389b06b82c2fdd68276148d7b9275b5f5cf13e5417e4252f6d1a34f72a2"}, - {file = "contourpy-1.3.0-cp39-cp39-musllinux_1_2_aarch64.whl", hash = "sha256:94e848a6b83da10898cbf1311a815f770acc9b6a3f2d646f330d57eb4e87592e"}, - {file = "contourpy-1.3.0-cp39-cp39-musllinux_1_2_x86_64.whl", hash = "sha256:d78ab28a03c854a873787a0a42254a0ccb3cb133c672f645c9f9c8f3ae9d0800"}, - {file = "contourpy-1.3.0-cp39-cp39-win32.whl", hash = "sha256:81cb5ed4952aae6014bc9d0421dec7c5835c9c8c31cdf51910b708f548cf58e5"}, - {file = "contourpy-1.3.0-cp39-cp39-win_amd64.whl", hash = "sha256:14e262f67bd7e6eb6880bc564dcda30b15e351a594657e55b7eec94b6ef72843"}, - {file = "contourpy-1.3.0-pp310-pypy310_pp73-macosx_10_15_x86_64.whl", hash = "sha256:fe41b41505a5a33aeaed2a613dccaeaa74e0e3ead6dd6fd3a118fb471644fd6c"}, - {file = "contourpy-1.3.0-pp310-pypy310_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:eca7e17a65f72a5133bdbec9ecf22401c62bcf4821361ef7811faee695799779"}, - {file = "contourpy-1.3.0-pp310-pypy310_pp73-win_amd64.whl", hash = "sha256:1ec4dc6bf570f5b22ed0d7efba0dfa9c5b9e0431aeea7581aa217542d9e809a4"}, - {file = "contourpy-1.3.0-pp39-pypy39_pp73-macosx_10_15_x86_64.whl", hash = "sha256:00ccd0dbaad6d804ab259820fa7cb0b8036bda0686ef844d24125d8287178ce0"}, - {file = "contourpy-1.3.0-pp39-pypy39_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:8ca947601224119117f7c19c9cdf6b3ab54c5726ef1d906aa4a69dfb6dd58102"}, - {file = "contourpy-1.3.0-pp39-pypy39_pp73-win_amd64.whl", hash = "sha256:c6ec93afeb848a0845a18989da3beca3eec2c0f852322efe21af1931147d12cb"}, - {file = "contourpy-1.3.0.tar.gz", hash = "sha256:7ffa0db17717a8ffb127efd0c95a4362d996b892c2904db72428d5b52e1938a4"}, -] - -[package.dependencies] -numpy = ">=1.23" - -[package.extras] -bokeh = ["bokeh", "selenium"] -docs = ["furo", "sphinx (>=7.2)", "sphinx-copybutton"] -mypy = ["contourpy[bokeh,docs]", "docutils-stubs", "mypy (==1.11.1)", "types-Pillow"] -test = ["Pillow", "contourpy[test-no-images]", "matplotlib"] -test-no-images = ["pytest", "pytest-cov", "pytest-rerunfailures", "pytest-xdist", "wurlitzer"] - -[[package]] -name = "cycler" -version = "0.12.1" -description = "Composable style cycles" -optional = false -python-versions = ">=3.8" -files = [ - {file = "cycler-0.12.1-py3-none-any.whl", hash = "sha256:85cef7cff222d8644161529808465972e51340599459b8ac3ccbac5a854e0d30"}, - {file = "cycler-0.12.1.tar.gz", hash = "sha256:88bb128f02ba341da8ef447245a9e138fae777f6a23943da4540077d3601eb1c"}, -] - -[package.extras] -docs = ["ipython", "matplotlib", "numpydoc", "sphinx"] -tests = ["pytest", "pytest-cov", "pytest-xdist"] - -[[package]] -name = "datetime" -version = "5.5" -description = "This package provides a DateTime data type, as known from Zope. Unless you need to communicate with Zope APIs, you're probably better off using Python's built-in datetime module." -optional = false -python-versions = ">=3.7" -files = [ - {file = "DateTime-5.5-py3-none-any.whl", hash = "sha256:0abf6c51cb4ba7cee775ca46ccc727f3afdde463be28dbbe8803631fefd4a120"}, - {file = "DateTime-5.5.tar.gz", hash = "sha256:21ec6331f87a7fcb57bd7c59e8a68bfffe6fcbf5acdbbc7b356d6a9a020191d3"}, -] - -[package.dependencies] -pytz = "*" -"zope.interface" = "*" - -[[package]] -name = "decorator" -version = "5.1.1" -description = "Decorators for Humans" -optional = false -python-versions = ">=3.5" -files = [ - {file = "decorator-5.1.1-py3-none-any.whl", hash = "sha256:b8c3f85900b9dc423225913c5aace94729fe1fa9763b38939a95226f02d37186"}, - {file = "decorator-5.1.1.tar.gz", hash = "sha256:637996211036b6385ef91435e4fae22989472f9d571faba8927ba8253acbc330"}, -] - -[[package]] -name = "exceptiongroup" -version = "1.2.2" -description = "Backport of PEP 654 (exception groups)" -optional = false -python-versions = ">=3.7" -files = [ - {file = "exceptiongroup-1.2.2-py3-none-any.whl", hash = "sha256:3111b9d131c238bec2f8f516e123e14ba243563fb135d3fe885990585aa7795b"}, - {file = "exceptiongroup-1.2.2.tar.gz", hash = "sha256:47c2edf7c6738fafb49fd34290706d1a1a2f4d1c6df275526b62cbb4aa5393cc"}, -] - -[package.extras] -test = ["pytest (>=6)"] - -[[package]] -name = "executing" -version = "2.1.0" -description = "Get the currently executing AST node of a frame, and other information" -optional = false -python-versions = ">=3.8" -files = [ - {file = "executing-2.1.0-py2.py3-none-any.whl", hash = "sha256:8d63781349375b5ebccc3142f4b30350c0cd9c79f921cde38be2be4637e98eaf"}, - {file = "executing-2.1.0.tar.gz", hash = "sha256:8ea27ddd260da8150fa5a708269c4a10e76161e2496ec3e587da9e3c0fe4b9ab"}, -] - -[package.extras] -tests = ["asttokens (>=2.1.0)", "coverage", "coverage-enable-subprocess", "ipython", "littleutils", "pytest", "rich"] - -[[package]] -name = "exifread" -version = "3.0.0" -description = "Read Exif metadata from tiff and jpeg files." -optional = false -python-versions = "*" -files = [ - {file = "ExifRead-3.0.0-py3-none-any.whl", hash = "sha256:2c5c59ef03b3bbee75b82b82d2498006b3c13509f35c9a76c7552faff73fa2d5"}, - {file = "ExifRead-3.0.0.tar.gz", hash = "sha256:0ac5a364169dbdf2bd62f94f5c073970ab6694a3166177f5e448b10c943e2ca4"}, -] - -[package.extras] -dev = ["mypy (==0.950)", "pylint (==2.13.8)"] - -[[package]] -name = "fonttools" -version = "4.54.1" -description = "Tools to manipulate font files" -optional = false -python-versions = ">=3.8" -files = [ - {file = "fonttools-4.54.1-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:7ed7ee041ff7b34cc62f07545e55e1468808691dddfd315d51dd82a6b37ddef2"}, - {file = "fonttools-4.54.1-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:41bb0b250c8132b2fcac148e2e9198e62ff06f3cc472065dff839327945c5882"}, - {file = "fonttools-4.54.1-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:7965af9b67dd546e52afcf2e38641b5be956d68c425bef2158e95af11d229f10"}, - {file = "fonttools-4.54.1-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:278913a168f90d53378c20c23b80f4e599dca62fbffae4cc620c8eed476b723e"}, - {file = "fonttools-4.54.1-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:0e88e3018ac809b9662615072dcd6b84dca4c2d991c6d66e1970a112503bba7e"}, - {file = "fonttools-4.54.1-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:4aa4817f0031206e637d1e685251ac61be64d1adef111060df84fdcbc6ab6c44"}, - {file = "fonttools-4.54.1-cp310-cp310-win32.whl", hash = "sha256:7e3b7d44e18c085fd8c16dcc6f1ad6c61b71ff463636fcb13df7b1b818bd0c02"}, - {file = "fonttools-4.54.1-cp310-cp310-win_amd64.whl", hash = "sha256:dd9cc95b8d6e27d01e1e1f1fae8559ef3c02c76317da650a19047f249acd519d"}, - {file = "fonttools-4.54.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:5419771b64248484299fa77689d4f3aeed643ea6630b2ea750eeab219588ba20"}, - {file = "fonttools-4.54.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:301540e89cf4ce89d462eb23a89464fef50915255ece765d10eee8b2bf9d75b2"}, - {file = "fonttools-4.54.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:76ae5091547e74e7efecc3cbf8e75200bc92daaeb88e5433c5e3e95ea8ce5aa7"}, - {file = "fonttools-4.54.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:82834962b3d7c5ca98cb56001c33cf20eb110ecf442725dc5fdf36d16ed1ab07"}, - {file = "fonttools-4.54.1-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:d26732ae002cc3d2ecab04897bb02ae3f11f06dd7575d1df46acd2f7c012a8d8"}, - {file = "fonttools-4.54.1-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:58974b4987b2a71ee08ade1e7f47f410c367cdfc5a94fabd599c88165f56213a"}, - {file = "fonttools-4.54.1-cp311-cp311-win32.whl", hash = "sha256:ab774fa225238986218a463f3fe151e04d8c25d7de09df7f0f5fce27b1243dbc"}, - {file = "fonttools-4.54.1-cp311-cp311-win_amd64.whl", hash = "sha256:07e005dc454eee1cc60105d6a29593459a06321c21897f769a281ff2d08939f6"}, - {file = "fonttools-4.54.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:54471032f7cb5fca694b5f1a0aaeba4af6e10ae989df408e0216f7fd6cdc405d"}, - {file = "fonttools-4.54.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:8fa92cb248e573daab8d032919623cc309c005086d743afb014c836636166f08"}, - {file = "fonttools-4.54.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:0a911591200114969befa7f2cb74ac148bce5a91df5645443371aba6d222e263"}, - {file = "fonttools-4.54.1-cp312-cp312-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:93d458c8a6a354dc8b48fc78d66d2a8a90b941f7fec30e94c7ad9982b1fa6bab"}, - {file = "fonttools-4.54.1-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:5eb2474a7c5be8a5331146758debb2669bf5635c021aee00fd7c353558fc659d"}, - {file = "fonttools-4.54.1-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:c9c563351ddc230725c4bdf7d9e1e92cbe6ae8553942bd1fb2b2ff0884e8b714"}, - {file = "fonttools-4.54.1-cp312-cp312-win32.whl", hash = "sha256:fdb062893fd6d47b527d39346e0c5578b7957dcea6d6a3b6794569370013d9ac"}, - {file = "fonttools-4.54.1-cp312-cp312-win_amd64.whl", hash = "sha256:e4564cf40cebcb53f3dc825e85910bf54835e8a8b6880d59e5159f0f325e637e"}, - {file = "fonttools-4.54.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:6e37561751b017cf5c40fce0d90fd9e8274716de327ec4ffb0df957160be3bff"}, - {file = "fonttools-4.54.1-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:357cacb988a18aace66e5e55fe1247f2ee706e01debc4b1a20d77400354cddeb"}, - {file = "fonttools-4.54.1-cp313-cp313-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f8e953cc0bddc2beaf3a3c3b5dd9ab7554677da72dfaf46951e193c9653e515a"}, - {file = "fonttools-4.54.1-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:58d29b9a294573d8319f16f2f79e42428ba9b6480442fa1836e4eb89c4d9d61c"}, - {file = "fonttools-4.54.1-cp313-cp313-win32.whl", hash = "sha256:9ef1b167e22709b46bf8168368b7b5d3efeaaa746c6d39661c1b4405b6352e58"}, - {file = "fonttools-4.54.1-cp313-cp313-win_amd64.whl", hash = "sha256:262705b1663f18c04250bd1242b0515d3bbae177bee7752be67c979b7d47f43d"}, - {file = "fonttools-4.54.1-cp38-cp38-macosx_10_9_universal2.whl", hash = "sha256:ed2f80ca07025551636c555dec2b755dd005e2ea8fbeb99fc5cdff319b70b23b"}, - {file = "fonttools-4.54.1-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:9dc080e5a1c3b2656caff2ac2633d009b3a9ff7b5e93d0452f40cd76d3da3b3c"}, - {file = "fonttools-4.54.1-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:1d152d1be65652fc65e695e5619e0aa0982295a95a9b29b52b85775243c06556"}, - {file = "fonttools-4.54.1-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:8583e563df41fdecef31b793b4dd3af8a9caa03397be648945ad32717a92885b"}, - {file = "fonttools-4.54.1-cp38-cp38-musllinux_1_2_aarch64.whl", hash = "sha256:0d1d353ef198c422515a3e974a1e8d5b304cd54a4c2eebcae708e37cd9eeffb1"}, - {file = "fonttools-4.54.1-cp38-cp38-musllinux_1_2_x86_64.whl", hash = "sha256:fda582236fee135d4daeca056c8c88ec5f6f6d88a004a79b84a02547c8f57386"}, - {file = "fonttools-4.54.1-cp38-cp38-win32.whl", hash = "sha256:e7d82b9e56716ed32574ee106cabca80992e6bbdcf25a88d97d21f73a0aae664"}, - {file = "fonttools-4.54.1-cp38-cp38-win_amd64.whl", hash = "sha256:ada215fd079e23e060157aab12eba0d66704316547f334eee9ff26f8c0d7b8ab"}, - {file = "fonttools-4.54.1-cp39-cp39-macosx_10_9_universal2.whl", hash = "sha256:f5b8a096e649768c2f4233f947cf9737f8dbf8728b90e2771e2497c6e3d21d13"}, - {file = "fonttools-4.54.1-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:4e10d2e0a12e18f4e2dd031e1bf7c3d7017be5c8dbe524d07706179f355c5dac"}, - {file = "fonttools-4.54.1-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:31c32d7d4b0958600eac75eaf524b7b7cb68d3a8c196635252b7a2c30d80e986"}, - {file = "fonttools-4.54.1-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:c39287f5c8f4a0c5a55daf9eaf9ccd223ea59eed3f6d467133cc727d7b943a55"}, - {file = "fonttools-4.54.1-cp39-cp39-musllinux_1_2_aarch64.whl", hash = "sha256:a7a310c6e0471602fe3bf8efaf193d396ea561486aeaa7adc1f132e02d30c4b9"}, - {file = "fonttools-4.54.1-cp39-cp39-musllinux_1_2_x86_64.whl", hash = "sha256:d3b659d1029946f4ff9b6183984578041b520ce0f8fb7078bb37ec7445806b33"}, - {file = "fonttools-4.54.1-cp39-cp39-win32.whl", hash = "sha256:e96bc94c8cda58f577277d4a71f51c8e2129b8b36fd05adece6320dd3d57de8a"}, - {file = "fonttools-4.54.1-cp39-cp39-win_amd64.whl", hash = "sha256:e8a4b261c1ef91e7188a30571be6ad98d1c6d9fa2427244c545e2fa0a2494dd7"}, - {file = "fonttools-4.54.1-py3-none-any.whl", hash = "sha256:37cddd62d83dc4f72f7c3f3c2bcf2697e89a30efb152079896544a93907733bd"}, - {file = "fonttools-4.54.1.tar.gz", hash = "sha256:957f669d4922f92c171ba01bef7f29410668db09f6c02111e22b2bce446f3285"}, -] - -[package.extras] -all = ["brotli (>=1.0.1)", "brotlicffi (>=0.8.0)", "fs (>=2.2.0,<3)", "lxml (>=4.0)", "lz4 (>=1.7.4.2)", "matplotlib", "munkres", "pycairo", "scipy", "skia-pathops (>=0.5.0)", "sympy", "uharfbuzz (>=0.23.0)", "unicodedata2 (>=15.1.0)", "xattr", "zopfli (>=0.1.4)"] -graphite = ["lz4 (>=1.7.4.2)"] -interpolatable = ["munkres", "pycairo", "scipy"] -lxml = ["lxml (>=4.0)"] -pathops = ["skia-pathops (>=0.5.0)"] -plot = ["matplotlib"] -repacker = ["uharfbuzz (>=0.23.0)"] -symfont = ["sympy"] -type1 = ["xattr"] -ufo = ["fs (>=2.2.0,<3)"] -unicode = ["unicodedata2 (>=15.1.0)"] -woff = ["brotli (>=1.0.1)", "brotlicffi (>=0.8.0)", "zopfli (>=0.1.4)"] - -[[package]] -name = "GDAL" -version = "3.9.2" -description = "GDAL: Geospatial Data Abstraction Library" -optional = false -python-versions = ">=3.7.0" -files = [ - {file = "GDAL-3.9.2-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:0ccdfd68893818a86d2225c1efe6b4a64a6d84676f6fb1e7ec5a4138f70d837b"}, -] - -[package.extras] -numpy = ["numpy (>1.0.0)"] - -[package.source] -type = "url" -url = "https://github.com/girder/large_image_wheels/raw/wheelhouse/GDAL-3.9.2-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl#sha256=0ccdfd68893818a86d2225c1efe6b4a64a6d84676f6fb1e7ec5a4138f70d837b" - -[[package]] -name = "ipdb" -version = "0.13.13" -description = "IPython-enabled pdb" -optional = false -python-versions = ">=2.7, !=3.0.*, !=3.1.*, !=3.2.*, !=3.3.*" -files = [ - {file = "ipdb-0.13.13-py3-none-any.whl", hash = "sha256:45529994741c4ab6d2388bfa5d7b725c2cf7fe9deffabdb8a6113aa5ed449ed4"}, - {file = "ipdb-0.13.13.tar.gz", hash = "sha256:e3ac6018ef05126d442af680aad863006ec19d02290561ac88b8b1c0b0cfc726"}, -] - -[package.dependencies] -decorator = {version = "*", markers = "python_version > \"3.6\""} -ipython = {version = ">=7.31.1", markers = "python_version > \"3.6\""} -tomli = {version = "*", markers = "python_version > \"3.6\" and python_version < \"3.11\""} - -[[package]] -name = "ipython" -version = "8.28.0" -description = "IPython: Productive Interactive Computing" -optional = false -python-versions = ">=3.10" -files = [ - {file = "ipython-8.28.0-py3-none-any.whl", hash = "sha256:530ef1e7bb693724d3cdc37287c80b07ad9b25986c007a53aa1857272dac3f35"}, - {file = "ipython-8.28.0.tar.gz", hash = "sha256:0d0d15ca1e01faeb868ef56bc7ee5a0de5bd66885735682e8a322ae289a13d1a"}, -] - -[package.dependencies] -colorama = {version = "*", markers = "sys_platform == \"win32\""} -decorator = "*" -exceptiongroup = {version = "*", markers = "python_version < \"3.11\""} -jedi = ">=0.16" -matplotlib-inline = "*" -pexpect = {version = ">4.3", markers = "sys_platform != \"win32\" and sys_platform != \"emscripten\""} -prompt-toolkit = ">=3.0.41,<3.1.0" -pygments = ">=2.4.0" -stack-data = "*" -traitlets = ">=5.13.0" -typing-extensions = {version = ">=4.6", markers = "python_version < \"3.12\""} - -[package.extras] -all = ["ipython[black,doc,kernel,matplotlib,nbconvert,nbformat,notebook,parallel,qtconsole]", "ipython[test,test-extra]"] -black = ["black"] -doc = ["docrepr", "exceptiongroup", "intersphinx-registry", "ipykernel", "ipython[test]", "matplotlib", "setuptools (>=18.5)", "sphinx (>=1.3)", "sphinx-rtd-theme", "sphinxcontrib-jquery", "tomli", "typing-extensions"] -kernel = ["ipykernel"] -matplotlib = ["matplotlib"] -nbconvert = ["nbconvert"] -nbformat = ["nbformat"] -notebook = ["ipywidgets", "notebook"] -parallel = ["ipyparallel"] -qtconsole = ["qtconsole"] -test = ["packaging", "pickleshare", "pytest", "pytest-asyncio (<0.22)", "testpath"] -test-extra = ["curio", "ipython[test]", "matplotlib (!=3.2.0)", "nbformat", "numpy (>=1.23)", "pandas", "trio"] - -[[package]] -name = "jedi" -version = "0.19.1" -description = "An autocompletion tool for Python that can be used for text editors." -optional = false -python-versions = ">=3.6" -files = [ - {file = "jedi-0.19.1-py2.py3-none-any.whl", hash = "sha256:e983c654fe5c02867aef4cdfce5a2fbb4a50adc0af145f70504238f18ef5e7e0"}, - {file = "jedi-0.19.1.tar.gz", hash = "sha256:cf0496f3651bc65d7174ac1b7d043eff454892c708a87d1b683e57b569927ffd"}, -] - -[package.dependencies] -parso = ">=0.8.3,<0.9.0" - -[package.extras] -docs = ["Jinja2 (==2.11.3)", "MarkupSafe (==1.1.1)", "Pygments (==2.8.1)", "alabaster (==0.7.12)", "babel (==2.9.1)", "chardet (==4.0.0)", "commonmark (==0.8.1)", "docutils (==0.17.1)", "future (==0.18.2)", "idna (==2.10)", "imagesize (==1.2.0)", "mock (==1.0.1)", "packaging (==20.9)", "pyparsing (==2.4.7)", "pytz (==2021.1)", "readthedocs-sphinx-ext (==2.1.4)", "recommonmark (==0.5.0)", "requests (==2.25.1)", "six (==1.15.0)", "snowballstemmer (==2.1.0)", "sphinx (==1.8.5)", "sphinx-rtd-theme (==0.4.3)", "sphinxcontrib-serializinghtml (==1.1.4)", "sphinxcontrib-websupport (==1.2.4)", "urllib3 (==1.26.4)"] -qa = ["flake8 (==5.0.4)", "mypy (==0.971)", "types-setuptools (==67.2.0.1)"] -testing = ["Django", "attrs", "colorama", "docopt", "pytest (<7.0.0)"] - -[[package]] -name = "kiwisolver" -version = "1.4.7" -description = "A fast implementation of the Cassowary constraint solver" -optional = false -python-versions = ">=3.8" -files = [ - {file = "kiwisolver-1.4.7-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:8a9c83f75223d5e48b0bc9cb1bf2776cf01563e00ade8775ffe13b0b6e1af3a6"}, - {file = "kiwisolver-1.4.7-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:58370b1ffbd35407444d57057b57da5d6549d2d854fa30249771775c63b5fe17"}, - {file = "kiwisolver-1.4.7-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:aa0abdf853e09aff551db11fce173e2177d00786c688203f52c87ad7fcd91ef9"}, - {file = "kiwisolver-1.4.7-cp310-cp310-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:8d53103597a252fb3ab8b5845af04c7a26d5e7ea8122303dd7a021176a87e8b9"}, - {file = "kiwisolver-1.4.7-cp310-cp310-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:88f17c5ffa8e9462fb79f62746428dd57b46eb931698e42e990ad63103f35e6c"}, - {file = "kiwisolver-1.4.7-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:88a9ca9c710d598fd75ee5de59d5bda2684d9db36a9f50b6125eaea3969c2599"}, - {file = "kiwisolver-1.4.7-cp310-cp310-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:f4d742cb7af1c28303a51b7a27aaee540e71bb8e24f68c736f6f2ffc82f2bf05"}, - {file = "kiwisolver-1.4.7-cp310-cp310-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:e28c7fea2196bf4c2f8d46a0415c77a1c480cc0724722f23d7410ffe9842c407"}, - {file = "kiwisolver-1.4.7-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:e968b84db54f9d42046cf154e02911e39c0435c9801681e3fc9ce8a3c4130278"}, - {file = "kiwisolver-1.4.7-cp310-cp310-musllinux_1_2_i686.whl", hash = "sha256:0c18ec74c0472de033e1bebb2911c3c310eef5649133dd0bedf2a169a1b269e5"}, - {file = "kiwisolver-1.4.7-cp310-cp310-musllinux_1_2_ppc64le.whl", hash = "sha256:8f0ea6da6d393d8b2e187e6a5e3fb81f5862010a40c3945e2c6d12ae45cfb2ad"}, - {file = "kiwisolver-1.4.7-cp310-cp310-musllinux_1_2_s390x.whl", hash = "sha256:f106407dda69ae456dd1227966bf445b157ccc80ba0dff3802bb63f30b74e895"}, - {file = "kiwisolver-1.4.7-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:84ec80df401cfee1457063732d90022f93951944b5b58975d34ab56bb150dfb3"}, - {file = "kiwisolver-1.4.7-cp310-cp310-win32.whl", hash = "sha256:71bb308552200fb2c195e35ef05de12f0c878c07fc91c270eb3d6e41698c3bcc"}, - {file = "kiwisolver-1.4.7-cp310-cp310-win_amd64.whl", hash = "sha256:44756f9fd339de0fb6ee4f8c1696cfd19b2422e0d70b4cefc1cc7f1f64045a8c"}, - {file = "kiwisolver-1.4.7-cp310-cp310-win_arm64.whl", hash = "sha256:78a42513018c41c2ffd262eb676442315cbfe3c44eed82385c2ed043bc63210a"}, - {file = "kiwisolver-1.4.7-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:d2b0e12a42fb4e72d509fc994713d099cbb15ebf1103545e8a45f14da2dfca54"}, - {file = "kiwisolver-1.4.7-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:2a8781ac3edc42ea4b90bc23e7d37b665d89423818e26eb6df90698aa2287c95"}, - {file = "kiwisolver-1.4.7-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:46707a10836894b559e04b0fd143e343945c97fd170d69a2d26d640b4e297935"}, - {file = "kiwisolver-1.4.7-cp311-cp311-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:ef97b8df011141c9b0f6caf23b29379f87dd13183c978a30a3c546d2c47314cb"}, - {file = "kiwisolver-1.4.7-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:3ab58c12a2cd0fc769089e6d38466c46d7f76aced0a1f54c77652446733d2d02"}, - {file = "kiwisolver-1.4.7-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:803b8e1459341c1bb56d1c5c010406d5edec8a0713a0945851290a7930679b51"}, - {file = "kiwisolver-1.4.7-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:f9a9e8a507420fe35992ee9ecb302dab68550dedc0da9e2880dd88071c5fb052"}, - {file = "kiwisolver-1.4.7-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:18077b53dc3bb490e330669a99920c5e6a496889ae8c63b58fbc57c3d7f33a18"}, - {file = "kiwisolver-1.4.7-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:6af936f79086a89b3680a280c47ea90b4df7047b5bdf3aa5c524bbedddb9e545"}, - {file = "kiwisolver-1.4.7-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:3abc5b19d24af4b77d1598a585b8a719beb8569a71568b66f4ebe1fb0449460b"}, - {file = "kiwisolver-1.4.7-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:933d4de052939d90afbe6e9d5273ae05fb836cc86c15b686edd4b3560cc0ee36"}, - {file = "kiwisolver-1.4.7-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:65e720d2ab2b53f1f72fb5da5fb477455905ce2c88aaa671ff0a447c2c80e8e3"}, - {file = "kiwisolver-1.4.7-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:3bf1ed55088f214ba6427484c59553123fdd9b218a42bbc8c6496d6754b1e523"}, - {file = "kiwisolver-1.4.7-cp311-cp311-win32.whl", hash = "sha256:4c00336b9dd5ad96d0a558fd18a8b6f711b7449acce4c157e7343ba92dd0cf3d"}, - {file = "kiwisolver-1.4.7-cp311-cp311-win_amd64.whl", hash = "sha256:929e294c1ac1e9f615c62a4e4313ca1823ba37326c164ec720a803287c4c499b"}, - {file = "kiwisolver-1.4.7-cp311-cp311-win_arm64.whl", hash = "sha256:e33e8fbd440c917106b237ef1a2f1449dfbb9b6f6e1ce17c94cd6a1e0d438376"}, - {file = "kiwisolver-1.4.7-cp312-cp312-macosx_10_9_universal2.whl", hash = "sha256:5360cc32706dab3931f738d3079652d20982511f7c0ac5711483e6eab08efff2"}, - {file = "kiwisolver-1.4.7-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:942216596dc64ddb25adb215c3c783215b23626f8d84e8eff8d6d45c3f29f75a"}, - {file = "kiwisolver-1.4.7-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:48b571ecd8bae15702e4f22d3ff6a0f13e54d3d00cd25216d5e7f658242065ee"}, - {file = "kiwisolver-1.4.7-cp312-cp312-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:ad42ba922c67c5f219097b28fae965e10045ddf145d2928bfac2eb2e17673640"}, - {file = "kiwisolver-1.4.7-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:612a10bdae23404a72941a0fc8fa2660c6ea1217c4ce0dbcab8a8f6543ea9e7f"}, - {file = "kiwisolver-1.4.7-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:9e838bba3a3bac0fe06d849d29772eb1afb9745a59710762e4ba3f4cb8424483"}, - {file = "kiwisolver-1.4.7-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:22f499f6157236c19f4bbbd472fa55b063db77a16cd74d49afe28992dff8c258"}, - {file = "kiwisolver-1.4.7-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:693902d433cf585133699972b6d7c42a8b9f8f826ebcaf0132ff55200afc599e"}, - {file = "kiwisolver-1.4.7-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:4e77f2126c3e0b0d055f44513ed349038ac180371ed9b52fe96a32aa071a5107"}, - {file = "kiwisolver-1.4.7-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:657a05857bda581c3656bfc3b20e353c232e9193eb167766ad2dc58b56504948"}, - {file = "kiwisolver-1.4.7-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:4bfa75a048c056a411f9705856abfc872558e33c055d80af6a380e3658766038"}, - {file = "kiwisolver-1.4.7-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:34ea1de54beef1c104422d210c47c7d2a4999bdecf42c7b5718fbe59a4cac383"}, - {file = "kiwisolver-1.4.7-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:90da3b5f694b85231cf93586dad5e90e2d71b9428f9aad96952c99055582f520"}, - {file = "kiwisolver-1.4.7-cp312-cp312-win32.whl", hash = "sha256:18e0cca3e008e17fe9b164b55735a325140a5a35faad8de92dd80265cd5eb80b"}, - {file = "kiwisolver-1.4.7-cp312-cp312-win_amd64.whl", hash = "sha256:58cb20602b18f86f83a5c87d3ee1c766a79c0d452f8def86d925e6c60fbf7bfb"}, - {file = "kiwisolver-1.4.7-cp312-cp312-win_arm64.whl", hash = "sha256:f5a8b53bdc0b3961f8b6125e198617c40aeed638b387913bf1ce78afb1b0be2a"}, - {file = "kiwisolver-1.4.7-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:2e6039dcbe79a8e0f044f1c39db1986a1b8071051efba3ee4d74f5b365f5226e"}, - {file = "kiwisolver-1.4.7-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:a1ecf0ac1c518487d9d23b1cd7139a6a65bc460cd101ab01f1be82ecf09794b6"}, - {file = "kiwisolver-1.4.7-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:7ab9ccab2b5bd5702ab0803676a580fffa2aa178c2badc5557a84cc943fcf750"}, - {file = "kiwisolver-1.4.7-cp313-cp313-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:f816dd2277f8d63d79f9c8473a79fe54047bc0467754962840782c575522224d"}, - {file = "kiwisolver-1.4.7-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:cf8bcc23ceb5a1b624572a1623b9f79d2c3b337c8c455405ef231933a10da379"}, - {file = "kiwisolver-1.4.7-cp313-cp313-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:dea0bf229319828467d7fca8c7c189780aa9ff679c94539eed7532ebe33ed37c"}, - {file = "kiwisolver-1.4.7-cp313-cp313-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:7c06a4c7cf15ec739ce0e5971b26c93638730090add60e183530d70848ebdd34"}, - {file = "kiwisolver-1.4.7-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:913983ad2deb14e66d83c28b632fd35ba2b825031f2fa4ca29675e665dfecbe1"}, - {file = "kiwisolver-1.4.7-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:5337ec7809bcd0f424c6b705ecf97941c46279cf5ed92311782c7c9c2026f07f"}, - {file = "kiwisolver-1.4.7-cp313-cp313-musllinux_1_2_i686.whl", hash = "sha256:4c26ed10c4f6fa6ddb329a5120ba3b6db349ca192ae211e882970bfc9d91420b"}, - {file = "kiwisolver-1.4.7-cp313-cp313-musllinux_1_2_ppc64le.whl", hash = "sha256:c619b101e6de2222c1fcb0531e1b17bbffbe54294bfba43ea0d411d428618c27"}, - {file = "kiwisolver-1.4.7-cp313-cp313-musllinux_1_2_s390x.whl", hash = "sha256:073a36c8273647592ea332e816e75ef8da5c303236ec0167196793eb1e34657a"}, - {file = "kiwisolver-1.4.7-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:3ce6b2b0231bda412463e152fc18335ba32faf4e8c23a754ad50ffa70e4091ee"}, - {file = "kiwisolver-1.4.7-cp313-cp313-win32.whl", hash = "sha256:f4c9aee212bc89d4e13f58be11a56cc8036cabad119259d12ace14b34476fd07"}, - {file = "kiwisolver-1.4.7-cp313-cp313-win_amd64.whl", hash = "sha256:8a3ec5aa8e38fc4c8af308917ce12c536f1c88452ce554027e55b22cbbfbff76"}, - {file = "kiwisolver-1.4.7-cp313-cp313-win_arm64.whl", hash = "sha256:76c8094ac20ec259471ac53e774623eb62e6e1f56cd8690c67ce6ce4fcb05650"}, - {file = "kiwisolver-1.4.7-cp38-cp38-macosx_10_9_universal2.whl", hash = "sha256:5d5abf8f8ec1f4e22882273c423e16cae834c36856cac348cfbfa68e01c40f3a"}, - {file = "kiwisolver-1.4.7-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:aeb3531b196ef6f11776c21674dba836aeea9d5bd1cf630f869e3d90b16cfade"}, - {file = "kiwisolver-1.4.7-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:b7d755065e4e866a8086c9bdada157133ff466476a2ad7861828e17b6026e22c"}, - {file = "kiwisolver-1.4.7-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:08471d4d86cbaec61f86b217dd938a83d85e03785f51121e791a6e6689a3be95"}, - {file = "kiwisolver-1.4.7-cp38-cp38-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:7bbfcb7165ce3d54a3dfbe731e470f65739c4c1f85bb1018ee912bae139e263b"}, - {file = "kiwisolver-1.4.7-cp38-cp38-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:5d34eb8494bea691a1a450141ebb5385e4b69d38bb8403b5146ad279f4b30fa3"}, - {file = "kiwisolver-1.4.7-cp38-cp38-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:9242795d174daa40105c1d86aba618e8eab7bf96ba8c3ee614da8302a9f95503"}, - {file = "kiwisolver-1.4.7-cp38-cp38-manylinux_2_5_x86_64.manylinux1_x86_64.whl", hash = "sha256:a0f64a48bb81af7450e641e3fe0b0394d7381e342805479178b3d335d60ca7cf"}, - {file = "kiwisolver-1.4.7-cp38-cp38-musllinux_1_2_aarch64.whl", hash = "sha256:8e045731a5416357638d1700927529e2b8ab304811671f665b225f8bf8d8f933"}, - {file = "kiwisolver-1.4.7-cp38-cp38-musllinux_1_2_i686.whl", hash = "sha256:4322872d5772cae7369f8351da1edf255a604ea7087fe295411397d0cfd9655e"}, - {file = "kiwisolver-1.4.7-cp38-cp38-musllinux_1_2_ppc64le.whl", hash = "sha256:e1631290ee9271dffe3062d2634c3ecac02c83890ada077d225e081aca8aab89"}, - {file = "kiwisolver-1.4.7-cp38-cp38-musllinux_1_2_s390x.whl", hash = "sha256:edcfc407e4eb17e037bca59be0e85a2031a2ac87e4fed26d3e9df88b4165f92d"}, - {file = "kiwisolver-1.4.7-cp38-cp38-musllinux_1_2_x86_64.whl", hash = "sha256:4d05d81ecb47d11e7f8932bd8b61b720bf0b41199358f3f5e36d38e28f0532c5"}, - {file = "kiwisolver-1.4.7-cp38-cp38-win32.whl", hash = "sha256:b38ac83d5f04b15e515fd86f312479d950d05ce2368d5413d46c088dda7de90a"}, - {file = "kiwisolver-1.4.7-cp38-cp38-win_amd64.whl", hash = "sha256:d83db7cde68459fc803052a55ace60bea2bae361fc3b7a6d5da07e11954e4b09"}, - {file = "kiwisolver-1.4.7-cp39-cp39-macosx_10_9_universal2.whl", hash = "sha256:3f9362ecfca44c863569d3d3c033dbe8ba452ff8eed6f6b5806382741a1334bd"}, - {file = "kiwisolver-1.4.7-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:e8df2eb9b2bac43ef8b082e06f750350fbbaf2887534a5be97f6cf07b19d9583"}, - {file = "kiwisolver-1.4.7-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:f32d6edbc638cde7652bd690c3e728b25332acbadd7cad670cc4a02558d9c417"}, - {file = "kiwisolver-1.4.7-cp39-cp39-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:e2e6c39bd7b9372b0be21456caab138e8e69cc0fc1190a9dfa92bd45a1e6e904"}, - {file = "kiwisolver-1.4.7-cp39-cp39-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:dda56c24d869b1193fcc763f1284b9126550eaf84b88bbc7256e15028f19188a"}, - {file = "kiwisolver-1.4.7-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:79849239c39b5e1fd906556c474d9b0439ea6792b637511f3fe3a41158d89ca8"}, - {file = "kiwisolver-1.4.7-cp39-cp39-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:5e3bc157fed2a4c02ec468de4ecd12a6e22818d4f09cde2c31ee3226ffbefab2"}, - {file = "kiwisolver-1.4.7-cp39-cp39-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:3da53da805b71e41053dc670f9a820d1157aae77b6b944e08024d17bcd51ef88"}, - {file = "kiwisolver-1.4.7-cp39-cp39-musllinux_1_2_aarch64.whl", hash = "sha256:8705f17dfeb43139a692298cb6637ee2e59c0194538153e83e9ee0c75c2eddde"}, - {file = "kiwisolver-1.4.7-cp39-cp39-musllinux_1_2_i686.whl", hash = "sha256:82a5c2f4b87c26bb1a0ef3d16b5c4753434633b83d365cc0ddf2770c93829e3c"}, - {file = "kiwisolver-1.4.7-cp39-cp39-musllinux_1_2_ppc64le.whl", hash = "sha256:ce8be0466f4c0d585cdb6c1e2ed07232221df101a4c6f28821d2aa754ca2d9e2"}, - {file = "kiwisolver-1.4.7-cp39-cp39-musllinux_1_2_s390x.whl", hash = "sha256:409afdfe1e2e90e6ee7fc896f3df9a7fec8e793e58bfa0d052c8a82f99c37abb"}, - {file = "kiwisolver-1.4.7-cp39-cp39-musllinux_1_2_x86_64.whl", hash = "sha256:5b9c3f4ee0b9a439d2415012bd1b1cc2df59e4d6a9939f4d669241d30b414327"}, - {file = "kiwisolver-1.4.7-cp39-cp39-win32.whl", hash = "sha256:a79ae34384df2b615eefca647a2873842ac3b596418032bef9a7283675962644"}, - {file = "kiwisolver-1.4.7-cp39-cp39-win_amd64.whl", hash = "sha256:cf0438b42121a66a3a667de17e779330fc0f20b0d97d59d2f2121e182b0505e4"}, - {file = "kiwisolver-1.4.7-cp39-cp39-win_arm64.whl", hash = "sha256:764202cc7e70f767dab49e8df52c7455e8de0df5d858fa801a11aa0d882ccf3f"}, - {file = "kiwisolver-1.4.7-pp310-pypy310_pp73-macosx_10_15_x86_64.whl", hash = "sha256:94252291e3fe68001b1dd747b4c0b3be12582839b95ad4d1b641924d68fd4643"}, - {file = "kiwisolver-1.4.7-pp310-pypy310_pp73-macosx_11_0_arm64.whl", hash = "sha256:5b7dfa3b546da08a9f622bb6becdb14b3e24aaa30adba66749d38f3cc7ea9706"}, - {file = "kiwisolver-1.4.7-pp310-pypy310_pp73-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:bd3de6481f4ed8b734da5df134cd5a6a64fe32124fe83dde1e5b5f29fe30b1e6"}, - {file = "kiwisolver-1.4.7-pp310-pypy310_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a91b5f9f1205845d488c928e8570dcb62b893372f63b8b6e98b863ebd2368ff2"}, - {file = "kiwisolver-1.4.7-pp310-pypy310_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:40fa14dbd66b8b8f470d5fc79c089a66185619d31645f9b0773b88b19f7223c4"}, - {file = "kiwisolver-1.4.7-pp310-pypy310_pp73-win_amd64.whl", hash = "sha256:eb542fe7933aa09d8d8f9d9097ef37532a7df6497819d16efe4359890a2f417a"}, - {file = "kiwisolver-1.4.7-pp38-pypy38_pp73-macosx_10_9_x86_64.whl", hash = "sha256:bfa1acfa0c54932d5607e19a2c24646fb4c1ae2694437789129cf099789a3b00"}, - {file = "kiwisolver-1.4.7-pp38-pypy38_pp73-macosx_11_0_arm64.whl", hash = "sha256:eee3ea935c3d227d49b4eb85660ff631556841f6e567f0f7bda972df6c2c9935"}, - {file = "kiwisolver-1.4.7-pp38-pypy38_pp73-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:f3160309af4396e0ed04db259c3ccbfdc3621b5559b5453075e5de555e1f3a1b"}, - {file = "kiwisolver-1.4.7-pp38-pypy38_pp73-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:a17f6a29cf8935e587cc8a4dbfc8368c55edc645283db0ce9801016f83526c2d"}, - {file = "kiwisolver-1.4.7-pp38-pypy38_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:10849fb2c1ecbfae45a693c070e0320a91b35dd4bcf58172c023b994283a124d"}, - {file = "kiwisolver-1.4.7-pp38-pypy38_pp73-win_amd64.whl", hash = "sha256:ac542bf38a8a4be2dc6b15248d36315ccc65f0743f7b1a76688ffb6b5129a5c2"}, - {file = "kiwisolver-1.4.7-pp39-pypy39_pp73-macosx_10_15_x86_64.whl", hash = "sha256:8b01aac285f91ca889c800042c35ad3b239e704b150cfd3382adfc9dcc780e39"}, - {file = "kiwisolver-1.4.7-pp39-pypy39_pp73-macosx_11_0_arm64.whl", hash = "sha256:48be928f59a1f5c8207154f935334d374e79f2b5d212826307d072595ad76a2e"}, - {file = "kiwisolver-1.4.7-pp39-pypy39_pp73-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:f37cfe618a117e50d8c240555331160d73d0411422b59b5ee217843d7b693608"}, - {file = "kiwisolver-1.4.7-pp39-pypy39_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:599b5c873c63a1f6ed7eead644a8a380cfbdf5db91dcb6f85707aaab213b1674"}, - {file = "kiwisolver-1.4.7-pp39-pypy39_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:801fa7802e5cfabe3ab0c81a34c323a319b097dfb5004be950482d882f3d7225"}, - {file = "kiwisolver-1.4.7-pp39-pypy39_pp73-win_amd64.whl", hash = "sha256:0c6c43471bc764fad4bc99c5c2d6d16a676b1abf844ca7c8702bdae92df01ee0"}, - {file = "kiwisolver-1.4.7.tar.gz", hash = "sha256:9893ff81bd7107f7b685d3017cc6583daadb4fc26e4a888350df530e41980a60"}, -] - -[[package]] -name = "markdown-it-py" -version = "3.0.0" -description = "Python port of markdown-it. Markdown parsing, done right!" -optional = false -python-versions = ">=3.8" -files = [ - {file = "markdown-it-py-3.0.0.tar.gz", hash = "sha256:e3f60a94fa066dc52ec76661e37c851cb232d92f9886b15cb560aaada2df8feb"}, - {file = "markdown_it_py-3.0.0-py3-none-any.whl", hash = "sha256:355216845c60bd96232cd8d8c40e8f9765cc86f46880e43a8fd22dc1a1a8cab1"}, -] - -[package.dependencies] -mdurl = ">=0.1,<1.0" - -[package.extras] -benchmarking = ["psutil", "pytest", "pytest-benchmark"] -code-style = ["pre-commit (>=3.0,<4.0)"] -compare = ["commonmark (>=0.9,<1.0)", "markdown (>=3.4,<4.0)", "mistletoe (>=1.0,<2.0)", "mistune (>=2.0,<3.0)", "panflute (>=2.3,<3.0)"] -linkify = ["linkify-it-py (>=1,<3)"] -plugins = ["mdit-py-plugins"] -profiling = ["gprof2dot"] -rtd = ["jupyter_sphinx", "mdit-py-plugins", "myst-parser", "pyyaml", "sphinx", "sphinx-copybutton", "sphinx-design", "sphinx_book_theme"] -testing = ["coverage", "pytest", "pytest-cov", "pytest-regressions"] - -[[package]] -name = "matplotlib" -version = "3.9.2" -description = "Python plotting package" -optional = false -python-versions = ">=3.9" -files = [ - {file = "matplotlib-3.9.2-cp310-cp310-macosx_10_12_x86_64.whl", hash = "sha256:9d78bbc0cbc891ad55b4f39a48c22182e9bdaea7fc0e5dbd364f49f729ca1bbb"}, - {file = "matplotlib-3.9.2-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:c375cc72229614632c87355366bdf2570c2dac01ac66b8ad048d2dabadf2d0d4"}, - {file = "matplotlib-3.9.2-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:1d94ff717eb2bd0b58fe66380bd8b14ac35f48a98e7c6765117fe67fb7684e64"}, - {file = "matplotlib-3.9.2-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:ab68d50c06938ef28681073327795c5db99bb4666214d2d5f880ed11aeaded66"}, - {file = "matplotlib-3.9.2-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:65aacf95b62272d568044531e41de26285d54aec8cb859031f511f84bd8b495a"}, - {file = "matplotlib-3.9.2-cp310-cp310-win_amd64.whl", hash = "sha256:3fd595f34aa8a55b7fc8bf9ebea8aa665a84c82d275190a61118d33fbc82ccae"}, - {file = "matplotlib-3.9.2-cp311-cp311-macosx_10_12_x86_64.whl", hash = "sha256:d8dd059447824eec055e829258ab092b56bb0579fc3164fa09c64f3acd478772"}, - {file = "matplotlib-3.9.2-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:c797dac8bb9c7a3fd3382b16fe8f215b4cf0f22adccea36f1545a6d7be310b41"}, - {file = "matplotlib-3.9.2-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d719465db13267bcef19ea8954a971db03b9f48b4647e3860e4bc8e6ed86610f"}, - {file = "matplotlib-3.9.2-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:8912ef7c2362f7193b5819d17dae8629b34a95c58603d781329712ada83f9447"}, - {file = "matplotlib-3.9.2-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:7741f26a58a240f43bee74965c4882b6c93df3e7eb3de160126d8c8f53a6ae6e"}, - {file = "matplotlib-3.9.2-cp311-cp311-win_amd64.whl", hash = "sha256:ae82a14dab96fbfad7965403c643cafe6515e386de723e498cf3eeb1e0b70cc7"}, - {file = "matplotlib-3.9.2-cp312-cp312-macosx_10_12_x86_64.whl", hash = "sha256:ac43031375a65c3196bee99f6001e7fa5bdfb00ddf43379d3c0609bdca042df9"}, - {file = "matplotlib-3.9.2-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:be0fc24a5e4531ae4d8e858a1a548c1fe33b176bb13eff7f9d0d38ce5112a27d"}, - {file = "matplotlib-3.9.2-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:bf81de2926c2db243c9b2cbc3917619a0fc85796c6ba4e58f541df814bbf83c7"}, - {file = "matplotlib-3.9.2-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f6ee45bc4245533111ced13f1f2cace1e7f89d1c793390392a80c139d6cf0e6c"}, - {file = "matplotlib-3.9.2-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:306c8dfc73239f0e72ac50e5a9cf19cc4e8e331dd0c54f5e69ca8758550f1e1e"}, - {file = "matplotlib-3.9.2-cp312-cp312-win_amd64.whl", hash = "sha256:5413401594cfaff0052f9d8b1aafc6d305b4bd7c4331dccd18f561ff7e1d3bd3"}, - {file = "matplotlib-3.9.2-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:18128cc08f0d3cfff10b76baa2f296fc28c4607368a8402de61bb3f2eb33c7d9"}, - {file = "matplotlib-3.9.2-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:4876d7d40219e8ae8bb70f9263bcbe5714415acfdf781086601211335e24f8aa"}, - {file = "matplotlib-3.9.2-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:6d9f07a80deab4bb0b82858a9e9ad53d1382fd122be8cde11080f4e7dfedb38b"}, - {file = "matplotlib-3.9.2-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f7c0410f181a531ec4e93bbc27692f2c71a15c2da16766f5ba9761e7ae518413"}, - {file = "matplotlib-3.9.2-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:909645cce2dc28b735674ce0931a4ac94e12f5b13f6bb0b5a5e65e7cea2c192b"}, - {file = "matplotlib-3.9.2-cp313-cp313-win_amd64.whl", hash = "sha256:f32c7410c7f246838a77d6d1eff0c0f87f3cb0e7c4247aebea71a6d5a68cab49"}, - {file = "matplotlib-3.9.2-cp313-cp313t-macosx_10_13_x86_64.whl", hash = "sha256:37e51dd1c2db16ede9cfd7b5cabdfc818b2c6397c83f8b10e0e797501c963a03"}, - {file = "matplotlib-3.9.2-cp313-cp313t-macosx_11_0_arm64.whl", hash = "sha256:b82c5045cebcecd8496a4d694d43f9cc84aeeb49fe2133e036b207abe73f4d30"}, - {file = "matplotlib-3.9.2-cp313-cp313t-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f053c40f94bc51bc03832a41b4f153d83f2062d88c72b5e79997072594e97e51"}, - {file = "matplotlib-3.9.2-cp313-cp313t-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:dbe196377a8248972f5cede786d4c5508ed5f5ca4a1e09b44bda889958b33f8c"}, - {file = "matplotlib-3.9.2-cp313-cp313t-musllinux_1_2_x86_64.whl", hash = "sha256:5816b1e1fe8c192cbc013f8f3e3368ac56fbecf02fb41b8f8559303f24c5015e"}, - {file = "matplotlib-3.9.2-cp39-cp39-macosx_10_12_x86_64.whl", hash = "sha256:cef2a73d06601437be399908cf13aee74e86932a5ccc6ccdf173408ebc5f6bb2"}, - {file = "matplotlib-3.9.2-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:e0830e188029c14e891fadd99702fd90d317df294c3298aad682739c5533721a"}, - {file = "matplotlib-3.9.2-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:03ba9c1299c920964e8d3857ba27173b4dbb51ca4bab47ffc2c2ba0eb5e2cbc5"}, - {file = "matplotlib-3.9.2-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:1cd93b91ab47a3616b4d3c42b52f8363b88ca021e340804c6ab2536344fad9ca"}, - {file = "matplotlib-3.9.2-cp39-cp39-musllinux_1_2_x86_64.whl", hash = "sha256:6d1ce5ed2aefcdce11904fc5bbea7d9c21fff3d5f543841edf3dea84451a09ea"}, - {file = "matplotlib-3.9.2-cp39-cp39-win_amd64.whl", hash = "sha256:b2696efdc08648536efd4e1601b5fd491fd47f4db97a5fbfd175549a7365c1b2"}, - {file = "matplotlib-3.9.2-pp39-pypy39_pp73-macosx_10_15_x86_64.whl", hash = "sha256:d52a3b618cb1cbb769ce2ee1dcdb333c3ab6e823944e9a2d36e37253815f9556"}, - {file = "matplotlib-3.9.2-pp39-pypy39_pp73-macosx_11_0_arm64.whl", hash = "sha256:039082812cacd6c6bec8e17a9c1e6baca230d4116d522e81e1f63a74d01d2e21"}, - {file = "matplotlib-3.9.2-pp39-pypy39_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6758baae2ed64f2331d4fd19be38b7b4eae3ecec210049a26b6a4f3ae1c85dcc"}, - {file = "matplotlib-3.9.2-pp39-pypy39_pp73-win_amd64.whl", hash = "sha256:050598c2b29e0b9832cde72bcf97627bf00262adbc4a54e2b856426bb2ef0697"}, - {file = "matplotlib-3.9.2.tar.gz", hash = "sha256:96ab43906269ca64a6366934106fa01534454a69e471b7bf3d79083981aaab92"}, -] - -[package.dependencies] -contourpy = ">=1.0.1" -cycler = ">=0.10" -fonttools = ">=4.22.0" -kiwisolver = ">=1.3.1" -numpy = ">=1.23" -packaging = ">=20.0" -pillow = ">=8" -pyparsing = ">=2.3.1" -python-dateutil = ">=2.7" - -[package.extras] -dev = ["meson-python (>=0.13.1)", "numpy (>=1.25)", "pybind11 (>=2.6)", "setuptools (>=64)", "setuptools_scm (>=7)"] - -[[package]] -name = "matplotlib-inline" -version = "0.1.7" -description = "Inline Matplotlib backend for Jupyter" -optional = false -python-versions = ">=3.8" -files = [ - {file = "matplotlib_inline-0.1.7-py3-none-any.whl", hash = "sha256:df192d39a4ff8f21b1895d72e6a13f5fcc5099f00fa84384e0ea28c2cc0653ca"}, - {file = "matplotlib_inline-0.1.7.tar.gz", hash = "sha256:8423b23ec666be3d16e16b60bdd8ac4e86e840ebd1dd11a30b9f117f2fa0ab90"}, -] - -[package.dependencies] -traitlets = "*" - -[[package]] -name = "mdurl" -version = "0.1.2" -description = "Markdown URL utilities" -optional = false -python-versions = ">=3.7" -files = [ - {file = "mdurl-0.1.2-py3-none-any.whl", hash = "sha256:84008a41e51615a49fc9966191ff91509e3c40b939176e643fd50a5c2196b8f8"}, - {file = "mdurl-0.1.2.tar.gz", hash = "sha256:bb413d29f5eea38f31dd4754dd7377d4465116fb207585f97bf925588687c1ba"}, -] - -[[package]] -name = "numpy" -version = "2.1.1" -description = "Fundamental package for array computing in Python" -optional = false -python-versions = ">=3.10" -files = [ - {file = "numpy-2.1.1-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:c8a0e34993b510fc19b9a2ce7f31cb8e94ecf6e924a40c0c9dd4f62d0aac47d9"}, - {file = "numpy-2.1.1-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:7dd86dfaf7c900c0bbdcb8b16e2f6ddf1eb1fe39c6c8cca6e94844ed3152a8fd"}, - {file = "numpy-2.1.1-cp310-cp310-macosx_14_0_arm64.whl", hash = "sha256:5889dd24f03ca5a5b1e8a90a33b5a0846d8977565e4ae003a63d22ecddf6782f"}, - {file = "numpy-2.1.1-cp310-cp310-macosx_14_0_x86_64.whl", hash = "sha256:59ca673ad11d4b84ceb385290ed0ebe60266e356641428c845b39cd9df6713ab"}, - {file = "numpy-2.1.1-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:13ce49a34c44b6de5241f0b38b07e44c1b2dcacd9e36c30f9c2fcb1bb5135db7"}, - {file = "numpy-2.1.1-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:913cc1d311060b1d409e609947fa1b9753701dac96e6581b58afc36b7ee35af6"}, - {file = "numpy-2.1.1-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:caf5d284ddea7462c32b8d4a6b8af030b6c9fd5332afb70e7414d7fdded4bfd0"}, - {file = "numpy-2.1.1-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:57eb525e7c2a8fdee02d731f647146ff54ea8c973364f3b850069ffb42799647"}, - {file = "numpy-2.1.1-cp310-cp310-win32.whl", hash = "sha256:9a8e06c7a980869ea67bbf551283bbed2856915f0a792dc32dd0f9dd2fb56728"}, - {file = "numpy-2.1.1-cp310-cp310-win_amd64.whl", hash = "sha256:d10c39947a2d351d6d466b4ae83dad4c37cd6c3cdd6d5d0fa797da56f710a6ae"}, - {file = "numpy-2.1.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:0d07841fd284718feffe7dd17a63a2e6c78679b2d386d3e82f44f0108c905550"}, - {file = "numpy-2.1.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:b5613cfeb1adfe791e8e681128f5f49f22f3fcaa942255a6124d58ca59d9528f"}, - {file = "numpy-2.1.1-cp311-cp311-macosx_14_0_arm64.whl", hash = "sha256:0b8cc2715a84b7c3b161f9ebbd942740aaed913584cae9cdc7f8ad5ad41943d0"}, - {file = "numpy-2.1.1-cp311-cp311-macosx_14_0_x86_64.whl", hash = "sha256:b49742cdb85f1f81e4dc1b39dcf328244f4d8d1ded95dea725b316bd2cf18c95"}, - {file = "numpy-2.1.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e8d5f8a8e3bc87334f025194c6193e408903d21ebaeb10952264943a985066ca"}, - {file = "numpy-2.1.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:d51fc141ddbe3f919e91a096ec739f49d686df8af254b2053ba21a910ae518bf"}, - {file = "numpy-2.1.1-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:98ce7fb5b8063cfdd86596b9c762bf2b5e35a2cdd7e967494ab78a1fa7f8b86e"}, - {file = "numpy-2.1.1-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:24c2ad697bd8593887b019817ddd9974a7f429c14a5469d7fad413f28340a6d2"}, - {file = "numpy-2.1.1-cp311-cp311-win32.whl", hash = "sha256:397bc5ce62d3fb73f304bec332171535c187e0643e176a6e9421a6e3eacef06d"}, - {file = "numpy-2.1.1-cp311-cp311-win_amd64.whl", hash = "sha256:ae8ce252404cdd4de56dcfce8b11eac3c594a9c16c231d081fb705cf23bd4d9e"}, - {file = "numpy-2.1.1-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:7c803b7934a7f59563db459292e6aa078bb38b7ab1446ca38dd138646a38203e"}, - {file = "numpy-2.1.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:6435c48250c12f001920f0751fe50c0348f5f240852cfddc5e2f97e007544cbe"}, - {file = "numpy-2.1.1-cp312-cp312-macosx_14_0_arm64.whl", hash = "sha256:3269c9eb8745e8d975980b3a7411a98976824e1fdef11f0aacf76147f662b15f"}, - {file = "numpy-2.1.1-cp312-cp312-macosx_14_0_x86_64.whl", hash = "sha256:fac6e277a41163d27dfab5f4ec1f7a83fac94e170665a4a50191b545721c6521"}, - {file = "numpy-2.1.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:fcd8f556cdc8cfe35e70efb92463082b7f43dd7e547eb071ffc36abc0ca4699b"}, - {file = "numpy-2.1.1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:d2b9cd92c8f8e7b313b80e93cedc12c0112088541dcedd9197b5dee3738c1201"}, - {file = "numpy-2.1.1-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:afd9c680df4de71cd58582b51e88a61feed4abcc7530bcd3d48483f20fc76f2a"}, - {file = "numpy-2.1.1-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:8661c94e3aad18e1ea17a11f60f843a4933ccaf1a25a7c6a9182af70610b2313"}, - {file = "numpy-2.1.1-cp312-cp312-win32.whl", hash = "sha256:950802d17a33c07cba7fd7c3dcfa7d64705509206be1606f196d179e539111ed"}, - {file = "numpy-2.1.1-cp312-cp312-win_amd64.whl", hash = "sha256:3fc5eabfc720db95d68e6646e88f8b399bfedd235994016351b1d9e062c4b270"}, - {file = "numpy-2.1.1-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:046356b19d7ad1890c751b99acad5e82dc4a02232013bd9a9a712fddf8eb60f5"}, - {file = "numpy-2.1.1-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:6e5a9cb2be39350ae6c8f79410744e80154df658d5bea06e06e0ac5bb75480d5"}, - {file = "numpy-2.1.1-cp313-cp313-macosx_14_0_arm64.whl", hash = "sha256:d4c57b68c8ef5e1ebf47238e99bf27657511ec3f071c465f6b1bccbef12d4136"}, - {file = "numpy-2.1.1-cp313-cp313-macosx_14_0_x86_64.whl", hash = "sha256:8ae0fd135e0b157365ac7cc31fff27f07a5572bdfc38f9c2d43b2aff416cc8b0"}, - {file = "numpy-2.1.1-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:981707f6b31b59c0c24bcda52e5605f9701cb46da4b86c2e8023656ad3e833cb"}, - {file = "numpy-2.1.1-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:2ca4b53e1e0b279142113b8c5eb7d7a877e967c306edc34f3b58e9be12fda8df"}, - {file = "numpy-2.1.1-cp313-cp313-musllinux_1_1_x86_64.whl", hash = "sha256:e097507396c0be4e547ff15b13dc3866f45f3680f789c1a1301b07dadd3fbc78"}, - {file = "numpy-2.1.1-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:f7506387e191fe8cdb267f912469a3cccc538ab108471291636a96a54e599556"}, - {file = "numpy-2.1.1-cp313-cp313-win32.whl", hash = "sha256:251105b7c42abe40e3a689881e1793370cc9724ad50d64b30b358bbb3a97553b"}, - {file = "numpy-2.1.1-cp313-cp313-win_amd64.whl", hash = "sha256:f212d4f46b67ff604d11fff7cc62d36b3e8714edf68e44e9760e19be38c03eb0"}, - {file = "numpy-2.1.1-cp313-cp313t-macosx_10_13_x86_64.whl", hash = "sha256:920b0911bb2e4414c50e55bd658baeb78281a47feeb064ab40c2b66ecba85553"}, - {file = "numpy-2.1.1-cp313-cp313t-macosx_11_0_arm64.whl", hash = "sha256:bab7c09454460a487e631ffc0c42057e3d8f2a9ddccd1e60c7bb8ed774992480"}, - {file = "numpy-2.1.1-cp313-cp313t-macosx_14_0_arm64.whl", hash = "sha256:cea427d1350f3fd0d2818ce7350095c1a2ee33e30961d2f0fef48576ddbbe90f"}, - {file = "numpy-2.1.1-cp313-cp313t-macosx_14_0_x86_64.whl", hash = "sha256:e30356d530528a42eeba51420ae8bf6c6c09559051887196599d96ee5f536468"}, - {file = "numpy-2.1.1-cp313-cp313t-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e8dfa9e94fc127c40979c3eacbae1e61fda4fe71d84869cc129e2721973231ef"}, - {file = "numpy-2.1.1-cp313-cp313t-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:910b47a6d0635ec1bd53b88f86120a52bf56dcc27b51f18c7b4a2e2224c29f0f"}, - {file = "numpy-2.1.1-cp313-cp313t-musllinux_1_1_x86_64.whl", hash = "sha256:13cc11c00000848702322af4de0147ced365c81d66053a67c2e962a485b3717c"}, - {file = "numpy-2.1.1-cp313-cp313t-musllinux_1_2_aarch64.whl", hash = "sha256:53e27293b3a2b661c03f79aa51c3987492bd4641ef933e366e0f9f6c9bf257ec"}, - {file = "numpy-2.1.1-pp310-pypy310_pp73-macosx_10_15_x86_64.whl", hash = "sha256:7be6a07520b88214ea85d8ac8b7d6d8a1839b0b5cb87412ac9f49fa934eb15d5"}, - {file = "numpy-2.1.1-pp310-pypy310_pp73-macosx_14_0_x86_64.whl", hash = "sha256:52ac2e48f5ad847cd43c4755520a2317f3380213493b9d8a4c5e37f3b87df504"}, - {file = "numpy-2.1.1-pp310-pypy310_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:50a95ca3560a6058d6ea91d4629a83a897ee27c00630aed9d933dff191f170cd"}, - {file = "numpy-2.1.1-pp310-pypy310_pp73-win_amd64.whl", hash = "sha256:99f4a9ee60eed1385a86e82288971a51e71df052ed0b2900ed30bc840c0f2e39"}, - {file = "numpy-2.1.1.tar.gz", hash = "sha256:d0cf7d55b1051387807405b3898efafa862997b4cba8aa5dbe657be794afeafd"}, -] - -[[package]] -name = "opencv-python" -version = "4.10.0.84" -description = "Wrapper package for OpenCV python bindings." -optional = false -python-versions = ">=3.6" -files = [ - {file = "opencv-python-4.10.0.84.tar.gz", hash = "sha256:72d234e4582e9658ffea8e9cae5b63d488ad06994ef12d81dc303b17472f3526"}, - {file = "opencv_python-4.10.0.84-cp37-abi3-macosx_11_0_arm64.whl", hash = "sha256:fc182f8f4cda51b45f01c64e4cbedfc2f00aff799debebc305d8d0210c43f251"}, - {file = "opencv_python-4.10.0.84-cp37-abi3-macosx_12_0_x86_64.whl", hash = "sha256:71e575744f1d23f79741450254660442785f45a0797212852ee5199ef12eed98"}, - {file = "opencv_python-4.10.0.84-cp37-abi3-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:09a332b50488e2dda866a6c5573ee192fe3583239fb26ff2f7f9ceb0bc119ea6"}, - {file = "opencv_python-4.10.0.84-cp37-abi3-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:9ace140fc6d647fbe1c692bcb2abce768973491222c067c131d80957c595b71f"}, - {file = "opencv_python-4.10.0.84-cp37-abi3-win32.whl", hash = "sha256:2db02bb7e50b703f0a2d50c50ced72e95c574e1e5a0bb35a8a86d0b35c98c236"}, - {file = "opencv_python-4.10.0.84-cp37-abi3-win_amd64.whl", hash = "sha256:32dbbd94c26f611dc5cc6979e6b7aa1f55a64d6b463cc1dcd3c95505a63e48fe"}, -] - -[package.dependencies] -numpy = [ - {version = ">=1.23.5", markers = "python_version >= \"3.11\" and python_version < \"3.12\""}, - {version = ">=1.21.4", markers = "python_version >= \"3.10\" and platform_system == \"Darwin\" and python_version < \"3.11\""}, - {version = ">=1.21.2", markers = "platform_system != \"Darwin\" and python_version >= \"3.10\" and python_version < \"3.11\""}, - {version = ">=1.26.0", markers = "python_version >= \"3.12\""}, -] - -[[package]] -name = "packaging" -version = "24.1" -description = "Core utilities for Python packages" -optional = false -python-versions = ">=3.8" -files = [ - {file = "packaging-24.1-py3-none-any.whl", hash = "sha256:5b8f2217dbdbd2f7f384c41c628544e6d52f2d0f53c6d0c3ea61aa5d1d7ff124"}, - {file = "packaging-24.1.tar.gz", hash = "sha256:026ed72c8ed3fcce5bf8950572258698927fd1dbda10a5e981cdf0ac37f4f002"}, -] - -[[package]] -name = "parso" -version = "0.8.4" -description = "A Python Parser" -optional = false -python-versions = ">=3.6" -files = [ - {file = "parso-0.8.4-py2.py3-none-any.whl", hash = "sha256:a418670a20291dacd2dddc80c377c5c3791378ee1e8d12bffc35420643d43f18"}, - {file = "parso-0.8.4.tar.gz", hash = "sha256:eb3a7b58240fb99099a345571deecc0f9540ea5f4dd2fe14c2a99d6b281ab92d"}, -] - -[package.extras] -qa = ["flake8 (==5.0.4)", "mypy (==0.971)", "types-setuptools (==67.2.0.1)"] -testing = ["docopt", "pytest"] - -[[package]] -name = "pexpect" -version = "4.9.0" -description = "Pexpect allows easy control of interactive console applications." -optional = false -python-versions = "*" -files = [ - {file = "pexpect-4.9.0-py2.py3-none-any.whl", hash = "sha256:7236d1e080e4936be2dc3e326cec0af72acf9212a7e1d060210e70a47e253523"}, - {file = "pexpect-4.9.0.tar.gz", hash = "sha256:ee7d41123f3c9911050ea2c2dac107568dc43b2d3b0c7557a33212c398ead30f"}, -] - -[package.dependencies] -ptyprocess = ">=0.5" - -[[package]] -name = "pillow" -version = "10.4.0" -description = "Python Imaging Library (Fork)" -optional = false -python-versions = ">=3.8" -files = [ - {file = "pillow-10.4.0-cp310-cp310-macosx_10_10_x86_64.whl", hash = "sha256:4d9667937cfa347525b319ae34375c37b9ee6b525440f3ef48542fcf66f2731e"}, - {file = "pillow-10.4.0-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:543f3dc61c18dafb755773efc89aae60d06b6596a63914107f75459cf984164d"}, - {file = "pillow-10.4.0-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:7928ecbf1ece13956b95d9cbcfc77137652b02763ba384d9ab508099a2eca856"}, - {file = "pillow-10.4.0-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:e4d49b85c4348ea0b31ea63bc75a9f3857869174e2bf17e7aba02945cd218e6f"}, - {file = "pillow-10.4.0-cp310-cp310-manylinux_2_28_aarch64.whl", hash = "sha256:6c762a5b0997f5659a5ef2266abc1d8851ad7749ad9a6a5506eb23d314e4f46b"}, - {file = "pillow-10.4.0-cp310-cp310-manylinux_2_28_x86_64.whl", hash = "sha256:a985e028fc183bf12a77a8bbf36318db4238a3ded7fa9df1b9a133f1cb79f8fc"}, - {file = "pillow-10.4.0-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:812f7342b0eee081eaec84d91423d1b4650bb9828eb53d8511bcef8ce5aecf1e"}, - {file = "pillow-10.4.0-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:ac1452d2fbe4978c2eec89fb5a23b8387aba707ac72810d9490118817d9c0b46"}, - {file = "pillow-10.4.0-cp310-cp310-win32.whl", hash = "sha256:bcd5e41a859bf2e84fdc42f4edb7d9aba0a13d29a2abadccafad99de3feff984"}, - {file = "pillow-10.4.0-cp310-cp310-win_amd64.whl", hash = "sha256:ecd85a8d3e79cd7158dec1c9e5808e821feea088e2f69a974db5edf84dc53141"}, - {file = "pillow-10.4.0-cp310-cp310-win_arm64.whl", hash = "sha256:ff337c552345e95702c5fde3158acb0625111017d0e5f24bf3acdb9cc16b90d1"}, - {file = "pillow-10.4.0-cp311-cp311-macosx_10_10_x86_64.whl", hash = "sha256:0a9ec697746f268507404647e531e92889890a087e03681a3606d9b920fbee3c"}, - {file = "pillow-10.4.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:dfe91cb65544a1321e631e696759491ae04a2ea11d36715eca01ce07284738be"}, - {file = "pillow-10.4.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:5dc6761a6efc781e6a1544206f22c80c3af4c8cf461206d46a1e6006e4429ff3"}, - {file = "pillow-10.4.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:5e84b6cc6a4a3d76c153a6b19270b3526a5a8ed6b09501d3af891daa2a9de7d6"}, - {file = "pillow-10.4.0-cp311-cp311-manylinux_2_28_aarch64.whl", hash = "sha256:bbc527b519bd3aa9d7f429d152fea69f9ad37c95f0b02aebddff592688998abe"}, - {file = "pillow-10.4.0-cp311-cp311-manylinux_2_28_x86_64.whl", hash = "sha256:76a911dfe51a36041f2e756b00f96ed84677cdeb75d25c767f296c1c1eda1319"}, - {file = "pillow-10.4.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:59291fb29317122398786c2d44427bbd1a6d7ff54017075b22be9d21aa59bd8d"}, - {file = "pillow-10.4.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:416d3a5d0e8cfe4f27f574362435bc9bae57f679a7158e0096ad2beb427b8696"}, - {file = "pillow-10.4.0-cp311-cp311-win32.whl", hash = "sha256:7086cc1d5eebb91ad24ded9f58bec6c688e9f0ed7eb3dbbf1e4800280a896496"}, - {file = "pillow-10.4.0-cp311-cp311-win_amd64.whl", hash = "sha256:cbed61494057c0f83b83eb3a310f0bf774b09513307c434d4366ed64f4128a91"}, - {file = "pillow-10.4.0-cp311-cp311-win_arm64.whl", hash = "sha256:f5f0c3e969c8f12dd2bb7e0b15d5c468b51e5017e01e2e867335c81903046a22"}, - {file = "pillow-10.4.0-cp312-cp312-macosx_10_10_x86_64.whl", hash = "sha256:673655af3eadf4df6b5457033f086e90299fdd7a47983a13827acf7459c15d94"}, - {file = "pillow-10.4.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:866b6942a92f56300012f5fbac71f2d610312ee65e22f1aa2609e491284e5597"}, - {file = "pillow-10.4.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:29dbdc4207642ea6aad70fbde1a9338753d33fb23ed6956e706936706f52dd80"}, - {file = "pillow-10.4.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:bf2342ac639c4cf38799a44950bbc2dfcb685f052b9e262f446482afaf4bffca"}, - {file = "pillow-10.4.0-cp312-cp312-manylinux_2_28_aarch64.whl", hash = "sha256:f5b92f4d70791b4a67157321c4e8225d60b119c5cc9aee8ecf153aace4aad4ef"}, - {file = "pillow-10.4.0-cp312-cp312-manylinux_2_28_x86_64.whl", hash = "sha256:86dcb5a1eb778d8b25659d5e4341269e8590ad6b4e8b44d9f4b07f8d136c414a"}, - {file = "pillow-10.4.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:780c072c2e11c9b2c7ca37f9a2ee8ba66f44367ac3e5c7832afcfe5104fd6d1b"}, - {file = "pillow-10.4.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:37fb69d905be665f68f28a8bba3c6d3223c8efe1edf14cc4cfa06c241f8c81d9"}, - {file = "pillow-10.4.0-cp312-cp312-win32.whl", hash = "sha256:7dfecdbad5c301d7b5bde160150b4db4c659cee2b69589705b6f8a0c509d9f42"}, - {file = "pillow-10.4.0-cp312-cp312-win_amd64.whl", hash = "sha256:1d846aea995ad352d4bdcc847535bd56e0fd88d36829d2c90be880ef1ee4668a"}, - {file = "pillow-10.4.0-cp312-cp312-win_arm64.whl", hash = "sha256:e553cad5179a66ba15bb18b353a19020e73a7921296a7979c4a2b7f6a5cd57f9"}, - {file = "pillow-10.4.0-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:8bc1a764ed8c957a2e9cacf97c8b2b053b70307cf2996aafd70e91a082e70df3"}, - {file = "pillow-10.4.0-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:6209bb41dc692ddfee4942517c19ee81b86c864b626dbfca272ec0f7cff5d9fb"}, - {file = "pillow-10.4.0-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:bee197b30783295d2eb680b311af15a20a8b24024a19c3a26431ff83eb8d1f70"}, - {file = "pillow-10.4.0-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:1ef61f5dd14c300786318482456481463b9d6b91ebe5ef12f405afbba77ed0be"}, - {file = "pillow-10.4.0-cp313-cp313-manylinux_2_28_aarch64.whl", hash = "sha256:297e388da6e248c98bc4a02e018966af0c5f92dfacf5a5ca22fa01cb3179bca0"}, - {file = "pillow-10.4.0-cp313-cp313-manylinux_2_28_x86_64.whl", hash = "sha256:e4db64794ccdf6cb83a59d73405f63adbe2a1887012e308828596100a0b2f6cc"}, - {file = "pillow-10.4.0-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:bd2880a07482090a3bcb01f4265f1936a903d70bc740bfcb1fd4e8a2ffe5cf5a"}, - {file = "pillow-10.4.0-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:4b35b21b819ac1dbd1233317adeecd63495f6babf21b7b2512d244ff6c6ce309"}, - {file = "pillow-10.4.0-cp313-cp313-win32.whl", hash = "sha256:551d3fd6e9dc15e4c1eb6fc4ba2b39c0c7933fa113b220057a34f4bb3268a060"}, - {file = "pillow-10.4.0-cp313-cp313-win_amd64.whl", hash = "sha256:030abdbe43ee02e0de642aee345efa443740aa4d828bfe8e2eb11922ea6a21ea"}, - {file = "pillow-10.4.0-cp313-cp313-win_arm64.whl", hash = "sha256:5b001114dd152cfd6b23befeb28d7aee43553e2402c9f159807bf55f33af8a8d"}, - {file = "pillow-10.4.0-cp38-cp38-macosx_10_10_x86_64.whl", hash = "sha256:8d4d5063501b6dd4024b8ac2f04962d661222d120381272deea52e3fc52d3736"}, - {file = "pillow-10.4.0-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:7c1ee6f42250df403c5f103cbd2768a28fe1a0ea1f0f03fe151c8741e1469c8b"}, - {file = "pillow-10.4.0-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:b15e02e9bb4c21e39876698abf233c8c579127986f8207200bc8a8f6bb27acf2"}, - {file = "pillow-10.4.0-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:7a8d4bade9952ea9a77d0c3e49cbd8b2890a399422258a77f357b9cc9be8d680"}, - {file = "pillow-10.4.0-cp38-cp38-manylinux_2_28_aarch64.whl", hash = "sha256:43efea75eb06b95d1631cb784aa40156177bf9dd5b4b03ff38979e048258bc6b"}, - {file = "pillow-10.4.0-cp38-cp38-manylinux_2_28_x86_64.whl", hash = "sha256:950be4d8ba92aca4b2bb0741285a46bfae3ca699ef913ec8416c1b78eadd64cd"}, - {file = "pillow-10.4.0-cp38-cp38-musllinux_1_2_aarch64.whl", hash = "sha256:d7480af14364494365e89d6fddc510a13e5a2c3584cb19ef65415ca57252fb84"}, - {file = "pillow-10.4.0-cp38-cp38-musllinux_1_2_x86_64.whl", hash = "sha256:73664fe514b34c8f02452ffb73b7a92c6774e39a647087f83d67f010eb9a0cf0"}, - {file = "pillow-10.4.0-cp38-cp38-win32.whl", hash = "sha256:e88d5e6ad0d026fba7bdab8c3f225a69f063f116462c49892b0149e21b6c0a0e"}, - {file = "pillow-10.4.0-cp38-cp38-win_amd64.whl", hash = "sha256:5161eef006d335e46895297f642341111945e2c1c899eb406882a6c61a4357ab"}, - {file = "pillow-10.4.0-cp39-cp39-macosx_10_10_x86_64.whl", hash = "sha256:0ae24a547e8b711ccaaf99c9ae3cd975470e1a30caa80a6aaee9a2f19c05701d"}, - {file = "pillow-10.4.0-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:298478fe4f77a4408895605f3482b6cc6222c018b2ce565c2b6b9c354ac3229b"}, - {file = "pillow-10.4.0-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:134ace6dc392116566980ee7436477d844520a26a4b1bd4053f6f47d096997fd"}, - {file = "pillow-10.4.0-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:930044bb7679ab003b14023138b50181899da3f25de50e9dbee23b61b4de2126"}, - {file = "pillow-10.4.0-cp39-cp39-manylinux_2_28_aarch64.whl", hash = "sha256:c76e5786951e72ed3686e122d14c5d7012f16c8303a674d18cdcd6d89557fc5b"}, - {file = "pillow-10.4.0-cp39-cp39-manylinux_2_28_x86_64.whl", hash = "sha256:b2724fdb354a868ddf9a880cb84d102da914e99119211ef7ecbdc613b8c96b3c"}, - {file = "pillow-10.4.0-cp39-cp39-musllinux_1_2_aarch64.whl", hash = "sha256:dbc6ae66518ab3c5847659e9988c3b60dc94ffb48ef9168656e0019a93dbf8a1"}, - {file = "pillow-10.4.0-cp39-cp39-musllinux_1_2_x86_64.whl", hash = "sha256:06b2f7898047ae93fad74467ec3d28fe84f7831370e3c258afa533f81ef7f3df"}, - {file = "pillow-10.4.0-cp39-cp39-win32.whl", hash = "sha256:7970285ab628a3779aecc35823296a7869f889b8329c16ad5a71e4901a3dc4ef"}, - {file = "pillow-10.4.0-cp39-cp39-win_amd64.whl", hash = "sha256:961a7293b2457b405967af9c77dcaa43cc1a8cd50d23c532e62d48ab6cdd56f5"}, - {file = "pillow-10.4.0-cp39-cp39-win_arm64.whl", hash = "sha256:32cda9e3d601a52baccb2856b8ea1fc213c90b340c542dcef77140dfa3278a9e"}, - {file = "pillow-10.4.0-pp310-pypy310_pp73-macosx_10_15_x86_64.whl", hash = "sha256:5b4815f2e65b30f5fbae9dfffa8636d992d49705723fe86a3661806e069352d4"}, - {file = "pillow-10.4.0-pp310-pypy310_pp73-macosx_11_0_arm64.whl", hash = "sha256:8f0aef4ef59694b12cadee839e2ba6afeab89c0f39a3adc02ed51d109117b8da"}, - {file = "pillow-10.4.0-pp310-pypy310_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:9f4727572e2918acaa9077c919cbbeb73bd2b3ebcfe033b72f858fc9fbef0026"}, - {file = "pillow-10.4.0-pp310-pypy310_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:ff25afb18123cea58a591ea0244b92eb1e61a1fd497bf6d6384f09bc3262ec3e"}, - {file = "pillow-10.4.0-pp310-pypy310_pp73-manylinux_2_28_aarch64.whl", hash = "sha256:dc3e2db6ba09ffd7d02ae9141cfa0ae23393ee7687248d46a7507b75d610f4f5"}, - {file = "pillow-10.4.0-pp310-pypy310_pp73-manylinux_2_28_x86_64.whl", hash = "sha256:02a2be69f9c9b8c1e97cf2713e789d4e398c751ecfd9967c18d0ce304efbf885"}, - {file = "pillow-10.4.0-pp310-pypy310_pp73-win_amd64.whl", hash = "sha256:0755ffd4a0c6f267cccbae2e9903d95477ca2f77c4fcf3a3a09570001856c8a5"}, - {file = "pillow-10.4.0-pp39-pypy39_pp73-macosx_10_15_x86_64.whl", hash = "sha256:a02364621fe369e06200d4a16558e056fe2805d3468350df3aef21e00d26214b"}, - {file = "pillow-10.4.0-pp39-pypy39_pp73-macosx_11_0_arm64.whl", hash = "sha256:1b5dea9831a90e9d0721ec417a80d4cbd7022093ac38a568db2dd78363b00908"}, - {file = "pillow-10.4.0-pp39-pypy39_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:9b885f89040bb8c4a1573566bbb2f44f5c505ef6e74cec7ab9068c900047f04b"}, - {file = "pillow-10.4.0-pp39-pypy39_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:87dd88ded2e6d74d31e1e0a99a726a6765cda32d00ba72dc37f0651f306daaa8"}, - {file = "pillow-10.4.0-pp39-pypy39_pp73-manylinux_2_28_aarch64.whl", hash = "sha256:2db98790afc70118bd0255c2eeb465e9767ecf1f3c25f9a1abb8ffc8cfd1fe0a"}, - {file = "pillow-10.4.0-pp39-pypy39_pp73-manylinux_2_28_x86_64.whl", hash = "sha256:f7baece4ce06bade126fb84b8af1c33439a76d8a6fd818970215e0560ca28c27"}, - {file = "pillow-10.4.0-pp39-pypy39_pp73-win_amd64.whl", hash = "sha256:cfdd747216947628af7b259d274771d84db2268ca062dd5faf373639d00113a3"}, - {file = "pillow-10.4.0.tar.gz", hash = "sha256:166c1cd4d24309b30d61f79f4a9114b7b2313d7450912277855ff5dfd7cd4a06"}, -] - -[package.extras] -docs = ["furo", "olefile", "sphinx (>=7.3)", "sphinx-copybutton", "sphinx-inline-tabs", "sphinxext-opengraph"] -fpx = ["olefile"] -mic = ["olefile"] -tests = ["check-manifest", "coverage", "defusedxml", "markdown2", "olefile", "packaging", "pyroma", "pytest", "pytest-cov", "pytest-timeout"] -typing = ["typing-extensions"] -xmp = ["defusedxml"] - -[[package]] -name = "prompt-toolkit" -version = "3.0.48" -description = "Library for building powerful interactive command lines in Python" -optional = false -python-versions = ">=3.7.0" -files = [ - {file = "prompt_toolkit-3.0.48-py3-none-any.whl", hash = "sha256:f49a827f90062e411f1ce1f854f2aedb3c23353244f8108b89283587397ac10e"}, - {file = "prompt_toolkit-3.0.48.tar.gz", hash = "sha256:d6623ab0477a80df74e646bdbc93621143f5caf104206aa29294d53de1a03d90"}, -] - -[package.dependencies] -wcwidth = "*" - -[[package]] -name = "ptyprocess" -version = "0.7.0" -description = "Run a subprocess in a pseudo terminal" -optional = false -python-versions = "*" -files = [ - {file = "ptyprocess-0.7.0-py2.py3-none-any.whl", hash = "sha256:4b41f3967fce3af57cc7e94b888626c18bf37a083e3651ca8feeb66d492fef35"}, - {file = "ptyprocess-0.7.0.tar.gz", hash = "sha256:5c5d0a3b48ceee0b48485e0c26037c0acd7d29765ca3fbb5cb3831d347423220"}, -] - -[[package]] -name = "pure-eval" -version = "0.2.3" -description = "Safely evaluate AST nodes without side effects" -optional = false -python-versions = "*" -files = [ - {file = "pure_eval-0.2.3-py3-none-any.whl", hash = "sha256:1db8e35b67b3d218d818ae653e27f06c3aa420901fa7b081ca98cbedc874e0d0"}, - {file = "pure_eval-0.2.3.tar.gz", hash = "sha256:5f4e983f40564c576c7c8635ae88db5956bb2229d7e9237d03b3c0b0190eaf42"}, -] - -[package.extras] -tests = ["pytest"] - -[[package]] -name = "pycolmap" -version = "3.11.1" -description = "COLMAP bindings" -optional = false -python-versions = ">=3.8" -files = [ - {file = "pycolmap-3.11.1-cp310-cp310-macosx_10_15_x86_64.whl", hash = "sha256:52810e9d63c3f2d5e0e0ebac97b453c14ca06f42072ede26fe9bc5207e5f32ea"}, - {file = "pycolmap-3.11.1-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:92d12806ed7252e2c8f9584d2751e3afacbd21be5150d8f24c52b067c67695ab"}, - {file = "pycolmap-3.11.1-cp310-cp310-manylinux_2_28_x86_64.whl", hash = "sha256:413b95d933b8ed10ece2011cbd80fe32704464b5ba38cfbc978dec68757dfaec"}, - {file = "pycolmap-3.11.1-cp310-cp310-win_amd64.whl", hash = "sha256:b3bb1831287246b0825a17f9ee19e90d18fbfe096eada7b89bdee3a1d8c5e040"}, - {file = "pycolmap-3.11.1-cp311-cp311-macosx_10_15_x86_64.whl", hash = "sha256:1949ca7eaa0a74ff76d3758d10496a0147d98bb89c6c7aad2514f1c70d88b852"}, - {file = "pycolmap-3.11.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:7c8f9679a78fa68e3b718f5efc87d520012330c32b1c0c1321766addda7903e5"}, - {file = "pycolmap-3.11.1-cp311-cp311-manylinux_2_28_x86_64.whl", hash = "sha256:9bb98585e540a403df718b26ffdf475eba74891d16bf59ba94eef0f3acb827a5"}, - {file = "pycolmap-3.11.1-cp311-cp311-win_amd64.whl", hash = "sha256:f41e1c057b5acfd4363aac0c85960fd880b612c93b96569bdc188b743e31ec0d"}, - {file = "pycolmap-3.11.1-cp312-cp312-macosx_10_15_x86_64.whl", hash = "sha256:994dc06fb94d733897cf696df25f1217f3491f34b3c26354ceee5a5e60f7a22b"}, - {file = "pycolmap-3.11.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:6d3541c671b7e61f5e381ed6a08de522f4f26ada957cecff1f8e7f964f03d3d7"}, - {file = "pycolmap-3.11.1-cp312-cp312-manylinux_2_28_x86_64.whl", hash = "sha256:14f04f48d13358e9418d71b3a806f1aa39ab0b2a35904907f74142e4964b098b"}, - {file = "pycolmap-3.11.1-cp312-cp312-win_amd64.whl", hash = "sha256:e023af9e4fb54c5e2dec23ff7410eedfa79d53f5f8eeac31f435cf560a9e4c94"}, - {file = "pycolmap-3.11.1-cp38-cp38-macosx_10_15_x86_64.whl", hash = "sha256:f7ab7704f0692347027e17cb218bf1e56933a670561a988fe2d3608a7b836d38"}, - {file = "pycolmap-3.11.1-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:aa51d8adbd52b310ec46f71220443acf5d54d1ec5f809fba741774a7532a78e8"}, - {file = "pycolmap-3.11.1-cp38-cp38-manylinux_2_28_x86_64.whl", hash = "sha256:9ee22f77230fb92519327a5bfb48c9f9624840a5103007a0fc62b2b9940221b5"}, - {file = "pycolmap-3.11.1-cp38-cp38-win_amd64.whl", hash = "sha256:d9f94f5d4134a3b29d38e85e07aa88ae502567fd549bc000312a5d4f3932cb9f"}, - {file = "pycolmap-3.11.1-cp39-cp39-macosx_10_15_x86_64.whl", hash = "sha256:0564490d3511ccadd3dc0e7e640f1109fda1e59b883041ce744a08f1393abb52"}, - {file = "pycolmap-3.11.1-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:c7e107117837ccd0a4b6a22adc5a26849afed26b0d2ddde354e402614e5cad51"}, - {file = "pycolmap-3.11.1-cp39-cp39-manylinux_2_28_x86_64.whl", hash = "sha256:2c6d3671f84eebd005ae5b77d39a8fad5bf49d85caea49ef81f87325316437d1"}, - {file = "pycolmap-3.11.1-cp39-cp39-win_amd64.whl", hash = "sha256:26dcd876aceca8dffa8877c4beefda68b1ce37369621b27c5ae6fed8409cb41d"}, -] - -[package.dependencies] -numpy = "*" - -[[package]] -name = "pygeodesy" -version = "24.9.29" -description = "Pure Python geodesy tools" -optional = false -python-versions = "*" -files = [ - {file = "PyGeodesy-24.9.29-py2.py3-none-any.whl", hash = "sha256:754f2cf603bb54315257e8eb619c286457cea0ae64d802abb6c0088155dc45c4"}, - {file = "PyGeodesy-24.9.29.zip", hash = "sha256:c28ce86d450f7a7e8d5c432cec15cc7c01fded6b4e240aa0b07d20c46cc84038"}, -] - -[[package]] -name = "pygments" -version = "2.18.0" -description = "Pygments is a syntax highlighting package written in Python." -optional = false -python-versions = ">=3.8" -files = [ - {file = "pygments-2.18.0-py3-none-any.whl", hash = "sha256:b8e6aca0523f3ab76fee51799c488e38782ac06eafcf95e7ba832985c8e7b13a"}, - {file = "pygments-2.18.0.tar.gz", hash = "sha256:786ff802f32e91311bff3889f6e9a86e81505fe99f2735bb6d60ae0c5004f199"}, -] - -[package.extras] -windows-terminal = ["colorama (>=0.4.6)"] - -[[package]] -name = "pyparsing" -version = "3.1.4" -description = "pyparsing module - Classes and methods to define and execute parsing grammars" -optional = false -python-versions = ">=3.6.8" -files = [ - {file = "pyparsing-3.1.4-py3-none-any.whl", hash = "sha256:a6a7ee4235a3f944aa1fa2249307708f893fe5717dc603503c6c7969c070fb7c"}, - {file = "pyparsing-3.1.4.tar.gz", hash = "sha256:f86ec8d1a83f11977c9a6ea7598e8c27fc5cddfa5b07ea2241edbbde1d7bc032"}, -] - -[package.extras] -diagrams = ["jinja2", "railroad-diagrams"] - -[[package]] -name = "pyshp" -version = "2.3.1" -description = "Pure Python read/write support for ESRI Shapefile format" -optional = false -python-versions = ">=2.7" -files = [ - {file = "pyshp-2.3.1-py2.py3-none-any.whl", hash = "sha256:67024c0ccdc352ba5db777c4e968483782dfa78f8e200672a90d2d30fd8b7b49"}, - {file = "pyshp-2.3.1.tar.gz", hash = "sha256:4caec82fd8dd096feba8217858068bacb2a3b5950f43c048c6dc32a3489d5af1"}, -] - -[[package]] -name = "python-dateutil" -version = "2.9.0.post0" -description = "Extensions to the standard Python datetime module" -optional = false -python-versions = "!=3.0.*,!=3.1.*,!=3.2.*,>=2.7" -files = [ - {file = "python-dateutil-2.9.0.post0.tar.gz", hash = "sha256:37dd54208da7e1cd875388217d5e00ebd4179249f90fb72437e91a35459a0ad3"}, - {file = "python_dateutil-2.9.0.post0-py2.py3-none-any.whl", hash = "sha256:a8b2bc7bffae282281c8140a97d3aa9c14da0b136dfe83f850eea9a5f7470427"}, -] - -[package.dependencies] -six = ">=1.5" - -[[package]] -name = "pytz" -version = "2024.2" -description = "World timezone definitions, modern and historical" -optional = false -python-versions = "*" -files = [ - {file = "pytz-2024.2-py2.py3-none-any.whl", hash = "sha256:31c7c1817eb7fae7ca4b8c7ee50c72f93aa2dd863de768e1ef4245d426aa0725"}, - {file = "pytz-2024.2.tar.gz", hash = "sha256:2aa355083c50a0f93fa581709deac0c9ad65cca8a9e9beac660adcbd493c798a"}, -] - -[[package]] -name = "pyyaml" -version = "6.0.2" -description = "YAML parser and emitter for Python" -optional = false -python-versions = ">=3.8" -files = [ - {file = "PyYAML-6.0.2-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:0a9a2848a5b7feac301353437eb7d5957887edbf81d56e903999a75a3d743086"}, - {file = "PyYAML-6.0.2-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:29717114e51c84ddfba879543fb232a6ed60086602313ca38cce623c1d62cfbf"}, - {file = "PyYAML-6.0.2-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:8824b5a04a04a047e72eea5cec3bc266db09e35de6bdfe34c9436ac5ee27d237"}, - {file = "PyYAML-6.0.2-cp310-cp310-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:7c36280e6fb8385e520936c3cb3b8042851904eba0e58d277dca80a5cfed590b"}, - {file = "PyYAML-6.0.2-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:ec031d5d2feb36d1d1a24380e4db6d43695f3748343d99434e6f5f9156aaa2ed"}, - {file = "PyYAML-6.0.2-cp310-cp310-musllinux_1_1_aarch64.whl", hash = "sha256:936d68689298c36b53b29f23c6dbb74de12b4ac12ca6cfe0e047bedceea56180"}, - {file = "PyYAML-6.0.2-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:23502f431948090f597378482b4812b0caae32c22213aecf3b55325e049a6c68"}, - {file = "PyYAML-6.0.2-cp310-cp310-win32.whl", hash = "sha256:2e99c6826ffa974fe6e27cdb5ed0021786b03fc98e5ee3c5bfe1fd5015f42b99"}, - {file = "PyYAML-6.0.2-cp310-cp310-win_amd64.whl", hash = "sha256:a4d3091415f010369ae4ed1fc6b79def9416358877534caf6a0fdd2146c87a3e"}, - {file = "PyYAML-6.0.2-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:cc1c1159b3d456576af7a3e4d1ba7e6924cb39de8f67111c735f6fc832082774"}, - {file = "PyYAML-6.0.2-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:1e2120ef853f59c7419231f3bf4e7021f1b936f6ebd222406c3b60212205d2ee"}, - {file = "PyYAML-6.0.2-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:5d225db5a45f21e78dd9358e58a98702a0302f2659a3c6cd320564b75b86f47c"}, - {file = "PyYAML-6.0.2-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:5ac9328ec4831237bec75defaf839f7d4564be1e6b25ac710bd1a96321cc8317"}, - {file = "PyYAML-6.0.2-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:3ad2a3decf9aaba3d29c8f537ac4b243e36bef957511b4766cb0057d32b0be85"}, - {file = "PyYAML-6.0.2-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:ff3824dc5261f50c9b0dfb3be22b4567a6f938ccce4587b38952d85fd9e9afe4"}, - {file = "PyYAML-6.0.2-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:797b4f722ffa07cc8d62053e4cff1486fa6dc094105d13fea7b1de7d8bf71c9e"}, - {file = "PyYAML-6.0.2-cp311-cp311-win32.whl", hash = "sha256:11d8f3dd2b9c1207dcaf2ee0bbbfd5991f571186ec9cc78427ba5bd32afae4b5"}, - {file = "PyYAML-6.0.2-cp311-cp311-win_amd64.whl", hash = "sha256:e10ce637b18caea04431ce14fabcf5c64a1c61ec9c56b071a4b7ca131ca52d44"}, - {file = "PyYAML-6.0.2-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:c70c95198c015b85feafc136515252a261a84561b7b1d51e3384e0655ddf25ab"}, - {file = "PyYAML-6.0.2-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:ce826d6ef20b1bc864f0a68340c8b3287705cae2f8b4b1d932177dcc76721725"}, - {file = "PyYAML-6.0.2-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:1f71ea527786de97d1a0cc0eacd1defc0985dcf6b3f17bb77dcfc8c34bec4dc5"}, - {file = "PyYAML-6.0.2-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:9b22676e8097e9e22e36d6b7bda33190d0d400f345f23d4065d48f4ca7ae0425"}, - {file = "PyYAML-6.0.2-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:80bab7bfc629882493af4aa31a4cfa43a4c57c83813253626916b8c7ada83476"}, - {file = "PyYAML-6.0.2-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:0833f8694549e586547b576dcfaba4a6b55b9e96098b36cdc7ebefe667dfed48"}, - {file = "PyYAML-6.0.2-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:8b9c7197f7cb2738065c481a0461e50ad02f18c78cd75775628afb4d7137fb3b"}, - {file = "PyYAML-6.0.2-cp312-cp312-win32.whl", hash = "sha256:ef6107725bd54b262d6dedcc2af448a266975032bc85ef0172c5f059da6325b4"}, - {file = "PyYAML-6.0.2-cp312-cp312-win_amd64.whl", hash = "sha256:7e7401d0de89a9a855c839bc697c079a4af81cf878373abd7dc625847d25cbd8"}, - {file = "PyYAML-6.0.2-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:efdca5630322a10774e8e98e1af481aad470dd62c3170801852d752aa7a783ba"}, - {file = "PyYAML-6.0.2-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:50187695423ffe49e2deacb8cd10510bc361faac997de9efef88badc3bb9e2d1"}, - {file = "PyYAML-6.0.2-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:0ffe8360bab4910ef1b9e87fb812d8bc0a308b0d0eef8c8f44e0254ab3b07133"}, - {file = "PyYAML-6.0.2-cp313-cp313-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:17e311b6c678207928d649faa7cb0d7b4c26a0ba73d41e99c4fff6b6c3276484"}, - {file = "PyYAML-6.0.2-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:70b189594dbe54f75ab3a1acec5f1e3faa7e8cf2f1e08d9b561cb41b845f69d5"}, - {file = "PyYAML-6.0.2-cp313-cp313-musllinux_1_1_aarch64.whl", hash = "sha256:41e4e3953a79407c794916fa277a82531dd93aad34e29c2a514c2c0c5fe971cc"}, - {file = "PyYAML-6.0.2-cp313-cp313-musllinux_1_1_x86_64.whl", hash = "sha256:68ccc6023a3400877818152ad9a1033e3db8625d899c72eacb5a668902e4d652"}, - {file = "PyYAML-6.0.2-cp313-cp313-win32.whl", hash = "sha256:bc2fa7c6b47d6bc618dd7fb02ef6fdedb1090ec036abab80d4681424b84c1183"}, - {file = "PyYAML-6.0.2-cp313-cp313-win_amd64.whl", hash = "sha256:8388ee1976c416731879ac16da0aff3f63b286ffdd57cdeb95f3f2e085687563"}, - {file = "PyYAML-6.0.2-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:24471b829b3bf607e04e88d79542a9d48bb037c2267d7927a874e6c205ca7e9a"}, - {file = "PyYAML-6.0.2-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d7fded462629cfa4b685c5416b949ebad6cec74af5e2d42905d41e257e0869f5"}, - {file = "PyYAML-6.0.2-cp38-cp38-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:d84a1718ee396f54f3a086ea0a66d8e552b2ab2017ef8b420e92edbc841c352d"}, - {file = "PyYAML-6.0.2-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:9056c1ecd25795207ad294bcf39f2db3d845767be0ea6e6a34d856f006006083"}, - {file = "PyYAML-6.0.2-cp38-cp38-musllinux_1_1_x86_64.whl", hash = "sha256:82d09873e40955485746739bcb8b4586983670466c23382c19cffecbf1fd8706"}, - {file = "PyYAML-6.0.2-cp38-cp38-win32.whl", hash = "sha256:43fa96a3ca0d6b1812e01ced1044a003533c47f6ee8aca31724f78e93ccc089a"}, - {file = "PyYAML-6.0.2-cp38-cp38-win_amd64.whl", hash = "sha256:01179a4a8559ab5de078078f37e5c1a30d76bb88519906844fd7bdea1b7729ff"}, - {file = "PyYAML-6.0.2-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:688ba32a1cffef67fd2e9398a2efebaea461578b0923624778664cc1c914db5d"}, - {file = "PyYAML-6.0.2-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:a8786accb172bd8afb8be14490a16625cbc387036876ab6ba70912730faf8e1f"}, - {file = "PyYAML-6.0.2-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d8e03406cac8513435335dbab54c0d385e4a49e4945d2909a581c83647ca0290"}, - {file = "PyYAML-6.0.2-cp39-cp39-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:f753120cb8181e736c57ef7636e83f31b9c0d1722c516f7e86cf15b7aa57ff12"}, - {file = "PyYAML-6.0.2-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:3b1fdb9dc17f5a7677423d508ab4f243a726dea51fa5e70992e59a7411c89d19"}, - {file = "PyYAML-6.0.2-cp39-cp39-musllinux_1_1_aarch64.whl", hash = "sha256:0b69e4ce7a131fe56b7e4d770c67429700908fc0752af059838b1cfb41960e4e"}, - {file = "PyYAML-6.0.2-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:a9f8c2e67970f13b16084e04f134610fd1d374bf477b17ec1599185cf611d725"}, - {file = "PyYAML-6.0.2-cp39-cp39-win32.whl", hash = "sha256:6395c297d42274772abc367baaa79683958044e5d3835486c16da75d2a694631"}, - {file = "PyYAML-6.0.2-cp39-cp39-win_amd64.whl", hash = "sha256:39693e1f8320ae4f43943590b49779ffb98acb81f788220ea932a6b6c51004d8"}, - {file = "pyyaml-6.0.2.tar.gz", hash = "sha256:d584d9ec91ad65861cc08d42e834324ef890a082e591037abe114850ff7bbc3e"}, -] - -[[package]] -name = "rich" -version = "13.9.1" -description = "Render rich text, tables, progress bars, syntax highlighting, markdown and more to the terminal" -optional = false -python-versions = ">=3.8.0" -files = [ - {file = "rich-13.9.1-py3-none-any.whl", hash = "sha256:b340e739f30aa58921dc477b8adaa9ecdb7cecc217be01d93730ee1bc8aa83be"}, - {file = "rich-13.9.1.tar.gz", hash = "sha256:097cffdf85db1babe30cc7deba5ab3a29e1b9885047dab24c57e9a7f8a9c1466"}, -] - -[package.dependencies] -markdown-it-py = ">=2.2.0" -pygments = ">=2.13.0,<3.0.0" -typing-extensions = {version = ">=4.0.0,<5.0", markers = "python_version < \"3.11\""} - -[package.extras] -jupyter = ["ipywidgets (>=7.5.1,<9)"] - -[[package]] -name = "scipy" -version = "1.14.1" -description = "Fundamental algorithms for scientific computing in Python" -optional = false -python-versions = ">=3.10" -files = [ - {file = "scipy-1.14.1-cp310-cp310-macosx_10_13_x86_64.whl", hash = "sha256:b28d2ca4add7ac16ae8bb6632a3c86e4b9e4d52d3e34267f6e1b0c1f8d87e389"}, - {file = "scipy-1.14.1-cp310-cp310-macosx_12_0_arm64.whl", hash = "sha256:d0d2821003174de06b69e58cef2316a6622b60ee613121199cb2852a873f8cf3"}, - {file = "scipy-1.14.1-cp310-cp310-macosx_14_0_arm64.whl", hash = "sha256:8bddf15838ba768bb5f5083c1ea012d64c9a444e16192762bd858f1e126196d0"}, - {file = "scipy-1.14.1-cp310-cp310-macosx_14_0_x86_64.whl", hash = "sha256:97c5dddd5932bd2a1a31c927ba5e1463a53b87ca96b5c9bdf5dfd6096e27efc3"}, - {file = "scipy-1.14.1-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:2ff0a7e01e422c15739ecd64432743cf7aae2b03f3084288f399affcefe5222d"}, - {file = "scipy-1.14.1-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:8e32dced201274bf96899e6491d9ba3e9a5f6b336708656466ad0522d8528f69"}, - {file = "scipy-1.14.1-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:8426251ad1e4ad903a4514712d2fa8fdd5382c978010d1c6f5f37ef286a713ad"}, - {file = "scipy-1.14.1-cp310-cp310-win_amd64.whl", hash = "sha256:a49f6ed96f83966f576b33a44257d869756df6cf1ef4934f59dd58b25e0327e5"}, - {file = "scipy-1.14.1-cp311-cp311-macosx_10_13_x86_64.whl", hash = "sha256:2da0469a4ef0ecd3693761acbdc20f2fdeafb69e6819cc081308cc978153c675"}, - {file = "scipy-1.14.1-cp311-cp311-macosx_12_0_arm64.whl", hash = "sha256:c0ee987efa6737242745f347835da2cc5bb9f1b42996a4d97d5c7ff7928cb6f2"}, - {file = "scipy-1.14.1-cp311-cp311-macosx_14_0_arm64.whl", hash = "sha256:3a1b111fac6baec1c1d92f27e76511c9e7218f1695d61b59e05e0fe04dc59617"}, - {file = "scipy-1.14.1-cp311-cp311-macosx_14_0_x86_64.whl", hash = "sha256:8475230e55549ab3f207bff11ebfc91c805dc3463ef62eda3ccf593254524ce8"}, - {file = "scipy-1.14.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:278266012eb69f4a720827bdd2dc54b2271c97d84255b2faaa8f161a158c3b37"}, - {file = "scipy-1.14.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:fef8c87f8abfb884dac04e97824b61299880c43f4ce675dd2cbeadd3c9b466d2"}, - {file = "scipy-1.14.1-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:b05d43735bb2f07d689f56f7b474788a13ed8adc484a85aa65c0fd931cf9ccd2"}, - {file = "scipy-1.14.1-cp311-cp311-win_amd64.whl", hash = "sha256:716e389b694c4bb564b4fc0c51bc84d381735e0d39d3f26ec1af2556ec6aad94"}, - {file = "scipy-1.14.1-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:631f07b3734d34aced009aaf6fedfd0eb3498a97e581c3b1e5f14a04164a456d"}, - {file = "scipy-1.14.1-cp312-cp312-macosx_12_0_arm64.whl", hash = "sha256:af29a935803cc707ab2ed7791c44288a682f9c8107bc00f0eccc4f92c08d6e07"}, - {file = "scipy-1.14.1-cp312-cp312-macosx_14_0_arm64.whl", hash = "sha256:2843f2d527d9eebec9a43e6b406fb7266f3af25a751aa91d62ff416f54170bc5"}, - {file = "scipy-1.14.1-cp312-cp312-macosx_14_0_x86_64.whl", hash = "sha256:eb58ca0abd96911932f688528977858681a59d61a7ce908ffd355957f7025cfc"}, - {file = "scipy-1.14.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:30ac8812c1d2aab7131a79ba62933a2a76f582d5dbbc695192453dae67ad6310"}, - {file = "scipy-1.14.1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:8f9ea80f2e65bdaa0b7627fb00cbeb2daf163caa015e59b7516395fe3bd1e066"}, - {file = "scipy-1.14.1-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:edaf02b82cd7639db00dbff629995ef185c8df4c3ffa71a5562a595765a06ce1"}, - {file = "scipy-1.14.1-cp312-cp312-win_amd64.whl", hash = "sha256:2ff38e22128e6c03ff73b6bb0f85f897d2362f8c052e3b8ad00532198fbdae3f"}, - {file = "scipy-1.14.1-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:1729560c906963fc8389f6aac023739ff3983e727b1a4d87696b7bf108316a79"}, - {file = "scipy-1.14.1-cp313-cp313-macosx_12_0_arm64.whl", hash = "sha256:4079b90df244709e675cdc8b93bfd8a395d59af40b72e339c2287c91860deb8e"}, - {file = "scipy-1.14.1-cp313-cp313-macosx_14_0_arm64.whl", hash = "sha256:e0cf28db0f24a38b2a0ca33a85a54852586e43cf6fd876365c86e0657cfe7d73"}, - {file = "scipy-1.14.1-cp313-cp313-macosx_14_0_x86_64.whl", hash = "sha256:0c2f95de3b04e26f5f3ad5bb05e74ba7f68b837133a4492414b3afd79dfe540e"}, - {file = "scipy-1.14.1-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:b99722ea48b7ea25e8e015e8341ae74624f72e5f21fc2abd45f3a93266de4c5d"}, - {file = "scipy-1.14.1-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:5149e3fd2d686e42144a093b206aef01932a0059c2a33ddfa67f5f035bdfe13e"}, - {file = "scipy-1.14.1-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:e4f5a7c49323533f9103d4dacf4e4f07078f360743dec7f7596949149efeec06"}, - {file = "scipy-1.14.1-cp313-cp313-win_amd64.whl", hash = "sha256:baff393942b550823bfce952bb62270ee17504d02a1801d7fd0719534dfb9c84"}, - {file = "scipy-1.14.1.tar.gz", hash = "sha256:5a275584e726026a5699459aa72f828a610821006228e841b94275c4a7c08417"}, -] - -[package.dependencies] -numpy = ">=1.23.5,<2.3" - -[package.extras] -dev = ["cython-lint (>=0.12.2)", "doit (>=0.36.0)", "mypy (==1.10.0)", "pycodestyle", "pydevtool", "rich-click", "ruff (>=0.0.292)", "types-psutil", "typing_extensions"] -doc = ["jupyterlite-pyodide-kernel", "jupyterlite-sphinx (>=0.13.1)", "jupytext", "matplotlib (>=3.5)", "myst-nb", "numpydoc", "pooch", "pydata-sphinx-theme (>=0.15.2)", "sphinx (>=5.0.0,<=7.3.7)", "sphinx-design (>=0.4.0)"] -test = ["Cython", "array-api-strict (>=2.0)", "asv", "gmpy2", "hypothesis (>=6.30)", "meson", "mpmath", "ninja", "pooch", "pytest", "pytest-cov", "pytest-timeout", "pytest-xdist", "scikit-umfpack", "threadpoolctl"] - -[[package]] -name = "scriptconfig" -version = "0.8.0" -description = "Easy dict-based script configuration with CLI support" -optional = false -python-versions = ">=3.6" -files = [ - {file = "scriptconfig-0.8.0-py3-none-any.whl", hash = "sha256:c327e5cc4f136d4c87d08b97b4ae7ac20cbcb4f9120fd029442066758c3d2d36"}, - {file = "scriptconfig-0.8.0.tar.gz", hash = "sha256:d641365029d784cee577cfb8c4a213b83f05e9c2ea17329af0f707941326c975"}, -] - -[package.dependencies] -PyYAML = [ - {version = ">=6.0", markers = "python_version < \"3.12\" and python_version >= \"3.10\""}, - {version = ">=6.0.1", markers = "python_version < \"4.0\" and python_version >= \"3.12\""}, -] -ubelt = ">=1.3.6" - -[package.extras] -all = ["PyYAML (>=5.4.1)", "PyYAML (>=5.4.1)", "PyYAML (>=5.4.1)", "PyYAML (>=5.4.1)", "PyYAML (>=6.0)", "PyYAML (>=6.0)", "PyYAML (>=6.0.1)", "argcomplete (>=3.0.5)", "coverage (>=4.3.4)", "coverage (>=4.5)", "coverage (>=5.3.1)", "coverage (>=5.3.1)", "coverage (>=5.3.1)", "coverage (>=6.1.1)", "coverage (>=6.1.1)", "coverage (>=6.1.1)", "coverage (>=6.1.1)", "numpy (>=1.11.1)", "numpy (>=1.11.1)", "numpy (>=1.11.1)", "numpy (>=1.12.0)", "numpy (>=1.14.5)", "numpy (>=1.19.2)", "numpy (>=1.19.3)", "numpy (>=1.21.6)", "numpy (>=1.23.2)", "numpy (>=1.26.0)", "omegaconf (>=2.2.2)", "pytest (>=4.6.0)", "pytest (>=4.6.0)", "pytest (>=4.6.0,<=4.6.11)", "pytest (>=4.6.0,<=4.6.11)", "pytest (>=4.6.0,<=6.1.2)", "pytest (>=6.2.5)", "pytest-cov (>=2.8.1)", "pytest-cov (>=2.8.1)", "pytest-cov (>=2.9.0)", "pytest-cov (>=3.0.0)", "rich-argparse (>=1.1.0)", "ubelt (>=1.3.6)", "xdoctest (>=1.1.5)"] -all-strict = ["PyYAML (==5.4.1)", "PyYAML (==5.4.1)", "PyYAML (==5.4.1)", "PyYAML (==5.4.1)", "PyYAML (==6.0)", "PyYAML (==6.0)", "PyYAML (==6.0.1)", "argcomplete (==3.0.5)", "coverage (==4.3.4)", "coverage (==4.5)", "coverage (==5.3.1)", "coverage (==5.3.1)", "coverage (==5.3.1)", "coverage (==6.1.1)", "coverage (==6.1.1)", "coverage (==6.1.1)", "coverage (==6.1.1)", "numpy (==1.11.1)", "numpy (==1.11.1)", "numpy (==1.11.1)", "numpy (==1.12.0)", "numpy (==1.14.5)", "numpy (==1.19.2)", "numpy (==1.19.3)", "numpy (==1.21.6)", "numpy (==1.23.2)", "numpy (==1.26.0)", "omegaconf (==2.2.2)", "pytest (==4.6.0)", "pytest (==4.6.0)", "pytest (==4.6.0)", "pytest (==4.6.0)", "pytest (==4.6.0)", "pytest (==6.2.5)", "pytest-cov (==2.8.1)", "pytest-cov (==2.8.1)", "pytest-cov (==2.9.0)", "pytest-cov (==3.0.0)", "rich-argparse (==1.1.0)", "ubelt (==1.3.6)", "xdoctest (==1.1.5)"] -optional = ["argcomplete (>=3.0.5)", "numpy (>=1.11.1)", "numpy (>=1.11.1)", "numpy (>=1.11.1)", "numpy (>=1.12.0)", "numpy (>=1.14.5)", "numpy (>=1.19.2)", "numpy (>=1.19.3)", "numpy (>=1.21.6)", "numpy (>=1.23.2)", "numpy (>=1.26.0)", "omegaconf (>=2.2.2)", "rich-argparse (>=1.1.0)"] -optional-strict = ["argcomplete (==3.0.5)", "numpy (==1.11.1)", "numpy (==1.11.1)", "numpy (==1.11.1)", "numpy (==1.12.0)", "numpy (==1.14.5)", "numpy (==1.19.2)", "numpy (==1.19.3)", "numpy (==1.21.6)", "numpy (==1.23.2)", "numpy (==1.26.0)", "omegaconf (==2.2.2)", "rich-argparse (==1.1.0)"] -runtime-strict = ["PyYAML (==5.4.1)", "PyYAML (==5.4.1)", "PyYAML (==5.4.1)", "PyYAML (==5.4.1)", "PyYAML (==6.0)", "PyYAML (==6.0)", "PyYAML (==6.0.1)", "ubelt (==1.3.6)"] -tests = ["coverage (>=4.3.4)", "coverage (>=4.5)", "coverage (>=5.3.1)", "coverage (>=5.3.1)", "coverage (>=5.3.1)", "coverage (>=6.1.1)", "coverage (>=6.1.1)", "coverage (>=6.1.1)", "coverage (>=6.1.1)", "pytest (>=4.6.0)", "pytest (>=4.6.0)", "pytest (>=4.6.0,<=4.6.11)", "pytest (>=4.6.0,<=4.6.11)", "pytest (>=4.6.0,<=6.1.2)", "pytest (>=6.2.5)", "pytest-cov (>=2.8.1)", "pytest-cov (>=2.8.1)", "pytest-cov (>=2.9.0)", "pytest-cov (>=3.0.0)", "xdoctest (>=1.1.5)"] -tests-strict = ["coverage (==4.3.4)", "coverage (==4.5)", "coverage (==5.3.1)", "coverage (==5.3.1)", "coverage (==5.3.1)", "coverage (==6.1.1)", "coverage (==6.1.1)", "coverage (==6.1.1)", "coverage (==6.1.1)", "pytest (==4.6.0)", "pytest (==4.6.0)", "pytest (==4.6.0)", "pytest (==4.6.0)", "pytest (==4.6.0)", "pytest (==6.2.5)", "pytest-cov (==2.8.1)", "pytest-cov (==2.8.1)", "pytest-cov (==2.9.0)", "pytest-cov (==3.0.0)", "xdoctest (==1.1.5)"] - -[[package]] -name = "setuptools" -version = "75.1.0" -description = "Easily download, build, install, upgrade, and uninstall Python packages" -optional = false -python-versions = ">=3.8" -files = [ - {file = "setuptools-75.1.0-py3-none-any.whl", hash = "sha256:35ab7fd3bcd95e6b7fd704e4a1539513edad446c097797f2985e0e4b960772f2"}, - {file = "setuptools-75.1.0.tar.gz", hash = "sha256:d59a21b17a275fb872a9c3dae73963160ae079f1049ed956880cd7c09b120538"}, -] - -[package.extras] -check = ["pytest-checkdocs (>=2.4)", "pytest-ruff (>=0.2.1)", "ruff (>=0.5.2)"] -core = ["importlib-metadata (>=6)", "importlib-resources (>=5.10.2)", "jaraco.collections", "jaraco.functools", "jaraco.text (>=3.7)", "more-itertools", "more-itertools (>=8.8)", "packaging", "packaging (>=24)", "platformdirs (>=2.6.2)", "tomli (>=2.0.1)", "wheel (>=0.43.0)"] -cover = ["pytest-cov"] -doc = ["furo", "jaraco.packaging (>=9.3)", "jaraco.tidelift (>=1.4)", "pygments-github-lexers (==0.0.5)", "pyproject-hooks (!=1.1)", "rst.linker (>=1.9)", "sphinx (>=3.5)", "sphinx-favicon", "sphinx-inline-tabs", "sphinx-lint", "sphinx-notfound-page (>=1,<2)", "sphinx-reredirects", "sphinxcontrib-towncrier", "towncrier (<24.7)"] -enabler = ["pytest-enabler (>=2.2)"] -test = ["build[virtualenv] (>=1.0.3)", "filelock (>=3.4.0)", "ini2toml[lite] (>=0.14)", "jaraco.develop (>=7.21)", "jaraco.envs (>=2.2)", "jaraco.path (>=3.2.0)", "jaraco.test", "packaging (>=23.2)", "pip (>=19.1)", "pyproject-hooks (!=1.1)", "pytest (>=6,!=8.1.*)", "pytest-home (>=0.5)", "pytest-perf", "pytest-subprocess", "pytest-timeout", "pytest-xdist (>=3)", "tomli-w (>=1.0.0)", "virtualenv (>=13.0.0)", "wheel (>=0.44.0)"] -type = ["importlib-metadata (>=7.0.2)", "jaraco.develop (>=7.21)", "mypy (==1.11.*)", "pytest-mypy"] - -[[package]] -name = "shapely" -version = "2.0.6" -description = "Manipulation and analysis of geometric objects" -optional = false -python-versions = ">=3.7" -files = [ - {file = "shapely-2.0.6-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:29a34e068da2d321e926b5073539fd2a1d4429a2c656bd63f0bd4c8f5b236d0b"}, - {file = "shapely-2.0.6-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:e1c84c3f53144febf6af909d6b581bc05e8785d57e27f35ebaa5c1ab9baba13b"}, - {file = "shapely-2.0.6-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:2ad2fae12dca8d2b727fa12b007e46fbc522148a584f5d6546c539f3464dccde"}, - {file = "shapely-2.0.6-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b3304883bd82d44be1b27a9d17f1167fda8c7f5a02a897958d86c59ec69b705e"}, - {file = "shapely-2.0.6-cp310-cp310-win32.whl", hash = "sha256:3ec3a0eab496b5e04633a39fa3d5eb5454628228201fb24903d38174ee34565e"}, - {file = "shapely-2.0.6-cp310-cp310-win_amd64.whl", hash = "sha256:28f87cdf5308a514763a5c38de295544cb27429cfa655d50ed8431a4796090c4"}, - {file = "shapely-2.0.6-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:5aeb0f51a9db176da9a30cb2f4329b6fbd1e26d359012bb0ac3d3c7781667a9e"}, - {file = "shapely-2.0.6-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:9a7a78b0d51257a367ee115f4d41ca4d46edbd0dd280f697a8092dd3989867b2"}, - {file = "shapely-2.0.6-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f32c23d2f43d54029f986479f7c1f6e09c6b3a19353a3833c2ffb226fb63a855"}, - {file = "shapely-2.0.6-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b3dc9fb0eb56498912025f5eb352b5126f04801ed0e8bdbd867d21bdbfd7cbd0"}, - {file = "shapely-2.0.6-cp311-cp311-win32.whl", hash = "sha256:d93b7e0e71c9f095e09454bf18dad5ea716fb6ced5df3cb044564a00723f339d"}, - {file = "shapely-2.0.6-cp311-cp311-win_amd64.whl", hash = "sha256:c02eb6bf4cfb9fe6568502e85bb2647921ee49171bcd2d4116c7b3109724ef9b"}, - {file = "shapely-2.0.6-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:cec9193519940e9d1b86a3b4f5af9eb6910197d24af02f247afbfb47bcb3fab0"}, - {file = "shapely-2.0.6-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:83b94a44ab04a90e88be69e7ddcc6f332da7c0a0ebb1156e1c4f568bbec983c3"}, - {file = "shapely-2.0.6-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:537c4b2716d22c92036d00b34aac9d3775e3691f80c7aa517c2c290351f42cd8"}, - {file = "shapely-2.0.6-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:98fea108334be345c283ce74bf064fa00cfdd718048a8af7343c59eb40f59726"}, - {file = "shapely-2.0.6-cp312-cp312-win32.whl", hash = "sha256:42fd4cd4834747e4990227e4cbafb02242c0cffe9ce7ef9971f53ac52d80d55f"}, - {file = "shapely-2.0.6-cp312-cp312-win_amd64.whl", hash = "sha256:665990c84aece05efb68a21b3523a6b2057e84a1afbef426ad287f0796ef8a48"}, - {file = "shapely-2.0.6-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:42805ef90783ce689a4dde2b6b2f261e2c52609226a0438d882e3ced40bb3013"}, - {file = "shapely-2.0.6-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:6d2cb146191a47bd0cee8ff5f90b47547b82b6345c0d02dd8b25b88b68af62d7"}, - {file = "shapely-2.0.6-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e3fdef0a1794a8fe70dc1f514440aa34426cc0ae98d9a1027fb299d45741c381"}, - {file = "shapely-2.0.6-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:2c665a0301c645615a107ff7f52adafa2153beab51daf34587170d85e8ba6805"}, - {file = "shapely-2.0.6-cp313-cp313-win32.whl", hash = "sha256:0334bd51828f68cd54b87d80b3e7cee93f249d82ae55a0faf3ea21c9be7b323a"}, - {file = "shapely-2.0.6-cp313-cp313-win_amd64.whl", hash = "sha256:d37d070da9e0e0f0a530a621e17c0b8c3c9d04105655132a87cfff8bd77cc4c2"}, - {file = "shapely-2.0.6-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:fa7468e4f5b92049c0f36d63c3e309f85f2775752e076378e36c6387245c5462"}, - {file = "shapely-2.0.6-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:ed5867e598a9e8ac3291da6cc9baa62ca25706eea186117034e8ec0ea4355653"}, - {file = "shapely-2.0.6-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:81d9dfe155f371f78c8d895a7b7f323bb241fb148d848a2bf2244f79213123fe"}, - {file = "shapely-2.0.6-cp37-cp37m-win32.whl", hash = "sha256:fbb7bf02a7542dba55129062570211cfb0defa05386409b3e306c39612e7fbcc"}, - {file = "shapely-2.0.6-cp37-cp37m-win_amd64.whl", hash = "sha256:837d395fac58aa01aa544495b97940995211e3e25f9aaf87bc3ba5b3a8cd1ac7"}, - {file = "shapely-2.0.6-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:c6d88ade96bf02f6bfd667ddd3626913098e243e419a0325ebef2bbd481d1eb6"}, - {file = "shapely-2.0.6-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:8b3b818c4407eaa0b4cb376fd2305e20ff6df757bf1356651589eadc14aab41b"}, - {file = "shapely-2.0.6-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:1bbc783529a21f2bd50c79cef90761f72d41c45622b3e57acf78d984c50a5d13"}, - {file = "shapely-2.0.6-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:2423f6c0903ebe5df6d32e0066b3d94029aab18425ad4b07bf98c3972a6e25a1"}, - {file = "shapely-2.0.6-cp38-cp38-win32.whl", hash = "sha256:2de00c3bfa80d6750832bde1d9487e302a6dd21d90cb2f210515cefdb616e5f5"}, - {file = "shapely-2.0.6-cp38-cp38-win_amd64.whl", hash = "sha256:3a82d58a1134d5e975f19268710e53bddd9c473743356c90d97ce04b73e101ee"}, - {file = "shapely-2.0.6-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:392f66f458a0a2c706254f473290418236e52aa4c9b476a072539d63a2460595"}, - {file = "shapely-2.0.6-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:eba5bae271d523c938274c61658ebc34de6c4b33fdf43ef7e938b5776388c1be"}, - {file = "shapely-2.0.6-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:7060566bc4888b0c8ed14b5d57df8a0ead5c28f9b69fb6bed4476df31c51b0af"}, - {file = "shapely-2.0.6-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b02154b3e9d076a29a8513dffcb80f047a5ea63c897c0cd3d3679f29363cf7e5"}, - {file = "shapely-2.0.6-cp39-cp39-win32.whl", hash = "sha256:44246d30124a4f1a638a7d5419149959532b99dfa25b54393512e6acc9c211ac"}, - {file = "shapely-2.0.6-cp39-cp39-win_amd64.whl", hash = "sha256:2b542d7f1dbb89192d3512c52b679c822ba916f93479fa5d4fc2fe4fa0b3c9e8"}, - {file = "shapely-2.0.6.tar.gz", hash = "sha256:997f6159b1484059ec239cacaa53467fd8b5564dabe186cd84ac2944663b0bf6"}, -] - -[package.dependencies] -numpy = ">=1.14,<3" - -[package.extras] -docs = ["matplotlib", "numpydoc (==1.1.*)", "sphinx", "sphinx-book-theme", "sphinx-remove-toctrees"] -test = ["pytest", "pytest-cov"] - -[[package]] -name = "simplekml" -version = "1.3.6" -description = "A Simple KML creator" -optional = false -python-versions = "*" -files = [ - {file = "simplekml-1.3.6.tar.gz", hash = "sha256:cda687be2754395fcab664e908ebf589facd41e8436d233d2be37a69efb1c536"}, -] - -[[package]] -name = "six" -version = "1.16.0" -description = "Python 2 and 3 compatibility utilities" -optional = false -python-versions = ">=2.7, !=3.0.*, !=3.1.*, !=3.2.*" -files = [ - {file = "six-1.16.0-py2.py3-none-any.whl", hash = "sha256:8abb2f1d86890a2dfb989f9a77cfcfd3e47c2a354b01111771326f8aa26e0254"}, - {file = "six-1.16.0.tar.gz", hash = "sha256:1e61c37477a1626458e36f7b1d82aa5c9b094fa4802892072e49de9c60c4c926"}, -] - -[[package]] -name = "stack-data" -version = "0.6.3" -description = "Extract data from python stack frames and tracebacks for informative displays" -optional = false -python-versions = "*" -files = [ - {file = "stack_data-0.6.3-py3-none-any.whl", hash = "sha256:d5558e0c25a4cb0853cddad3d77da9891a08cb85dd9f9f91b9f8cd66e511e695"}, - {file = "stack_data-0.6.3.tar.gz", hash = "sha256:836a778de4fec4dcd1dcd89ed8abff8a221f58308462e1c4aa2a3cf30148f0b9"}, -] - -[package.dependencies] -asttokens = ">=2.1.0" -executing = ">=1.2.0" -pure-eval = "*" - -[package.extras] -tests = ["cython", "littleutils", "pygments", "pytest", "typeguard"] - -[[package]] -name = "tomli" -version = "2.0.2" -description = "A lil' TOML parser" -optional = false -python-versions = ">=3.8" -files = [ - {file = "tomli-2.0.2-py3-none-any.whl", hash = "sha256:2ebe24485c53d303f690b0ec092806a085f07af5a5aa1464f3931eec36caaa38"}, - {file = "tomli-2.0.2.tar.gz", hash = "sha256:d46d457a85337051c36524bc5349dd91b1877838e2979ac5ced3e710ed8a60ed"}, -] - -[[package]] -name = "traitlets" -version = "5.14.3" -description = "Traitlets Python configuration system" -optional = false -python-versions = ">=3.8" -files = [ - {file = "traitlets-5.14.3-py3-none-any.whl", hash = "sha256:b74e89e397b1ed28cc831db7aea759ba6640cb3de13090ca145426688ff1ac4f"}, - {file = "traitlets-5.14.3.tar.gz", hash = "sha256:9ed0579d3502c94b4b3732ac120375cda96f923114522847de4b3bb98b96b6b7"}, -] - -[package.extras] -docs = ["myst-parser", "pydata-sphinx-theme", "sphinx"] -test = ["argcomplete (>=3.0.3)", "mypy (>=1.7.0)", "pre-commit", "pytest (>=7.0,<8.2)", "pytest-mock", "pytest-mypy-testing"] - -[[package]] -name = "transformations" -version = "2024.5.24" -description = "Homogeneous Transformation Matrices and Quaternions" -optional = false -python-versions = ">=3.9" -files = [ - {file = "transformations-2024.5.24-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:b538ec7fc815c4ab6f427e339eb1a4eddd46860fff306f8f7c6eb80167d08d28"}, - {file = "transformations-2024.5.24-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:0c3c6b07e1d0d9714f3ccd163785845ff780df26ab094ed125b11d0922c4fee7"}, - {file = "transformations-2024.5.24-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:cc36351fed3d7bc2d413bab358828870f02a41d71723033032d08e2e75361892"}, - {file = "transformations-2024.5.24-cp310-cp310-win32.whl", hash = "sha256:5ddcec2e35a05a3f81a318c4d7184a4c347b85030cdbc36fdad92c7eb2ba70d4"}, - {file = "transformations-2024.5.24-cp310-cp310-win_amd64.whl", hash = "sha256:c599f0140f18f590c50992f5011593ce08e4b893ff26fde4bf7bf5e0db1d9c60"}, - {file = "transformations-2024.5.24-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:1290cdcb65067809cd8dd4b3c3ab552fb6b50e99c015c1678618de2b67913b72"}, - {file = "transformations-2024.5.24-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:575d0b5d8c2c92931da46fc55568f17f7b306334ba25fa6091ac5708808bfbfc"}, - {file = "transformations-2024.5.24-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:fba5109b455836829ce6476ba53c16f6e72187340084d004dcfac9bf11a2bfd7"}, - {file = "transformations-2024.5.24-cp311-cp311-win32.whl", hash = "sha256:c76e772b77d4665440dac82b36485565e0e0d4ef3679b48ef4449b73935e44fb"}, - {file = "transformations-2024.5.24-cp311-cp311-win_amd64.whl", hash = "sha256:22fd2283b4aa51609ce3d6929add2fef656f049c5cfa291cc6abfdae2a329f7f"}, - {file = "transformations-2024.5.24-cp311-cp311-win_arm64.whl", hash = "sha256:be69c3055aa341db7bd231d979ebaae1e64417246a6792c1d03631193edde442"}, - {file = "transformations-2024.5.24-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:cf0a5f141dcf84a7b5efb27747c2b852d1f9cc8d621d3bdc17fb2f9ac37eaee3"}, - {file = "transformations-2024.5.24-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:a655966a893ade762f12946c02e3ffa5cd826cf0866e9587e46f812d494ad56e"}, - {file = "transformations-2024.5.24-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:2f87541e8bb87337b8bc1839188d07ad922124f23ce1eca1ce4c6f5bcf5f1e4f"}, - {file = "transformations-2024.5.24-cp312-cp312-win32.whl", hash = "sha256:f713ac891a46abfd98158c8a72166a1f92ebaba1644dc8aa59b5357391d6d9e0"}, - {file = "transformations-2024.5.24-cp312-cp312-win_amd64.whl", hash = "sha256:d81ed1df5dbdd204cd447728cc5b44d4bf1ccd4af5401ee61032477f5de5788b"}, - {file = "transformations-2024.5.24-cp312-cp312-win_arm64.whl", hash = "sha256:bbb74d4701be2fc7852c80493e2b92cd52485d4712ce8bfc03c92fb7bdd365c5"}, - {file = "transformations-2024.5.24-cp313-cp313-win32.whl", hash = "sha256:a52ae7bc8a194dc6d9b5809f9c1bb38cd5088cefcb46fc18fac9d193e48b981a"}, - {file = "transformations-2024.5.24-cp313-cp313-win_amd64.whl", hash = "sha256:77b2d2ce824cfd2b555cbe35a05aed74a78e71f5783665b495a80e71ede2fd65"}, - {file = "transformations-2024.5.24-cp313-cp313-win_arm64.whl", hash = "sha256:2b86b05f304d2da980dabeb52a6bc49fbcc6c4f830f470b82c3559623ca1bae7"}, - {file = "transformations-2024.5.24-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:d70a175f7baff6cc70236f74d51c5adb14a3cc3d89fc2e108c1f086f9a834e88"}, - {file = "transformations-2024.5.24-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:29f4ebee83c2fb6857f7dbb15917e39bc6bed1f309179452a0dfeda37e2d4d0d"}, - {file = "transformations-2024.5.24-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:00b20a57cfe4b5f5fadf957bff68c40a86437f85e75b2ed655b87beb45d62940"}, - {file = "transformations-2024.5.24-cp39-cp39-win32.whl", hash = "sha256:873a7d09a428ccf0156949b1541eae93ee954771c7b431e7d15a79ab2c32d5e4"}, - {file = "transformations-2024.5.24-cp39-cp39-win_amd64.whl", hash = "sha256:dda37a7683acb10068c491b6d33bdbdbfb1a1ea4a3291639b23ee4a0af42138c"}, - {file = "transformations-2024.5.24.tar.gz", hash = "sha256:960328ce2f5e1dad8025b1b82c8588afbc57644c609899c5b9508af965cd7bc0"}, -] - -[package.dependencies] -numpy = "*" - -[[package]] -name = "typing-extensions" -version = "4.12.2" -description = "Backported and Experimental Type Hints for Python 3.8+" -optional = false -python-versions = ">=3.8" -files = [ - {file = "typing_extensions-4.12.2-py3-none-any.whl", hash = "sha256:04e5ca0351e0f3f85c6853954072df659d0d13fac324d0072316b67d7794700d"}, - {file = "typing_extensions-4.12.2.tar.gz", hash = "sha256:1a7ead55c7e559dd4dee8856e3a88b41225abfe1ce8df57b7c13915fe121ffb8"}, -] - -[[package]] -name = "ubelt" -version = "1.3.6" -description = "A Python utility belt containing simple tools, a stdlib like feel, and extra batteries" -optional = false -python-versions = ">=3.6" -files = [ - {file = "ubelt-1.3.6-py3-none-any.whl", hash = "sha256:2a38f260e7f3c25d3618f653d5c900230dc5af56bf0bc1ff85cfdbe9d0c88f0f"}, - {file = "ubelt-1.3.6.tar.gz", hash = "sha256:327a516a1fc95595096727ae3ae879379bc56fc11fb945857b971ef85a74f698"}, -] - -[package.extras] -all = ["Pygments (>=2.2.0)", "colorama (>=0.4.3)", "coverage (>=4.3.4)", "coverage (>=4.5)", "coverage (>=5.3.1)", "coverage (>=5.3.1)", "coverage (>=5.3.1)", "coverage (>=6.1.1)", "coverage (>=6.1.1)", "coverage (>=6.1.1)", "coverage (>=6.1.1)", "coverage (>=7.3.0)", "jaraco.windows (>=3.9.1)", "numpy (>=1.12.0,<2.0.0)", "numpy (>=1.14.5,<2.0.0)", "numpy (>=1.19.2)", "numpy (>=1.19.3)", "numpy (>=1.21.1)", "numpy (>=1.23.2)", "numpy (>=1.26.0)", "packaging (>=21.0)", "pydantic (<2.0)", "pytest (>=4.6.0)", "pytest (>=4.6.0)", "pytest (>=4.6.0,<=4.6.11)", "pytest (>=4.6.0,<=4.6.11)", "pytest (>=4.6.0,<=6.1.2)", "pytest (>=6.2.5)", "pytest (>=8.1.1)", "pytest (>=8.1.1)", "pytest (>=8.1.1)", "pytest-cov (>=2.8.1)", "pytest-cov (>=2.8.1)", "pytest-cov (>=2.9.0)", "pytest-cov (>=3.0.0)", "pytest-timeout (>=1.4.2)", "pytest-timeout (>=2.3.1)", "python-dateutil (>=2.8.1)", "requests (>=2.25.1)", "xdoctest (>=1.1.3)", "xxhash (>=1.3.0)", "xxhash (>=1.3.0)", "xxhash (>=1.4.3)", "xxhash (>=2.0.2)", "xxhash (>=3.0.0)", "xxhash (>=3.2.0)", "xxhash (>=3.4.1)"] -all-strict = ["Pygments (==2.2.0)", "colorama (==0.4.3)", "coverage (==4.3.4)", "coverage (==4.5)", "coverage (==5.3.1)", "coverage (==5.3.1)", "coverage (==5.3.1)", "coverage (==6.1.1)", "coverage (==6.1.1)", "coverage (==6.1.1)", "coverage (==6.1.1)", "coverage (==7.3.0)", "jaraco.windows (==3.9.1)", "numpy (==1.12.0)", "numpy (==1.14.5)", "numpy (==1.19.2)", "numpy (==1.19.3)", "numpy (==1.21.1)", "numpy (==1.23.2)", "numpy (==1.26.0)", "packaging (==21.0)", "pydantic (<2.0)", "pytest (==4.6.0)", "pytest (==4.6.0)", "pytest (==4.6.0)", "pytest (==4.6.0)", "pytest (==4.6.0)", "pytest (==6.2.5)", "pytest (==8.1.1)", "pytest (==8.1.1)", "pytest (==8.1.1)", "pytest-cov (==2.8.1)", "pytest-cov (==2.8.1)", "pytest-cov (==2.9.0)", "pytest-cov (==3.0.0)", "pytest-timeout (==1.4.2)", "pytest-timeout (==2.3.1)", "python-dateutil (==2.8.1)", "requests (==2.25.1)", "xdoctest (==1.1.3)", "xxhash (==1.3.0)", "xxhash (==1.3.0)", "xxhash (==1.4.3)", "xxhash (==2.0.2)", "xxhash (==3.0.0)", "xxhash (==3.2.0)", "xxhash (==3.4.1)"] -docs = ["Pygments (>=2.9.0)", "myst-parser (>=0.16.1)", "sphinx (>=4.3.2)", "sphinx-autoapi (>=1.8.4)", "sphinx-autobuild (>=2021.3.14)", "sphinx-reredirects (>=0.0.1)", "sphinx-rtd-theme (>=1.0.0)", "sphinxcontrib-napoleon (>=0.7)"] -docs-strict = ["Pygments (==2.9.0)", "myst-parser (==0.16.1)", "sphinx (==4.3.2)", "sphinx-autoapi (==1.8.4)", "sphinx-autobuild (==2021.3.14)", "sphinx-reredirects (==0.0.1)", "sphinx-rtd-theme (==1.0.0)", "sphinxcontrib-napoleon (==0.7)"] -optional = ["Pygments (>=2.2.0)", "colorama (>=0.4.3)", "jaraco.windows (>=3.9.1)", "numpy (>=1.12.0,<2.0.0)", "numpy (>=1.14.5,<2.0.0)", "numpy (>=1.19.2)", "numpy (>=1.19.3)", "numpy (>=1.21.1)", "numpy (>=1.23.2)", "numpy (>=1.26.0)", "packaging (>=21.0)", "pydantic (<2.0)", "python-dateutil (>=2.8.1)", "xxhash (>=1.3.0)", "xxhash (>=1.3.0)", "xxhash (>=1.4.3)", "xxhash (>=2.0.2)", "xxhash (>=3.0.0)", "xxhash (>=3.2.0)", "xxhash (>=3.4.1)"] -optional-strict = ["Pygments (==2.2.0)", "colorama (==0.4.3)", "jaraco.windows (==3.9.1)", "numpy (==1.12.0)", "numpy (==1.14.5)", "numpy (==1.19.2)", "numpy (==1.19.3)", "numpy (==1.21.1)", "numpy (==1.23.2)", "numpy (==1.26.0)", "packaging (==21.0)", "pydantic (<2.0)", "python-dateutil (==2.8.1)", "xxhash (==1.3.0)", "xxhash (==1.3.0)", "xxhash (==1.4.3)", "xxhash (==2.0.2)", "xxhash (==3.0.0)", "xxhash (==3.2.0)", "xxhash (==3.4.1)"] -tests = ["coverage (>=4.3.4)", "coverage (>=4.5)", "coverage (>=5.3.1)", "coverage (>=5.3.1)", "coverage (>=5.3.1)", "coverage (>=6.1.1)", "coverage (>=6.1.1)", "coverage (>=6.1.1)", "coverage (>=6.1.1)", "coverage (>=7.3.0)", "pytest (>=4.6.0)", "pytest (>=4.6.0)", "pytest (>=4.6.0,<=4.6.11)", "pytest (>=4.6.0,<=4.6.11)", "pytest (>=4.6.0,<=6.1.2)", "pytest (>=6.2.5)", "pytest (>=8.1.1)", "pytest (>=8.1.1)", "pytest (>=8.1.1)", "pytest-cov (>=2.8.1)", "pytest-cov (>=2.8.1)", "pytest-cov (>=2.9.0)", "pytest-cov (>=3.0.0)", "pytest-timeout (>=1.4.2)", "pytest-timeout (>=2.3.1)", "requests (>=2.25.1)", "xdoctest (>=1.1.3)"] -tests-strict = ["coverage (==4.3.4)", "coverage (==4.5)", "coverage (==5.3.1)", "coverage (==5.3.1)", "coverage (==5.3.1)", "coverage (==6.1.1)", "coverage (==6.1.1)", "coverage (==6.1.1)", "coverage (==6.1.1)", "coverage (==7.3.0)", "pytest (==4.6.0)", "pytest (==4.6.0)", "pytest (==4.6.0)", "pytest (==4.6.0)", "pytest (==4.6.0)", "pytest (==6.2.5)", "pytest (==8.1.1)", "pytest (==8.1.1)", "pytest (==8.1.1)", "pytest-cov (==2.8.1)", "pytest-cov (==2.8.1)", "pytest-cov (==2.9.0)", "pytest-cov (==3.0.0)", "pytest-timeout (==1.4.2)", "pytest-timeout (==2.3.1)", "requests (==2.25.1)", "xdoctest (==1.1.3)"] -types = ["autoflake (>=1.4)", "mypy", "yapf (>=0.32.0)"] -types-strict = ["autoflake (==1.4)", "mypy", "yapf (==0.32.0)"] - -[[package]] -name = "wcwidth" -version = "0.2.13" -description = "Measures the displayed width of unicode strings in a terminal" -optional = false -python-versions = "*" -files = [ - {file = "wcwidth-0.2.13-py2.py3-none-any.whl", hash = "sha256:3da69048e4540d84af32131829ff948f1e022c1c6bdb8d6102117aac784f6859"}, - {file = "wcwidth-0.2.13.tar.gz", hash = "sha256:72ea0c06399eb286d978fdedb6923a9eb47e1c486ce63e9b4e64fc18303972b5"}, -] - -[[package]] -name = "zope-interface" -version = "7.0.3" -description = "Interfaces for Python" -optional = false -python-versions = ">=3.8" -files = [ - {file = "zope.interface-7.0.3-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:9b9369671a20b8d039b8e5a1a33abd12e089e319a3383b4cc0bf5c67bd05fe7b"}, - {file = "zope.interface-7.0.3-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:db6237e8fa91ea4f34d7e2d16d74741187e9105a63bbb5686c61fea04cdbacca"}, - {file = "zope.interface-7.0.3-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:53d678bb1c3b784edbfb0adeebfeea6bf479f54da082854406a8f295d36f8386"}, - {file = "zope.interface-7.0.3-cp310-cp310-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:3aa8fcbb0d3c2be1bfd013a0f0acd636f6ed570c287743ae2bbd467ee967154d"}, - {file = "zope.interface-7.0.3-cp310-cp310-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6195c3c03fef9f87c0dbee0b3b6451df6e056322463cf35bca9a088e564a3c58"}, - {file = "zope.interface-7.0.3-cp310-cp310-win_amd64.whl", hash = "sha256:11fa1382c3efb34abf16becff8cb214b0b2e3144057c90611621f2d186b7e1b7"}, - {file = "zope.interface-7.0.3-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:af94e429f9d57b36e71ef4e6865182090648aada0cb2d397ae2b3f7fc478493a"}, - {file = "zope.interface-7.0.3-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:6dd647fcd765030638577fe6984284e0ebba1a1008244c8a38824be096e37fe3"}, - {file = "zope.interface-7.0.3-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:1bee1b722077d08721005e8da493ef3adf0b7908e0cd85cc7dc836ac117d6f32"}, - {file = "zope.interface-7.0.3-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:2545d6d7aac425d528cd9bf0d9e55fcd47ab7fd15f41a64b1c4bf4c6b24946dc"}, - {file = "zope.interface-7.0.3-cp311-cp311-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6d04b11ea47c9c369d66340dbe51e9031df2a0de97d68f442305ed7625ad6493"}, - {file = "zope.interface-7.0.3-cp311-cp311-win_amd64.whl", hash = "sha256:064ade95cb54c840647205987c7b557f75d2b2f7d1a84bfab4cf81822ef6e7d1"}, - {file = "zope.interface-7.0.3-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:3fcdc76d0cde1c09c37b7c6b0f8beba2d857d8417b055d4f47df9c34ec518bdd"}, - {file = "zope.interface-7.0.3-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:3d4b91821305c8d8f6e6207639abcbdaf186db682e521af7855d0bea3047c8ca"}, - {file = "zope.interface-7.0.3-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:35062d93bc49bd9b191331c897a96155ffdad10744ab812485b6bad5b588d7e4"}, - {file = "zope.interface-7.0.3-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:c96b3e6b0d4f6ddfec4e947130ec30bd2c7b19db6aa633777e46c8eecf1d6afd"}, - {file = "zope.interface-7.0.3-cp312-cp312-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:7e0c151a6c204f3830237c59ee4770cc346868a7a1af6925e5e38650141a7f05"}, - {file = "zope.interface-7.0.3-cp312-cp312-win_amd64.whl", hash = "sha256:3de1d553ce72868b77a7e9d598c9bff6d3816ad2b4cc81c04f9d8914603814f3"}, - {file = "zope.interface-7.0.3-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:ab985c566a99cc5f73bc2741d93f1ed24a2cc9da3890144d37b9582965aff996"}, - {file = "zope.interface-7.0.3-cp313-cp313-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:d976fa7b5faf5396eb18ce6c132c98e05504b52b60784e3401f4ef0b2e66709b"}, - {file = "zope.interface-7.0.3-cp313-cp313-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:21a207c6b2c58def5011768140861a73f5240f4f39800625072ba84e76c9da0b"}, - {file = "zope.interface-7.0.3-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:382d31d1e68877061daaa6499468e9eb38eb7625d4369b1615ac08d3860fe896"}, - {file = "zope.interface-7.0.3-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:2c4316a30e216f51acbd9fb318aa5af2e362b716596d82cbb92f9101c8f8d2e7"}, - {file = "zope.interface-7.0.3-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:01e6e58078ad2799130c14a1d34ec89044ada0e1495329d72ee0407b9ae5100d"}, - {file = "zope.interface-7.0.3-cp38-cp38-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:799ef7a444aebbad5a145c3b34bff012b54453cddbde3332d47ca07225792ea4"}, - {file = "zope.interface-7.0.3-cp38-cp38-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:d3b7ce6d46fb0e60897d62d1ff370790ce50a57d40a651db91a3dde74f73b738"}, - {file = "zope.interface-7.0.3-cp38-cp38-win_amd64.whl", hash = "sha256:f418c88f09c3ba159b95a9d1cfcdbe58f208443abb1f3109f4b9b12fd60b187c"}, - {file = "zope.interface-7.0.3-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:84f8794bd59ca7d09d8fce43ae1b571be22f52748169d01a13d3ece8394d8b5b"}, - {file = "zope.interface-7.0.3-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:7d92920416f31786bc1b2f34cc4fc4263a35a407425319572cbf96b51e835cd3"}, - {file = "zope.interface-7.0.3-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:95e5913ec718010dc0e7c215d79a9683b4990e7026828eedfda5268e74e73e11"}, - {file = "zope.interface-7.0.3-cp39-cp39-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:1eeeb92cb7d95c45e726e3c1afe7707919370addae7ed14f614e22217a536958"}, - {file = "zope.interface-7.0.3-cp39-cp39-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:ecd32f30f40bfd8511b17666895831a51b532e93fc106bfa97f366589d3e4e0e"}, - {file = "zope.interface-7.0.3-cp39-cp39-win_amd64.whl", hash = "sha256:5112c530fa8aa2108a3196b9c2f078f5738c1c37cfc716970edc0df0414acda8"}, - {file = "zope.interface-7.0.3.tar.gz", hash = "sha256:cd2690d4b08ec9eaf47a85914fe513062b20da78d10d6d789a792c0b20307fb1"}, -] - -[package.dependencies] -setuptools = "*" - -[package.extras] -docs = ["Sphinx", "repoze.sphinx.autointerface", "sphinx-rtd-theme"] -test = ["coverage (>=5.0.3)", "zope.event", "zope.testing"] -testing = ["coverage (>=5.0.3)", "zope.event", "zope.testing"] - -[metadata] -lock-version = "2.0" -python-versions = "^3.10" -content-hash = "e592e34b5bad869b2938ac89d0c685ea78a6a71ea5ef9e0f2b97fc96f4380a2c" diff --git a/pyproject.toml b/pyproject.toml index 04686dd..bb2aa78 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -1,35 +1,92 @@ -[tool.poetry] +[project] name = "kamera" version = "0.1.0" description = "KAMERA: Kitware's Image Acquisition ManagER and Archiver" -authors = ["Adam Romlein "] -license = "Apache-2.0" +authors = [ + {name = "Adam Romlein", email = "adam.romlein@kitware.com"} +] readme = "README.md" +requires-python = ">=3.10" +license = {text = "Apache-2.0"} +dependencies = [ + "numpy>=2.1.1", + "scipy>=1.14.1", + "matplotlib>=3.9.2", + "opencv-python>=4.10.0.84", + "pillow>=10.4.0", + "pyyaml>=6.0.2", + "exifread>=3.0.0", + "pygeodesy>=24.9.29", + "pyshp>=2.3.1", + "simplekml>=1.3.6", + "shapely>=2.0.6", + "transformations>=2024.5.24", + "scriptconfig>=0.8.0", + "ubelt>=1.3.6", + "rich>=13.9.1", + "ipdb>=0.13.13", + "bottle>=0.13.2", + "pycolmap>=3.11.1", +] +# Note: For best cross-platform support (especially GDAL and pycolmap), use conda/mamba: +# - Recommended: micromamba create -f environment.yml && micromamba activate kamera +# - Alternative: conda env create -f environment.yml && conda activate kamera +# +# For pip-only installation: +# - Linux: Install GDAL via system packages (libgdal-dev, python3-gdal) +# - Windows: Use optional dependency: uv pip install -e .[gdal-windows] +# - macOS: Install GDAL via Homebrew (gdal) or conda -[tool.poetry.dependencies] -python = "^3.10" -numpy = "^2.1.1" -scipy = "^1.14.1" -matplotlib = "^3.9.2" -opencv-python = "^4.10.0.84" -pillow = "^10.4.0" -pyyaml = "^6.0.2" -datetime = "^5.5" -exifread = "^3.0.0" -pygeodesy = "^24.9.29" -pyshp = "^2.3.1" -simplekml = "^1.3.6" -shapely = "^2.0.6" -transformations = "^2024.5.24" -scriptconfig = "^0.8.0" -ubelt = "^1.3.6" -rich = "^13.9.1" -gdal = {url = "https://github.com/girder/large_image_wheels/raw/wheelhouse/GDAL-3.9.2-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl#sha256=0ccdfd68893818a86d2225c1efe6b4a64a6d84676f6fb1e7ec5a4138f70d837b"} -ipdb = "^0.13.13" -bottle = "^0.13.2" -pycolmap = "^3.11.1" - +[project.optional-dependencies] +# Windows-specific GDAL wheel (fallback for pip-only installs on Windows) +# For production, prefer conda-forge (see environment.yml) +gdal-windows = [ + "gdal @ https://github.com/girder/large_image_wheels/raw/wheelhouse/GDAL-3.9.2-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl#sha256=0ccdfd68893818a86d2225c1efe6b4a64a6d84676f6fb1e7ec5a4138f70d837b" +] [build-system] -requires = ["poetry-core"] -build-backend = "poetry.core.masonry.api" +requires = ["hatchling"] +build-backend = "hatchling.build" + +[tool.hatch.metadata] +# Allow direct URL references for optional dependencies (e.g., GDAL wheel) +allow-direct-references = true + +# Hatchling will auto-discover packages in the project root +# For package data, use MANIFEST.in or configure here if needed + +[tool.ruff] +# Ruff configuration for linting +target-version = "py310" +line-length = 100 +select = [ + "E", # pycodestyle errors + "W", # pycodestyle warnings + "F", # pyflakes + "I", # isort + "B", # flake8-bugbear + "C4", # flake8-comprehensions + "UP", # pyupgrade + "ARG", # flake8-unused-arguments + "SIM", # flake8-simplify +] +ignore = [ + "E501", # line too long (handled by formatter) + "B008", # do not perform function calls in argument defaults + "B904", # Allow exceptions without specifying exception types in some cases + "UP007", # Use X | Y for type annotations (requires Python 3.10+) +] + +[tool.ruff.per-file-ignores] +"__init__.py" = ["F401"] # Allow unused imports in __init__.py +"*/tests/*" = ["ARG"] # Allow unused arguments in tests +"*/test_*.py" = ["ARG"] + +[tool.ruff.isort] +known-first-party = ["kamera"] +force-sort-within-sections = true + +[tool.ruff.lint] +# Allow autofix for all enabled rules +fixable = ["ALL"] +unfixable = [] diff --git a/requirements.txt b/requirements.txt deleted file mode 100644 index 9237998..0000000 --- a/requirements.txt +++ /dev/null @@ -1,18 +0,0 @@ -numpy -scipy -matplotlib -opencv-python -Pillow -pyyaml -datetime -exifread -matplotlib -numpy -pygeodesy -pyshp -simplekml -shapely -transformations -scriptconfig -ubelt -rich diff --git a/setup.py b/setup.py index 674e86a..91ad90f 100644 --- a/setup.py +++ b/setup.py @@ -1,9 +1,10 @@ -from setuptools import setup, find_packages -setup( - name='kamera', - version='0.1', - description="KAMERA: Kitware's Image Acquisition ManagER and Archiver", - author='Adam Romlein', - author_email='adam.romlein@kitware.com', - packages=find_packages("."), - ) +#!/usr/bin/env python +""" +Legacy setup.py for compatibility. +The package is configured via pyproject.toml and should be built/installed with uv or pip. +""" +from setuptools import setup + +# Minimal setup.py for backward compatibility +# Real configuration is in pyproject.toml +setup() From 1d627cb16a546aabac3e970b30d3dfaebf94e6a3 Mon Sep 17 00:00:00 2001 From: romleiaj Date: Mon, 29 Dec 2025 11:27:36 -0500 Subject: [PATCH 20/20] Update to latest colmap (3.13), test full pipeline again. --- kamera/postflight/colmap.py | 34 +++++++++++++++--------- kamera/postflight/scripts/calibration.py | 14 +++++----- kamera/postflight/utilities.py | 26 +++++++++++++----- kamera/sensor_models/nav_conversions.py | 5 ++++ kamera/sensor_models/nav_state.py | 3 +-- 5 files changed, 52 insertions(+), 30 deletions(-) diff --git a/kamera/postflight/colmap.py b/kamera/postflight/colmap.py index 3bd2b16..4fbe3a8 100644 --- a/kamera/postflight/colmap.py +++ b/kamera/postflight/colmap.py @@ -135,15 +135,16 @@ def prepare_calibration_data(self): continue # Query the navigation state recorded by the INS for this time. - pose = self.nav_state_provider.pose(t) + ins_pose = self.nav_state_provider.pose(t) llh = self.nav_state_provider.llh(t) # Query Colmaps pose for the camera. - R = image.cam_from_world.rotation.matrix() - pos = -np.dot(R.T, image.cam_from_world.translation) + pose = image.cam_from_world() + R = pose.rotation.matrix() + pos = -np.dot(R.T, pose.translation) - image.cam_from_world.rotation.normalize() - quat = image.cam_from_world.rotation.quat + pose.rotation.normalize() + quat = pose.rotation.quat # invert the w (rotation) component, # so we get the camera to world rotation quat[3] *= -1 @@ -151,7 +152,7 @@ def prepare_calibration_data(self): sfm_pose = [pos, quat] img_times.append(t) - ins_poses.append(pose) + ins_poses.append(ins_pose) img_fnames.append(image.name) sfm_poses.append(sfm_pose) llhs.append(llh) @@ -241,7 +242,7 @@ def transfer_calibration( to bootstrap the calibration process. """ # Find all valid indices of current cameras - channel, modality = camera_name.split("_")[2:] + channel, modality = camera_name.split("_")[-2:] cam_idxs = [ 1 if camera_name == os.path.basename(os.path.dirname(im)) else 0 for im in self.ccd.img_fnames @@ -260,7 +261,11 @@ def transfer_calibration( if cam_idxs[i] == 1: # Replace with the modality of the already calibrated modality calibrated_fname = fname.replace(modality, calibrated_modality) - ii = self.ccd.img_fnames.index(calibrated_fname) + try: + ii = self.ccd.img_fnames.index(calibrated_fname) + except: + print(f"Missing {calibrated_fname} from calibrated index.") + continue colocated_observations.append(self.ccd.points_per_image[ii]) observations.append(self.ccd.points_per_image[i]) if len(observations) < 10 or len(colocated_observations) < 10: @@ -316,14 +321,14 @@ def write_gifs( colocated_camera_model: StandardCamera, num_gifs: int = 5, ) -> None: - channel, modality = camera_name.split("_")[2:] + channel, modality = camera_name.split("_")[-2:] colocated_camera_name = camera_name.replace(modality, colocated_modality) print( f"Writing registration gifs for cameras {camera_name} " f"and {colocated_camera_name}." ) ub.ensuredir(gif_dir) - + img_fnames = self.ccd.img_fnames for k in range(num_gifs): inds = list(range(len(img_fnames))) @@ -331,11 +336,14 @@ def write_gifs( for i in range(len(img_fnames)): colocated_img = img = None fname = img_fnames[inds[i]] - if osp.basename(osp.dirname(fname)) != camera_name: + base_fname = osp.basename(osp.dirname(fname)) + chan_mode = "_".join(osp.basename(osp.dirname(fname)).split("_")[-2:]) + cam_chan_mode = "_".join(camera_name.split("_")[-2:]) + if chan_mode != cam_chan_mode: continue try: bname = osp.basename(fname) - abs_fname = osp.join(self.colmap_dir, "images0", camera_name, bname) + abs_fname = osp.join(self.colmap_dir, "images0", base_fname, bname) img = cv2.imread(abs_fname, cv2.IMREAD_COLOR)[:, :, ::-1] except Exception as e: print(f"No {modality} image found at path {abs_fname}") @@ -364,7 +372,7 @@ def write_gifs( break except Exception as e: print( - f"No {colocated_modality} image found at filepath {abs_colocated_fname}" + f"No {colocated_modality} image found at filepath {abs_colocated_bname}" ) continue diff --git a/kamera/postflight/scripts/calibration.py b/kamera/postflight/scripts/calibration.py index acb09ab..edc8b58 100644 --- a/kamera/postflight/scripts/calibration.py +++ b/kamera/postflight/scripts/calibration.py @@ -47,8 +47,8 @@ def align_model( def main(): # REQUIREMENTS: Must already have built a reasonable 3-D model using Colmap # And have a flight directory populated by the kamera system - flight_dir = "/home/local/KHQ/adam.romlein/noaa/data/052025_Calibration/" - colmap_dir = os.path.join(flight_dir, "colmap") + flight_dir = "/Users/adam.romlein/kitware/noaa/data/fl09_85mm_25_5deg" + colmap_dir = os.path.join(flight_dir, "colmap_rgb") # Location to save KAMERA camera models. save_dir = os.path.join(flight_dir, "kamera_models") # Location to find / build aligned model @@ -86,7 +86,7 @@ def main(): ) joint_calibration = False for camera_str in cc.ccd.best_cameras.keys(): - channel, modality = camera_str.split("_")[2:] + channel, modality = camera_str.split("_")[-2:] # skip all modalities except the "main" ones if joint_calibration and modality != main_modality: continue @@ -119,7 +119,7 @@ def main(): # are colocated to use 3D points obtained from one to project into the other if joint_calibration: for camera_str in cc.ccd.best_cameras.keys(): - channel, modality = camera_str.split("_")[2:] + channel, modality = camera_str.split("_")[-2:] # now calibrate all other modalities if modality == main_modality: continue @@ -165,7 +165,7 @@ def main(): ir_cc.prepare_calibration_data() camera_strs = list(ir_cc.ccd.best_cameras.keys()) for camera_str in ir_cc.ccd.best_cameras.keys(): - channel, modality = camera_str.split("_")[2:] + channel, modality = camera_str.split("_")[-2:] out_path = os.path.join(save_dir, f"{camera_str}_v2.yaml") if os.path.exists(out_path) and not force_calibrate: print( @@ -177,9 +177,7 @@ def main(): else: print(f"Calibrating camera {camera_str}.") tic = time.perf_counter() - camera_model, error = ir_cc.calibrate_camera( - camera_str, error_threshold=100 - ) + camera_model, error = ir_cc.calibrate_camera(camera_str) toc = time.perf_counter() if camera_model is not None: print(f"Saving camera model to {out_path}") diff --git a/kamera/postflight/utilities.py b/kamera/postflight/utilities.py index 0d6fd05..85b18c6 100644 --- a/kamera/postflight/utilities.py +++ b/kamera/postflight/utilities.py @@ -26,9 +26,6 @@ import shapefile # Custom package imports. -import sys - -sys.path.insert(0, "C:/Users/path_to/postflight_scripts/sensor_models/src") from kamera.sensor_models import ( quaternion_multiply, quaternion_from_matrix, @@ -42,10 +39,25 @@ from kamera.sensor_models.nav_state import NavStateINSJson from kamera.postflight.dat_to_csv import convert_dat_to_csv -# Adjust as necessary -GEOD_FNAME = "/src/kamera/assets/geods/egm84-15.pgm" -if not os.path.isfile(GEOD_FNAME): - raise FileNotFoundError(GEOD_FNAME) +# Find geoid file relative to package root (cross-platform) +# Try multiple possible locations for flexibility +_package_root = pathlib.Path(__file__).parent.parent.parent +_possible_geod_paths = [ + _package_root / "assets" / "geods" / "egm84-15.pgm", # Development/installed package + pathlib.Path("/src/kamera/assets/geods/egm84-15.pgm"), # Docker container path + pathlib.Path("assets/geods/egm84-15.pgm"), # Relative to current working directory +] + +GEOD_FNAME = None +for geod_path in _possible_geod_paths: + if geod_path.is_file(): + GEOD_FNAME = str(geod_path.resolve()) + break + +if GEOD_FNAME is None or not os.path.isfile(GEOD_FNAME): + raise FileNotFoundError( + f"Geoid file not found. Tried: {[str(p) for p in _possible_geod_paths]}" + ) geod = pygeodesy.geoids.GeoidPGM(GEOD_FNAME) SUFFIX_RGB = "rgb.jpg" diff --git a/kamera/sensor_models/nav_conversions.py b/kamera/sensor_models/nav_conversions.py index 6246e3b..85a8300 100644 --- a/kamera/sensor_models/nav_conversions.py +++ b/kamera/sensor_models/nav_conversions.py @@ -403,6 +403,11 @@ def ecef_to_llh(X, Y, Z, in_degrees=True): else: h = - _a * (1) * H / _e2a + sphi = np.min(sphi) + cphi = np.min(cphi) + slam = np.min(slam) + clam = np.min(clam) + lat = float(np.arctan2(sphi, cphi)*180/np.pi) lon = float(np.arctan2(slam, clam)*180/np.pi) return lat, lon, h diff --git a/kamera/sensor_models/nav_state.py b/kamera/sensor_models/nav_state.py index 132f1e4..b43f97d 100644 --- a/kamera/sensor_models/nav_state.py +++ b/kamera/sensor_models/nav_state.py @@ -240,8 +240,7 @@ def average_pos(self): def llh(self, t): # East/north/up coordinates. pos = self.pos(t) - - lat, lon, alt = enu_to_llh(*pos, lat0=self.lat0, lon0=self.lon0, + lat, lon, alt = enu_to_llh(pos[0], pos[1], pos[2], lat0=self.lat0, lon0=self.lon0, h0=self.h0) return lat, lon, alt