From 45e96eb340c63757c26eb6ae716a2fd1d4f1c84c Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Sat, 21 Sep 2024 12:08:51 +0200 Subject: [PATCH 001/253] Add comments about the IMU --- python/PiFinder/imu_pi.py | 16 +++++++++++++--- 1 file changed, 13 insertions(+), 3 deletions(-) diff --git a/python/PiFinder/imu_pi.py b/python/PiFinder/imu_pi.py index f9c263afa..f1ca41f72 100644 --- a/python/PiFinder/imu_pi.py +++ b/python/PiFinder/imu_pi.py @@ -76,9 +76,17 @@ def __init__(self): self.__moving_threshold = (0.0005, 0.0003) def quat_to_euler(self, quat): + """ + INPUTS: + quat: Scalar last quaternion (x, y, z, w) + + OUTPUTS: + rot_euler: [Az, related_to_roll, Alt] + """ if quat[0] + quat[1] + quat[2] + quat[3] == 0: return 0, 0, 0 - rot = Rotation.from_quat(quat) + rot = Rotation.from_quat(quat) # Expects scalar-last quaternion + # Lowercase 'xyz' indicate extrinsic rotation: rot_euler = rot.as_euler("xyz", degrees=True) # convert from -180/180 to 0/360 rot_euler[0] += 180 @@ -105,6 +113,7 @@ def update(self): if self.calibration == 0: logger.warning("NOIMU CAL") return True + # adafruit_bno055 gives quaternion convention (w, x, y,) quat = self.sensor.quaternion if quat[0] is None: logger.warning("IMU: Failed to get sensor values") @@ -181,11 +190,12 @@ def imu_monitor(shared_state, console_queue, log_queue): "moving": False, "move_start": None, "move_end": None, - "pos": [0, 0, 0], - "quat": [0, 0, 0, 0], + "pos": [0, 0, 0], # Corresponds to [Az, related_to_roll, Alt] + "quat": [0, 0, 0, 0], # Scalar last quaternion (x, y, z, w) "start_pos": [0, 0, 0], "status": 0, } + while True: imu.update() imu_data["status"] = imu.calibration From dcb47b5a267dc2935027b540ed8a3a2ca0ab5568 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Mon, 30 Dec 2024 11:11:55 +0000 Subject: [PATCH 002/253] Add comments about IMU --- python/PiFinder/imu_pi.py | 4 ++-- python/PiFinder/integrator.py | 16 +++++++++++----- 2 files changed, 13 insertions(+), 7 deletions(-) diff --git a/python/PiFinder/imu_pi.py b/python/PiFinder/imu_pi.py index f1ca41f72..91d2a7a76 100644 --- a/python/PiFinder/imu_pi.py +++ b/python/PiFinder/imu_pi.py @@ -113,7 +113,7 @@ def update(self): if self.calibration == 0: logger.warning("NOIMU CAL") return True - # adafruit_bno055 gives quaternion convention (w, x, y,) + # adafruit_bno055 gives quaternion convention (w, x, y, z) quat = self.sensor.quaternion if quat[0] is None: logger.warning("IMU: Failed to get sensor values") @@ -191,7 +191,7 @@ def imu_monitor(shared_state, console_queue, log_queue): "move_start": None, "move_end": None, "pos": [0, 0, 0], # Corresponds to [Az, related_to_roll, Alt] - "quat": [0, 0, 0, 0], # Scalar last quaternion (x, y, z, w) + "quat": [0, 0, 0, 0], # Scalar-last quaternion (x, y, z, w) "start_pos": [0, 0, 0], "status": 0, } diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 0f19d0cd5..94a7950eb 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -50,7 +50,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa logger.debug("Starting Integrator") solved = { - "RA": None, + "RA": None, # RA of scope "Dec": None, "Roll": None, "camera_center": { @@ -67,7 +67,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa }, "Roll_offset": 0, # May/may not be needed - for experimentation "imu_pos": None, - "Alt": None, + "Alt": None, # Alt of scope "Az": None, "solve_source": None, "solve_time": None, @@ -137,8 +137,8 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa # camera sensor with the Pole-to-Source great circle. solved["Roll_offset"] = estimate_roll_offset(solved, dt) # Find the roll at the target RA/Dec. Note that this doesn't include the - # roll offset so it's not the roll that the PiFinder camear sees but the - # roll relative to the celestial pole + # roll offset so it's not the roll that the PiFinder cameara sees but the + # roll relative to the celestial pole given the RA and Dec. roll_target_calculated = calc_utils.sf_utils.radec_to_roll( solved["RA"], solved["Dec"], dt ) @@ -162,7 +162,13 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa solved["solve_source"] = "CAM" # Use IMU dead-reckoning from the last camera solve: - # Check we have an alt/az solve, otherwise we can't use the IMU + # 1) Check we have an alt/az solve, otherwise we can't use the IMU + # If Alt exists: + # 2) Calculate the difference in the IMU measurements since the + # last plage solve. IMU "pos" is stored as Alt/Az. + # 3) Add the relative Alt/Az difference from the IMU to the plate + # -solved Alt/Az to give a dead-reckoning estimate of the current + # position. elif solved["Alt"]: imu = shared_state.imu() if imu: From 100b1994c4fa95f1d9e8257889801706b72f9227 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Sun, 1 Jun 2025 12:45:24 +0200 Subject: [PATCH 003/253] Create temporary environment_imu.yml file with numpy-quaternion --- python/environment_imu.yml | 46 ++++++++++++++++++++++++++++++++++++++ 1 file changed, 46 insertions(+) create mode 100644 python/environment_imu.yml diff --git a/python/environment_imu.yml b/python/environment_imu.yml new file mode 100644 index 000000000..e333bd431 --- /dev/null +++ b/python/environment_imu.yml @@ -0,0 +1,46 @@ +# YML for creating test environments with additional packages +name: pifinder_imu +channels: + - conda-forge +dependencies: + - pip + - pip: + # The base packages from requirements.txt + - adafruit-blinka==8.12.0 + - adafruit-circuitpython-bno055 + - bottle==0.12.25 + - cheroot==10.0.0 + - dataclasses_json==0.6.7 + - gpsdclient==1.3.2 + - grpcio==1.64.1 + - json5==0.9.25 + - luma.oled==3.12.0 + - luma.lcd==2.11.0 + - pillow==10.4.0 + - numpy==1.26.2 + - pandas==1.5.3 + - pydeepskylog==1.3.2 + - pyjwt==2.8.0 + - pytz==2022.7.1 + - requests==2.28.2 + - rpi-hardware-pwm==0.1.4 + - scipy + - scikit-learn==1.2.2 + - sh==1.14.3 + - skyfield==1.45 + - timezonefinder==6.1.9 + - tqdm==4.65.0 + - protobuf==4.25.2 + - aiofiles==24.1.0 + # Developer packages from requirements_dev.txt + - luma.emulator==1.4.0 + - PyHotKey==1.5.2 + - ruff==0.4.8 + - nox==2024.4.15 + - mypy==1.10.0 + - pytest==8.2.2 + - pygame==2.6.0 + - pre-commit==3.7.1 + - Babel==2.16.0 + # Additional packages for testing + - quaternion \ No newline at end of file From 27d4d7d8fdc6612a776485c8a4b2cbd82ef27874 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Sun, 1 Jun 2025 12:45:49 +0200 Subject: [PATCH 004/253] Init. commit of the temporary README_IMU.md with instructions --- python/README_IMU.md | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) create mode 100644 python/README_IMU.md diff --git a/python/README_IMU.md b/python/README_IMU.md new file mode 100644 index 000000000..672641f31 --- /dev/null +++ b/python/README_IMU.md @@ -0,0 +1,16 @@ +README: IMU support prototyping +=============================== + +> This README is temporary during the prototyping phase of the IMU support. + +# Installation & set up + +## Create a conda environment + +We need to install additional Python packages for the changes by creating a conda environment. + +``` +cd ~/PiFinder/python +conda env create -f environment_imu.yml +conda activate pifinder_imu +``` From 80b639b0f2f517b612228764526fa2f559acfb7a Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Sun, 1 Jun 2025 20:50:54 +0100 Subject: [PATCH 005/253] Replace conda environment_imu.yml with pip requirements --- python/environment_imu.yml | 46 ------------------------------------- python/requirements_imu.txt | 1 + 2 files changed, 1 insertion(+), 46 deletions(-) delete mode 100644 python/environment_imu.yml create mode 100644 python/requirements_imu.txt diff --git a/python/environment_imu.yml b/python/environment_imu.yml deleted file mode 100644 index e333bd431..000000000 --- a/python/environment_imu.yml +++ /dev/null @@ -1,46 +0,0 @@ -# YML for creating test environments with additional packages -name: pifinder_imu -channels: - - conda-forge -dependencies: - - pip - - pip: - # The base packages from requirements.txt - - adafruit-blinka==8.12.0 - - adafruit-circuitpython-bno055 - - bottle==0.12.25 - - cheroot==10.0.0 - - dataclasses_json==0.6.7 - - gpsdclient==1.3.2 - - grpcio==1.64.1 - - json5==0.9.25 - - luma.oled==3.12.0 - - luma.lcd==2.11.0 - - pillow==10.4.0 - - numpy==1.26.2 - - pandas==1.5.3 - - pydeepskylog==1.3.2 - - pyjwt==2.8.0 - - pytz==2022.7.1 - - requests==2.28.2 - - rpi-hardware-pwm==0.1.4 - - scipy - - scikit-learn==1.2.2 - - sh==1.14.3 - - skyfield==1.45 - - timezonefinder==6.1.9 - - tqdm==4.65.0 - - protobuf==4.25.2 - - aiofiles==24.1.0 - # Developer packages from requirements_dev.txt - - luma.emulator==1.4.0 - - PyHotKey==1.5.2 - - ruff==0.4.8 - - nox==2024.4.15 - - mypy==1.10.0 - - pytest==8.2.2 - - pygame==2.6.0 - - pre-commit==3.7.1 - - Babel==2.16.0 - # Additional packages for testing - - quaternion \ No newline at end of file diff --git a/python/requirements_imu.txt b/python/requirements_imu.txt new file mode 100644 index 000000000..fd5a90041 --- /dev/null +++ b/python/requirements_imu.txt @@ -0,0 +1 @@ +quaternion \ No newline at end of file From f2b50d343e79b0fd6d451a91dd9c76f35f6d49ba Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Sun, 1 Jun 2025 20:51:25 +0100 Subject: [PATCH 006/253] Update README_IMU.md with setup instructions --- python/README_IMU.md | 77 +++++++++++++++++++++++++++++++++++++++++--- 1 file changed, 73 insertions(+), 4 deletions(-) diff --git a/python/README_IMU.md b/python/README_IMU.md index 672641f31..f68985184 100644 --- a/python/README_IMU.md +++ b/python/README_IMU.md @@ -5,12 +5,81 @@ README: IMU support prototyping # Installation & set up -## Create a conda environment +## Set up a virtual environment to test the PiFinder We need to install additional Python packages for the changes by creating a conda environment. +## Create a virtual environment + +The first step is to create a virtual environment using `venv`. Connect to the PiFinder using `ssh` and install venv to create a virtual environment: + +```bash +sudo apt-get install python3-venv +``` + +Still on the PiFinder, create a virtual environment called `.venv_imu`. Note +that the virtual environment is created in the home directory because `venv` +creates the environment folder `.venv_imu\` where you run this command. + +```bash +cd ~ +python3 -m venv .venv_imu +``` + +Type this to activate the environment: + +```bash +source .venv_imu/bin/activate ``` -cd ~/PiFinder/python -conda env create -f environment_imu.yml -conda activate pifinder_imu + +At the end, it can be de-activated by typing: + +```bash +deactivate +``` + +### Install the packages + +Update `pip`: + +```bash +pip install --upgrade pip ``` + +Ensure that you're in new virtual environment and install the Python packages using `pip`. + +```bash +cd PiFinder/python +pip install -r requirements.txt +pip install -r requirements_dev.txt +pip install -r requirements_imu.txt +``` + +The last line installs the additional packages required (just `numpy-quaternion`). PiFinder can be +run from the command line as usual: + +```bash +python3 -m PiFinder.main +``` + +# Approach: Improved IMU support for quaternions for Altaz + +During normal operation, we want to find the pointing of the scope, expressed using $q_{hor2scope}$, which is the quaternion that rotates the scope axis in the horizontal frame from the *home* pointing to the current pointing. + +$$q_{hor2scope} = q_{hor2imu} \; q_{drift} \; q_{imu2scope}$$ + +The IMU outputs its orientation $q_{hor2imu}$ but this drifts over time by $q_{drift}$. $q_{imu2scope}$ rotates the IMU frame to the scope frame and is assumed to be fixed and determined during alignment of the PiFinder: + +$$q_{imu2scope} = q_{hor2imu}^{-1} \; q_{hor2scope}$$ + +During alignment, plate solving gives the pointing of the scope which can be used to estimate $q_{hor2scope}$ assuming a perfect altaz mount. For unit quaternions, we can also use the conjugate $q^*$ instead of $q^{-1}$, which is slightly faster to compute. + +When plate solved scope pointings are available during normal operation, we can estimate the drift, $q_{drift}$; + +$$q_{drift} = q_{hor2imu}^{-1} \; q_{hor2scope} \; q_{imu2scope}^{-1}$$ + +where $q_{hor2scope}$ can be estimated from plate solving (again, assuming a perfect altaz mount) and the IMU gives $q_{hor2imu}$. + +## Equatorial mounts + +It's possible that this can also work with equatorial mounts. Clearly, it won't be correct to use $q_{hor2scope}$ for the scope pointing because this is for altaz mounts and EQ mounts also rate the scope around its axis. It's possible that $q_{drift}$ will compensate for this but it won't be the most efficient way. \ No newline at end of file From fff26cf53f6f6ae65e8cb8035e5d808cb61b0001 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Sun, 1 Jun 2025 21:57:57 +0100 Subject: [PATCH 007/253] Convert IMU measurement to numpy quaternion --- python/PiFinder/integrator.py | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 94a7950eb..e3d473bf5 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -11,6 +11,8 @@ import time import copy import logging +import numpy as np +import quaternion # numpy-quaternion from PiFinder import config from PiFinder import state_utils @@ -67,6 +69,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa }, "Roll_offset": 0, # May/may not be needed - for experimentation "imu_pos": None, + "imu_quat": None, # IMU quaternion as numpy quaternion (scalar-first) "Alt": None, # Alt of scope "Az": None, "solve_source": None, @@ -179,7 +182,16 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa # calc new alt/az lis_imu = last_image_solve["imu_pos"] imu_pos = imu["pos"] + # Current IMU pointing relative to horizontal frame, + # converted from scalar-last to a scalar-first Numpy + # quaternion data type + q_hor2imu = np.quaternion(imu["quat"][3], + imu["quat"][0], imu["quat"][1], imu["quat"][2]) + if imu_moved(lis_imu, imu_pos): + # Estimate scope pointing using IMU dead-reckoning + q_hor2scope = q_hor2imu * q_drift * q_imu2scope + alt_offset = imu_pos[IMU_ALT] - lis_imu[IMU_ALT] if flip_alt_offset: alt_offset = ((alt_offset + 180) % 360 - 180) * -1 From bfb005623641d4eab265330ca4b1d99f94045b7f Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 7 Jun 2025 23:39:43 +0100 Subject: [PATCH 008/253] requirements_imu.txt: Fix - numpy-quaternion now installs correctly --- python/requirements_imu.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/python/requirements_imu.txt b/python/requirements_imu.txt index fd5a90041..01bc652ff 100644 --- a/python/requirements_imu.txt +++ b/python/requirements_imu.txt @@ -1 +1 @@ -quaternion \ No newline at end of file +numpy-quaternion \ No newline at end of file From 2407738235012d27c6a5559371b4c645f925c54a Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 7 Jun 2025 23:46:29 +0100 Subject: [PATCH 009/253] Move pip packages from requirements_imu to requirements_dev to try to pass Nox --- python/requirements_dev.txt | 1 + python/requirements_imu.txt | 1 - 2 files changed, 1 insertion(+), 1 deletion(-) delete mode 100644 python/requirements_imu.txt diff --git a/python/requirements_dev.txt b/python/requirements_dev.txt index 6bb063416..d00428a4f 100644 --- a/python/requirements_dev.txt +++ b/python/requirements_dev.txt @@ -9,3 +9,4 @@ pygame==2.6.0 pre-commit==3.7.1 Babel==2.16.0 xlrd==2.0.2 +numpy-quaternion # For testing IMU diff --git a/python/requirements_imu.txt b/python/requirements_imu.txt deleted file mode 100644 index 01bc652ff..000000000 --- a/python/requirements_imu.txt +++ /dev/null @@ -1 +0,0 @@ -numpy-quaternion \ No newline at end of file From 81dd0028b59406905065596e590722f58eb09fde Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Sun, 8 Jun 2025 11:03:42 +0200 Subject: [PATCH 010/253] Commit imu_simple_test.py to do basic tests of the IMU and print results to STDOUT. --- python/PiFinder/imu_simple_test.py | 183 +++++++++++++++++++++++++++++ 1 file changed, 183 insertions(+) create mode 100644 python/PiFinder/imu_simple_test.py diff --git a/python/PiFinder/imu_simple_test.py b/python/PiFinder/imu_simple_test.py new file mode 100644 index 000000000..b0b3c489b --- /dev/null +++ b/python/PiFinder/imu_simple_test.py @@ -0,0 +1,183 @@ +#!/usr/bin/python +# -*- coding:utf-8 -*- +""" +For testing: Not for use by PiFinder main loop. +Simple test with IMU based on imu_pi.py +""" + +import time +import board +import adafruit_bno055 +#import logging + +from scipy.spatial.transform import Rotation + +#from PiFinder import config + +#logger = logging.getLogger("IMU.pi") + +QUEUE_LEN = 10 +MOVE_CHECK_LEN = 2 + + +class Imu: + def __init__(self): + i2c = board.I2C() + self.sensor = adafruit_bno055.BNO055_I2C(i2c) + self.sensor.mode = adafruit_bno055.IMUPLUS_MODE + # self.sensor.mode = adafruit_bno055.NDOF_MODE + + self.quat_history = [(0, 0, 0, 0)] * QUEUE_LEN + self._flip_count = 0 + self.calibration = 0 + self.avg_quat = (0, 0, 0, 0) + self.__moving = False + + self.last_sample_time = time.time() + + # Calibration settings + self.imu_sample_frequency = 1 / 30 + + # First value is delta to exceed between samples + # to start moving, second is threshold to fall below + # to stop moving. + self.__moving_threshold = (0.0005, 0.0003) + + def quat_to_euler(self, quat): + """ + INPUTS: + quat: Scalar last quaternion (x, y, z, w) + + OUTPUTS: + rot_euler: [Az, related_to_roll, Alt] + """ + if quat[0] + quat[1] + quat[2] + quat[3] == 0: + return 0, 0, 0 + rot = Rotation.from_quat(quat) # Expects scalar-last quaternion + # Lowercase 'xyz' indicate extrinsic rotation: + rot_euler = rot.as_euler("xyz", degrees=True) + # convert from -180/180 to 0/360 + rot_euler[0] += 180 + rot_euler[1] += 180 + rot_euler[2] += 180 + return rot_euler + + def moving(self): + """ + Compares most recent reading + with past readings + """ + return self.__moving + + def update(self): + # check for update frequency + if time.time() - self.last_sample_time < self.imu_sample_frequency: + return + + self.last_sample_time = time.time() + + # Throw out non-calibrated data + self.calibration = self.sensor.calibration_status[1] + if self.calibration == 0: + #logger.warning("NOIMU CAL") + return True + # adafruit_bno055 gives quaternion convention (w, x, y,) + quat = self.sensor.quaternion + if quat[0] is None: + #logger.warning("IMU: Failed to get sensor values") + return + + _quat_diff = [] + for i in range(4): + _quat_diff.append(abs(quat[i] - self.quat_history[-1][i])) + + self.__reading_diff = sum(_quat_diff) + + # This seems to be some sort of defect / side effect + # of the integration system in the BNO055 + # When not moving quat output will vaccilate + # by exactly this amount... so filter this out + if self.__reading_diff == 0.0078125: + self.__reading_diff = 0 + return + + # Sometimes the quat output will 'flip' and change by 2.0+ + # from one reading to another. This is clearly noise or an + # artifact, so filter them out + if self.__reading_diff > 1.5: + self._flip_count += 1 + if self._flip_count > 10: + # with the history initialized to 0,0,0,0 the unit + # can get stuck seeing flips if the IMU starts + # returning data. This count will reset history + # to the current state if it exceeds 10 + self.quat_history = [quat] * QUEUE_LEN + self.__reading_diff = 0 + else: + self.__reading_diff = 0 + return + else: + # no flip + self._flip_count = 0 + + self.avg_quat = quat + if len(self.quat_history) == QUEUE_LEN: + self.quat_history = self.quat_history[1:] + self.quat_history.append(quat) + + if self.__moving: + if self.__reading_diff < self.__moving_threshold[1]: + self.__moving = False + else: + if self.__reading_diff > self.__moving_threshold[0]: + self.__moving = True + + def get_euler(self): + return list(self.quat_to_euler(self.avg_quat)) + + +def imu_monitor(): + #MultiprocLogging.configurer(log_queue) + imu = Imu() + imu_calibrated = False + imu_data = { + "moving": False, + "move_start": None, + "move_end": None, + "pos": [0, 0, 0], # Corresponds to [Az, related_to_roll, Alt] + "quat": [0, 0, 0, 0], # Scalar last quaternion (x, y, z, w) + "start_pos": [0, 0, 0], + "status": 0, + } + + while True: + imu.update() + imu_data["status"] = imu.calibration + if imu.moving(): + if not imu_data["moving"]: + #logger.debug("IMU: move start") + imu_data["moving"] = True + imu_data["start_pos"] = imu_data["pos"] + imu_data["move_start"] = time.time() + imu_data["pos"] = imu.get_euler() + imu_data["quat"] = imu.avg_quat + + print(imu_data["quat"]) + + else: + if imu_data["moving"]: + # If we were moving and we now stopped + #logger.debug("IMU: move end") + imu_data["moving"] = False + imu_data["pos"] = imu.get_euler() + imu_data["quat"] = imu.avg_quat + imu_data["move_end"] = time.time() + + if not imu_calibrated: + if imu_data["status"] == 3: + imu_calibrated = True + #console_queue.put("IMU: NDOF Calibrated!") + + +if __name__ == "__main__": + imu_monitor() From 56f94dcf731e6bb73b4f435e943e01ea69554b55 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Tue, 10 Jun 2025 17:59:47 +0100 Subject: [PATCH 011/253] Refactor --- python/PiFinder/imu_pi.py | 1 + python/PiFinder/imu_simple_test.py | 7 ++++--- 2 files changed, 5 insertions(+), 3 deletions(-) diff --git a/python/PiFinder/imu_pi.py b/python/PiFinder/imu_pi.py index 91d2a7a76..89239bc19 100644 --- a/python/PiFinder/imu_pi.py +++ b/python/PiFinder/imu_pi.py @@ -25,6 +25,7 @@ class Imu: def __init__(self): i2c = board.I2C() self.sensor = adafruit_bno055.BNO055_I2C(i2c) + # IMPLUS mode: Accelerometer + Gyro + Fusion data self.sensor.mode = adafruit_bno055.IMUPLUS_MODE # self.sensor.mode = adafruit_bno055.NDOF_MODE cfg = config.Config() diff --git a/python/PiFinder/imu_simple_test.py b/python/PiFinder/imu_simple_test.py index b0b3c489b..3ead1ea1f 100644 --- a/python/PiFinder/imu_simple_test.py +++ b/python/PiFinder/imu_simple_test.py @@ -20,13 +20,14 @@ MOVE_CHECK_LEN = 2 -class Imu: +class ImuSimple: def __init__(self): i2c = board.I2C() self.sensor = adafruit_bno055.BNO055_I2C(i2c) self.sensor.mode = adafruit_bno055.IMUPLUS_MODE # self.sensor.mode = adafruit_bno055.NDOF_MODE + # Unlike Imu(), we use the IMU's native orientation self.quat_history = [(0, 0, 0, 0)] * QUEUE_LEN self._flip_count = 0 self.calibration = 0 @@ -81,7 +82,7 @@ def update(self): if self.calibration == 0: #logger.warning("NOIMU CAL") return True - # adafruit_bno055 gives quaternion convention (w, x, y,) + # adafruit_bno055 gives quaternion convention (w, x, y, z) quat = self.sensor.quaternion if quat[0] is None: #logger.warning("IMU: Failed to get sensor values") @@ -138,7 +139,7 @@ def get_euler(self): def imu_monitor(): #MultiprocLogging.configurer(log_queue) - imu = Imu() + imu = ImuSimple() imu_calibrated = False imu_data = { "moving": False, From 9361d1339880b8534573ef7687fbe8de75387a51 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Sun, 22 Jun 2025 17:05:23 +0200 Subject: [PATCH 012/253] Resolve merge conflict --- python/PiFinder/imu_simple_test.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/python/PiFinder/imu_simple_test.py b/python/PiFinder/imu_simple_test.py index 3ead1ea1f..15c32982b 100644 --- a/python/PiFinder/imu_simple_test.py +++ b/python/PiFinder/imu_simple_test.py @@ -134,7 +134,7 @@ def update(self): self.__moving = True def get_euler(self): - return list(self.quat_to_euler(self.avg_quat)) + return list(self.quat_to_euler(self.avg_quat)) # !! Expect scalar-last but avg_quat is scalar-first?? def imu_monitor(): @@ -146,7 +146,7 @@ def imu_monitor(): "move_start": None, "move_end": None, "pos": [0, 0, 0], # Corresponds to [Az, related_to_roll, Alt] - "quat": [0, 0, 0, 0], # Scalar last quaternion (x, y, z, w) + "quat": [0, 0, 0, 0], # Scalar-first quaternion (w, x, y, z) "start_pos": [0, 0, 0], "status": 0, } From ab1ba5c93e704f9c5cfe7121d1b81e80acb5de9a Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Mon, 9 Jun 2025 23:36:56 +0200 Subject: [PATCH 013/253] Add comments to clarify that it should scalar-first quaternion --- python/PiFinder/imu_pi.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/python/PiFinder/imu_pi.py b/python/PiFinder/imu_pi.py index 89239bc19..ee3fb9bfe 100644 --- a/python/PiFinder/imu_pi.py +++ b/python/PiFinder/imu_pi.py @@ -114,7 +114,7 @@ def update(self): if self.calibration == 0: logger.warning("NOIMU CAL") return True - # adafruit_bno055 gives quaternion convention (w, x, y, z) + # adafruit_bno055 uses quaternion convention (w, x, y, z) quat = self.sensor.quaternion if quat[0] is None: logger.warning("IMU: Failed to get sensor values") @@ -166,7 +166,7 @@ def update(self): self.__moving = True def get_euler(self): - return list(self.quat_to_euler(self.avg_quat)) + return list(self.quat_to_euler(self.avg_quat)) # !! Expect scalar-last but avg_quat is scalar-first?? def __str__(self): return ( @@ -192,7 +192,7 @@ def imu_monitor(shared_state, console_queue, log_queue): "move_start": None, "move_end": None, "pos": [0, 0, 0], # Corresponds to [Az, related_to_roll, Alt] - "quat": [0, 0, 0, 0], # Scalar-last quaternion (x, y, z, w) + "quat": [0, 0, 0, 0], # Scalar-first quaternion (w, x, y, z) "start_pos": [0, 0, 0], "status": 0, } From 450a2e3d8e5d97f7f3a67ba0753ef57832e5fcf3 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Mon, 9 Jun 2025 23:42:17 +0200 Subject: [PATCH 014/253] Disable rotating the IMU axes - use its native axes --- python/PiFinder/imu_pi.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/python/PiFinder/imu_pi.py b/python/PiFinder/imu_pi.py index ee3fb9bfe..4c1cd71d2 100644 --- a/python/PiFinder/imu_pi.py +++ b/python/PiFinder/imu_pi.py @@ -29,6 +29,7 @@ def __init__(self): self.sensor.mode = adafruit_bno055.IMUPLUS_MODE # self.sensor.mode = adafruit_bno055.NDOF_MODE cfg = config.Config() + """ Disable rotating the IMU axes. Use its native form if ( cfg.get_option("screen_direction") == "flat" or cfg.get_option("screen_direction") == "straight" @@ -60,6 +61,7 @@ def __init__(self): adafruit_bno055.AXIS_REMAP_POSITIVE, adafruit_bno055.AXIS_REMAP_POSITIVE, ) + """ self.quat_history = [(0, 0, 0, 0)] * QUEUE_LEN self._flip_count = 0 self.calibration = 0 From 7648c3863166a1ce7d7ff080ba5532285c6bf708 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Mon, 9 Jun 2025 23:44:25 +0200 Subject: [PATCH 015/253] Remove calls to using Euler angles --- python/PiFinder/imu_pi.py | 27 +++------------------------ 1 file changed, 3 insertions(+), 24 deletions(-) diff --git a/python/PiFinder/imu_pi.py b/python/PiFinder/imu_pi.py index 4c1cd71d2..856eeda86 100644 --- a/python/PiFinder/imu_pi.py +++ b/python/PiFinder/imu_pi.py @@ -78,24 +78,6 @@ def __init__(self): # to stop moving. self.__moving_threshold = (0.0005, 0.0003) - def quat_to_euler(self, quat): - """ - INPUTS: - quat: Scalar last quaternion (x, y, z, w) - - OUTPUTS: - rot_euler: [Az, related_to_roll, Alt] - """ - if quat[0] + quat[1] + quat[2] + quat[3] == 0: - return 0, 0, 0 - rot = Rotation.from_quat(quat) # Expects scalar-last quaternion - # Lowercase 'xyz' indicate extrinsic rotation: - rot_euler = rot.as_euler("xyz", degrees=True) - # convert from -180/180 to 0/360 - rot_euler[0] += 180 - rot_euler[1] += 180 - rot_euler[2] += 180 - return rot_euler def moving(self): """ @@ -167,9 +149,6 @@ def update(self): if self.__reading_diff > self.__moving_threshold[0]: self.__moving = True - def get_euler(self): - return list(self.quat_to_euler(self.avg_quat)) # !! Expect scalar-last but avg_quat is scalar-first?? - def __str__(self): return ( f"IMU Information:\n" @@ -193,7 +172,7 @@ def imu_monitor(shared_state, console_queue, log_queue): "moving": False, "move_start": None, "move_end": None, - "pos": [0, 0, 0], # Corresponds to [Az, related_to_roll, Alt] + "pos": [0, 0, 0], # Corresponds to [Az, related_to_roll, Alt] --> **TO REMOVE LATER "quat": [0, 0, 0, 0], # Scalar-first quaternion (w, x, y, z) "start_pos": [0, 0, 0], "status": 0, @@ -208,7 +187,7 @@ def imu_monitor(shared_state, console_queue, log_queue): imu_data["moving"] = True imu_data["start_pos"] = imu_data["pos"] imu_data["move_start"] = time.time() - imu_data["pos"] = imu.get_euler() + imu_data["pos"] = None # Remove this later. Was used to store Euler angles imu_data["quat"] = imu.avg_quat else: @@ -216,7 +195,7 @@ def imu_monitor(shared_state, console_queue, log_queue): # If we were moving and we now stopped logger.debug("IMU: move end") imu_data["moving"] = False - imu_data["pos"] = imu.get_euler() + imu_data["pos"] = None imu_data["quat"] = imu.avg_quat imu_data["move_end"] = time.time() From 96d052c8d18eac55ad03be99265a24735b0670aa Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Mon, 9 Jun 2025 23:56:22 +0200 Subject: [PATCH 016/253] imu_pi: Disable "pos" (Euler angles) --- python/PiFinder/imu_pi.py | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/python/PiFinder/imu_pi.py b/python/PiFinder/imu_pi.py index 856eeda86..75b3c5662 100644 --- a/python/PiFinder/imu_pi.py +++ b/python/PiFinder/imu_pi.py @@ -172,9 +172,9 @@ def imu_monitor(shared_state, console_queue, log_queue): "moving": False, "move_start": None, "move_end": None, - "pos": [0, 0, 0], # Corresponds to [Az, related_to_roll, Alt] --> **TO REMOVE LATER + #"pos": [0, 0, 0], # Corresponds to [Az, related_to_roll, Alt] --> **TO REMOVE LATER "quat": [0, 0, 0, 0], # Scalar-first quaternion (w, x, y, z) - "start_pos": [0, 0, 0], + #"start_pos": [0, 0, 0], "status": 0, } @@ -185,9 +185,9 @@ def imu_monitor(shared_state, console_queue, log_queue): if not imu_data["moving"]: logger.debug("IMU: move start") imu_data["moving"] = True - imu_data["start_pos"] = imu_data["pos"] + #imu_data["start_pos"] = imu_data["pos"] imu_data["move_start"] = time.time() - imu_data["pos"] = None # Remove this later. Was used to store Euler angles + #imu_data["pos"] = None # Remove this later. Was used to store Euler angles imu_data["quat"] = imu.avg_quat else: @@ -195,7 +195,7 @@ def imu_monitor(shared_state, console_queue, log_queue): # If we were moving and we now stopped logger.debug("IMU: move end") imu_data["moving"] = False - imu_data["pos"] = None + #imu_data["pos"] = None imu_data["quat"] = imu.avg_quat imu_data["move_end"] = time.time() From ca5cbd8c1dba72e62ffd75ee7bfc0d7b50c3ae28 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Tue, 10 Jun 2025 00:07:45 +0200 Subject: [PATCH 017/253] imu_pi: Convert avg_quat to numpy quaternion to avoid ambiguity over scalar first/last --- python/PiFinder/imu_pi.py | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/python/PiFinder/imu_pi.py b/python/PiFinder/imu_pi.py index 75b3c5662..e17069990 100644 --- a/python/PiFinder/imu_pi.py +++ b/python/PiFinder/imu_pi.py @@ -10,8 +10,9 @@ import board import adafruit_bno055 import logging - -from scipy.spatial.transform import Rotation +import numpy as np +import quaternion # Numpy quaternion +#from scipy.spatial.transform import Rotation from PiFinder import config @@ -65,7 +66,7 @@ def __init__(self): self.quat_history = [(0, 0, 0, 0)] * QUEUE_LEN self._flip_count = 0 self.calibration = 0 - self.avg_quat = (0, 0, 0, 0) + self.avg_quat = np.quaternion(0, 0, 0, 0) # Init to invalid quaternion self.__moving = False self.last_sample_time = time.time() @@ -137,7 +138,7 @@ def update(self): # no flip self._flip_count = 0 - self.avg_quat = quat + self.avg_quat = np.quaternion(quat[0], quat[1], quat[2], quat[3]) if len(self.quat_history) == QUEUE_LEN: self.quat_history = self.quat_history[1:] self.quat_history.append(quat) @@ -173,7 +174,7 @@ def imu_monitor(shared_state, console_queue, log_queue): "move_start": None, "move_end": None, #"pos": [0, 0, 0], # Corresponds to [Az, related_to_roll, Alt] --> **TO REMOVE LATER - "quat": [0, 0, 0, 0], # Scalar-first quaternion (w, x, y, z) + "quat": np.quaternion(0, 0, 0, 0), # Scalar-first quaternion (w, x, y, z) - Init to invalid quaternion #"start_pos": [0, 0, 0], "status": 0, } From 996d937057af441fe452b829f5b6991ca8cca9b3 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Tue, 10 Jun 2025 00:43:05 +0200 Subject: [PATCH 018/253] integrator: Change over from using imu_pos to quaternions. Still in pseudo code --- python/PiFinder/integrator.py | 37 +++++++++++++++++++++++++---------- 1 file changed, 27 insertions(+), 10 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index e3d473bf5..237a5917d 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -19,8 +19,8 @@ import PiFinder.calc_utils as calc_utils from PiFinder.multiproclogging import MultiprocLogging -IMU_ALT = 2 -IMU_AZ = 0 +#IMU_ALT = 2 +#IMU_AZ = 0 logger = logging.getLogger("IMU.Integrator") @@ -29,6 +29,8 @@ def imu_moved(imu_a, imu_b): """ Compares two IMU states to determine if they are the 'same' if either is none, returns False + + **TODO: This imu_a and imu_b used to be pos. They are now quaternions** """ if imu_a is None: return False @@ -68,7 +70,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa "Roll": None, }, "Roll_offset": 0, # May/may not be needed - for experimentation - "imu_pos": None, + #"imu_pos": None, "imu_quat": None, # IMU quaternion as numpy quaternion (scalar-first) "Alt": None, # Alt of scope "Az": None, @@ -78,6 +80,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa "constellation": None, } cfg = config.Config() + """ Disable dependence of IMU on PiFinder type if ( cfg.get_option("screen_direction") == "left" or cfg.get_option("screen_direction") == "flat" @@ -87,7 +90,8 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa flip_alt_offset = True else: flip_alt_offset = False - + """ + # This holds the last image solve position info # so we can delta for IMU updates last_image_solve = None @@ -180,18 +184,30 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa # If we have alt, then we have a position/time # calc new alt/az - lis_imu = last_image_solve["imu_pos"] - imu_pos = imu["pos"] + #lis_imu = last_image_solve["imu_pos"] + lis_imu_quat = last_image_solve["imu_quat"] + imu_quat = imu["quat"] + #imu_pos = imu["pos"] # Current IMU pointing relative to horizontal frame, # converted from scalar-last to a scalar-first Numpy # quaternion data type - q_hor2imu = np.quaternion(imu["quat"][3], - imu["quat"][0], imu["quat"][1], imu["quat"][2]) + #q_hor2imu = np.quaternion(imu["quat"][3], + # imu["quat"][0], imu["quat"][1], imu["quat"][2]) - if imu_moved(lis_imu, imu_pos): + if imu_moved(lis_imu_quat, imu_quat): # Estimate scope pointing using IMU dead-reckoning - q_hor2scope = q_hor2imu * q_drift * q_imu2scope + #q_hor2scope = q_hor2imu * q_drift * q_imu2scope + + # Using pseudo code here: + lis_q_camera = altaz_to_quat(last_image_solve["camera_center"]["Az"], + last_image_solve["camera_center"]["Alt"]) + q_imu2camera = lis_imu_quat.conj() * lis_q_camera # For intrinsic rotations + + q_camera = imu_quat * q_imu2camera # Estimate current camera center using IMU + solved["Az"], solved["Alt"] = q_horiz2altaz(q_camera) + # Calculate for scope center + """ DISABLE - Use quaternions alt_offset = imu_pos[IMU_ALT] - lis_imu[IMU_ALT] if flip_alt_offset: alt_offset = ((alt_offset + 180) % 360 - 180) * -1 @@ -208,6 +224,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa solved["camera_center"]["Az"] = ( last_image_solve["camera_center"]["Az"] + az_offset ) % 360 + """ # N.B. Assumes that location hasn't changed since last solve # Turn this into RA/DEC From 28e64bac1e0f5385e3446708ca2898a599de7168 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 21 Jun 2025 14:21:20 +0100 Subject: [PATCH 019/253] Rename --> imu_print_measurements.py. Add usage in README_IMU.md --- astro_data/comets.txt | 1203 +++++++++++++++++ ...mple_test.py => imu_print_measurements.py} | 4 +- python/README_IMU.md | 6 + python/tetra3 | 1 + 4 files changed, 1212 insertions(+), 2 deletions(-) create mode 100644 astro_data/comets.txt rename python/PiFinder/{imu_simple_test.py => imu_print_measurements.py} (98%) create mode 120000 python/tetra3 diff --git a/astro_data/comets.txt b/astro_data/comets.txt new file mode 100644 index 000000000..4b650f6f4 --- /dev/null +++ b/astro_data/comets.txt @@ -0,0 +1,1203 @@ + PJ96R020 2026 06 15.6631 2.587044 0.314270 333.4862 40.0451 2.5990 20250607 11.5 4.0 P/1996 R2 (Lagerkvist) NK 1615 + PJ98V24S 2027 09 7.8207 3.419529 0.243582 244.8820 159.0401 5.0292 20250607 13.0 2.0 P/1998 VS24 (LINEAR) MPC 75703 + PJ99R28O 2025 10 30.3009 1.122847 0.672185 231.3524 137.8416 7.5670 20250607 20.0 2.0 P/1999 RO28 (LONEOS) NK 731 + PJ99XC0N 2025 12 21.6387 3.297889 0.211622 161.5994 285.2407 5.0298 20250607 13.5 2.0 P/1999 XN120 (Catalina) MPC 75704 + PK00R020 2025 12 2.2969 1.628195 0.530641 176.5814 160.2712 11.6788 20250607 18.0 4.0 P/2000 R2 (LINEAR) NK 744 + PK01H050 2030 10 22.6222 2.442745 0.599183 224.5860 328.6738 8.3720 20250607 12.0 4.0 P/2001 H5 (NEAT) MPC 43019 + PK02E57J 2018 06 20.2371 2.621487 0.593904 167.2783 330.2284 4.9889 20250607 12.5 4.0 P/2002 EJ57 (LINEAR) MPEC 2023-UR6 + CK02V94Q 2006 02 10.9809 6.755134 0.963821 99.8065 35.0990 70.6577 20250607 9.5 2.0 C/2002 VQ94 (LINEAR) MPC 75007 + CK03A020 2003 11 4.9613 11.358784 0.997924 346.4579 154.5067 8.0702 20250607 3.5 4.0 C/2003 A2 (Gleason) MPC184407 + PK03F020 2019 11 14.5137 3.013162 0.539112 192.9259 358.9192 11.6495 20250607 16.5 2.0 P/2003 F2 (NEAT) MPC 50354 + PK03T120 2024 07 3.7309 0.593884 0.770175 219.7925 174.5764 11.0235 20250607 17.0 4.0 P/2003 T12 (SOHO) MPC105235 + PK04FE0Y 2027 02 22.0486 4.011274 0.192745 254.2397 327.2620 2.1627 20250607 12.5 2.0 P/2004 FY140 (LINEAR) MPEC 2022-YN2 + PK04R030 2021 09 15.6937 3.539592 0.254472 37.2261 305.1202 12.8014 20250607 14.5 4.0 P/2004 R3 (LINEAR-NEAT) MPC 53304 + PK04V050 2027 08 6.2877 4.433603 0.448659 87.2012 47.7415 19.3379 20250607 8.0 4.0 P/2004 V5 (LINEAR-Hill) MPC 75705 + PK04V05b 2027 08 7.2597 4.433608 0.448677 87.2054 47.7419 19.3380 20250607 8.0 4.0 P/2004 V5-B (LINEAR-Hill) MPC 75705 + PK05E010 2023 09 28.1159 4.402632 0.377279 193.9221 335.4981 4.2606 20250607 10.0 4.0 P/2005 E1 (Tubbiolo) MPC 54164 + PK05J010 2025 07 11.7017 1.539551 0.569360 338.9133 268.7998 31.7405 20250607 16.5 4.0 P/2005 J1 (McNaught) MPC 79019 + PK05L010 2021 12 24.3227 2.935631 0.252620 160.0017 127.6738 8.5769 20250607 9.5 4.0 P/2005 L1 (McNaught) MPC 74246 + PK05S020 2029 01 25.9002 6.399698 0.198499 229.9970 161.3338 3.1385 20250607 7.5 4.0 P/2005 S2 (Skiff) MPC 75706 + PK05T030 2026 08 19.6558 6.253688 0.174377 7.0803 27.6229 6.2319 20250607 9.0 4.0 P/2005 T3 (Read) MPC 73461 + PK05T040 2034 05 27.9119 0.648203 0.930688 41.7987 25.8303 160.2515 20250607 15.0 4.0 P/2005 T4 (SWAN) MPC 73461 + PK05T050 2025 06 14.9420 3.253537 0.551769 304.7801 57.0620 21.3836 20250607 11.0 4.0 P/2005 T5 (Broughton) MPC 75706 + PK06H30R 2028 10 9.2542 1.219308 0.843615 117.5106 309.7590 31.9558 20250607 11.0 4.0 P/2006 HR30 (Siding Spring) MPC 75707 + PK07C020 2026 03 21.2175 3.692565 0.474325 180.1208 275.2340 8.6130 20250607 10.0 4.0 P/2007 C2 (Catalina) MPC 75707 + CK07D010 2007 06 14.0365 8.739347 0.992912 339.7507 171.0421 41.5133 20250607 3.5 4.0 C/2007 D1 (LINEAR) MPC 84315 + PK07K020 2027 01 26.4813 2.312371 0.686419 347.0918 188.4259 7.5950 20250607 14.0 4.0 P/2007 K2 (Gibbs) MPEC 2024-GJ3 + PK07Q020 2020 11 25.0393 1.875009 0.668787 162.8493 172.2261 10.1936 20250607 16.0 4.0 P/2007 Q2 (Gilmore) MPC 60925 + PK07S010 2022 10 6.4356 2.528059 0.337946 245.2735 141.3271 5.9632 20250607 13.0 4.0 P/2007 S1 (Zhao) MPC 73462 + CK07S020 2008 09 3.9818 5.535672 0.556952 210.1455 296.1300 16.9160 20250607 6.5 4.0 C/2007 S2 (Lemmon) MPEC 2024-GJ3 + PK07S24A 2022 12 1.7764 2.683412 0.568947 107.8067 233.2428 17.1112 20250607 12.6 4.0 P/2007 SA24 (Lemmon) MPC184407 + PK07T020 2023 11 17.5014 0.652963 0.785459 359.6677 3.3929 9.7481 20250607 18.5 4.0 P/2007 T2 (Kowalski) MPC 61994 + CK08E010 2008 08 22.3547 4.812629 0.552886 270.3589 188.9234 34.8644 20250607 7.0 4.0 C/2008 E1 (Catalina) MPEC 2024-GJ3 + PK08O030 2031 12 23.5938 2.494071 0.696168 341.2019 47.6075 32.3107 20250607 13.0 4.0 P/2008 O3 (Boattini) MPC 64114 + PK08Y030 2031 10 6.1790 4.435041 0.448196 238.1279 262.8392 38.7791 20250607 8.5 4.0 P/2008 Y3 (McNaught) MPC 75710 + PK09B010 2026 06 30.4285 2.448428 0.635945 129.0025 297.1087 22.2596 20250607 13.0 4.0 P/2009 B1 (Boattini) MPC 75710 + CK09G010 2009 04 17.3298 1.135790 0.997493 175.5077 120.8728 108.0359 20250607 9.0 4.0 C/2009 G1 (STEREO) MPC 66466 + PK09K37F 2026 01 17.7518 2.835003 0.310567 143.9722 111.9438 11.3881 20250607 14.9 4.0 P/2009 KF37 MPC184407 + PK09O030 2031 01 25.8804 2.439262 0.686160 154.4228 183.7170 16.2524 20250607 12.5 4.0 P/2009 O3 (Hill) MPC 75710 + PK09Q050 2029 12 18.2032 2.901108 0.609330 209.2043 160.2071 40.9542 20250607 10.0 4.0 P/2009 Q5 (McNaught) MPC 68902 + PK09T020 2031 06 11.2689 1.792320 0.767477 216.0034 216.3137 27.5993 20250607 14.0 4.0 P/2009 T2 (La Sagra) MPC112389 + PK09W51X 2026 04 15.0730 0.802412 0.739678 118.2942 31.5224 9.5979 20250607 19.0 2.0 P/2009 WX51 (Catalina) MPC105235 + PK09Y020 2026 12 1.7362 2.370734 0.637400 172.2414 262.0833 29.9731 20250607 13.0 4.0 P/2009 Y2 (Kowalski) MPC 74247 + PK10C010 2028 09 21.8475 5.248095 0.263857 2.9170 141.5904 9.1157 20250607 9.5 4.0 P/2010 C1 (Scotti) MPC 75008 + PK10D020 2027 07 9.4680 3.682828 0.451700 120.0136 319.8763 57.1352 20250607 16.0 4.0 P/2010 D2 (WISE) MPC 75008 + PK10E020 2035 08 1.5776 2.410277 0.720879 8.2124 177.8262 15.4258 20250607 14.0 4.0 P/2010 E2 (Jarnac) MPC 75009 + PK10H020 2025 03 9.6617 3.075967 0.197745 128.0513 64.1887 14.2792 20250607 6.0 4.0 P/2010 H2 (Vales) MPC 72851 + PK10H030 2026 05 25.2323 0.043785 0.985575 26.0715 77.1824 23.1483 20250607 20.0 2.0 P/2010 H3 (SOHO) MPC 70361 + PK10H040 2027 05 21.6248 4.850297 0.267092 179.0805 44.7463 2.3178 20250607 10.5 4.0 P/2010 H4 (Scotti) MPEC 2024-GJ3 + PK10H050 2029 05 21.8734 6.058627 0.155233 174.9000 24.5167 14.0527 20250607 13.0 2.0 P/2010 H5 (Scotti) MPC 74637 + PK10J030 2037 07 19.1961 2.479028 0.724184 157.4193 106.5395 13.2265 20250607 11.0 4.0 P/2010 J3 (McMillan) MPC 98558 + PK10J81C 2034 05 29.1727 1.798140 0.778084 12.5056 30.8516 38.7689 20250607 9.0 4.0 P/2010 JC81 (WISE) MPC 84315 + PK10K43G 2023 08 26.6335 2.885502 0.482916 354.3851 325.6891 13.6502 20250607 12.7 4.0 P/2010 KG43 MPC184408 + AK10LD5N 2011 05 25.1513 1.747047 0.999955 181.5725 184.8515 64.4600 20250607 14.0 2.0 A/2010 LN135 MPEC 2024-H77 + PK10LF5H 2025 04 9.0228 2.224047 0.405984 308.5231 221.1195 8.8068 20250607 14.3 4.0 P/2010 LH155 MPC184408 + PK10T020 2024 02 23.7559 3.768461 0.325775 350.2116 57.8187 7.8597 20250607 11.5 4.0 P/2010 T2 (PANSTARRS) MPC 74248 + PK10U010 2026 09 9.8898 4.875212 0.248382 86.5374 280.8069 8.2274 20250607 9.5 4.0 P/2010 U1 (Boattini) MPC 82316 + CK10U030 2019 02 28.0286 8.439075 0.999655 88.0835 42.9923 55.5467 20250607 1.0 4.0 C/2010 U3 (Boattini) MPEC 2023-J95 + PK10U55H 2028 06 2.2941 2.893950 0.564697 225.3112 232.8274 8.0368 20250607 11.0 4.0 P/2010 UH55 (Spacewatch) MPC 79021 + PK11C020 2032 02 4.1782 5.400215 0.271120 160.2807 11.9604 10.8951 20250607 9.0 4.0 P/2011 C2 (Gibbs) MPC 84021 + PK11FE3R 2029 02 1.3026 3.767600 0.452555 349.6492 190.8478 15.9624 20250607 14.0 2.0 P/2011 FR143 (Lemmon) MPC 79866 + PK11J15B 2032 01 11.5095 5.057223 0.314768 110.6992 153.5861 19.1256 20250607 9.0 4.0 P/2011 JB15 (Spacewatch-Boattini) MPC 82317 + PK11N010 2027 12 30.9343 2.833536 0.545461 330.4938 77.6285 35.7860 20250607 11.5 4.0 P/2011 N1 (ASH) MPC 87913 + PK11P010 2030 12 21.6293 5.026331 0.326370 349.1757 4.2587 5.6519 20250607 9.0 4.0 P/2011 P1 (McNaught) MPEC 2022-ED3 + PK11S010 2014 08 24.4875 6.868388 0.200997 192.9473 218.8973 2.6885 20250607 8.0 4.0 P/2011 S1 (Gibbs) MPEC 2022-HC2 + PK11V010 2026 04 23.5464 1.742157 0.548369 269.6087 46.4914 7.3829 20250607 15.5 4.0 P/2011 V1 (Boattini) MPEC 2023-UR6 + PK11W010 2022 02 9.4392 3.325909 0.288474 283.0319 161.8074 3.7161 20250607 11.5 4.0 P/2011 W1 (PANSTARRS) MPC 82718 + PK11Y020 2027 10 2.1955 1.798814 0.711201 132.0710 309.3201 6.3919 20250607 15.0 4.0 P/2011 Y2 (Boattini) MPC 79342 + PK12B010 2030 03 8.6275 3.858979 0.410122 161.9202 36.2097 7.6055 20250607 9.0 4.0 P/2012 B1 (PANSTARRS) MPEC 2022-K19 + PK12C030 2011 10 6.7469 3.605925 0.630111 344.9542 135.3677 9.0920 13.0 4.0 P/2012 C3 (PANSTARRS) MPC 78590 + PK12F020 2029 03 19.2652 2.916443 0.540542 33.1595 226.9537 14.6982 20250607 12.0 4.0 P/2012 F2 (PANSTARRS) MPC 84931 + PK12G010 2029 03 27.9895 2.790801 0.329538 266.0173 283.2373 12.1680 20250607 15.0 4.0 P/2012 G1 (PANSTARRS) MPEC 2022-ED3 + PK12K030 2026 07 15.9127 2.100790 0.421688 172.1395 125.8057 13.1816 20250607 15.0 4.0 P/2012 K3 (Gibbs) MPC 80898 + CK12K51A 2011 11 6.2419 4.866640 0.990866 93.9909 344.8390 70.7310 20250607 8.7 4.0 C/2012 KA51 MPC184408 + PK12N00J 2037 02 1.4393 1.299842 0.846492 338.3867 315.6944 84.3223 20250607 14.5 4.0 P/2012 NJ (La Sagra) MPC 88326 + PK12O010 2025 11 1.1140 1.440107 0.593567 238.2789 91.9402 7.4280 20250607 17.5 4.0 P/2012 O1 (McNaught) MPC 81470 + PK12O020 2026 04 1.5193 1.701652 0.531233 183.4108 120.6616 24.4555 20250607 17.0 4.0 P/2012 O2 (McNaught) MPC 80899 + PK12T020 2027 01 21.0961 4.790638 0.162089 311.1848 73.8756 12.5699 20250607 10.0 4.0 P/2012 T2 (PANSTARRS) MPC 82320 + PK12T030 2027 08 9.9441 2.367430 0.615592 195.4656 114.3253 9.5537 20250607 15.0 4.0 P/2012 T3 (PANSTARRS) MPC 80900 + PK12U020 2031 12 5.7929 3.559504 0.500479 228.4442 185.2727 10.7582 20250607 12.5 4.0 P/2012 U2 (PANSTARRS) MPC 82720 + PK13A76L 2029 06 28.0735 2.044172 0.685530 27.1165 146.0925 144.9137 20250607 16.0 4.0 P/2013 AL76 (Catalina) MPC 82721 + PK13G010 2032 01 19.0838 3.384753 0.509956 51.3674 221.3161 5.4571 20250607 11.0 4.0 P/2013 G1 (Kowalski) MPC 91612 + PK13G040 2022 06 19.1364 2.617985 0.409393 214.5193 339.5876 5.9201 20250607 15.0 4.0 P/2013 G4 (PANSTARRS) MPC 84025 + PK13J020 2029 03 13.7527 2.143851 0.655853 37.8582 289.2900 15.5002 20250607 13.0 4.0 P/2013 J2 (McNaught) MPC 91613 + PK13N030 2034 04 9.7756 3.029650 0.590906 323.8815 17.5931 2.1671 20250607 13.0 4.0 P/2013 N3 (PANSTARRS) MPC 86229 + PK13N050 2031 04 2.4677 1.825797 0.731474 176.9595 187.1596 23.4123 20250607 17.0 4.0 P/2013 N5 (PANSTARRS) MPC 85834 + PK13P010 2013 02 15.6232 3.415962 0.602454 138.1273 160.7029 18.6870 20250607 12.0 4.0 P/2013 P1 (PANSTARRS) MPC 85834 + PK13R030 2024 03 20.8635 2.193182 0.277062 11.4970 341.8131 0.8653 20250607 14.0 4.0 P/2013 R3 (Catalina-PANSTARRS) MPEC 2022-V95 + PK13R03a 2024 03 20.4872 2.193199 0.276995 11.5747 341.7677 0.8644 20250607 9.0 4.0 P/2013 R3-A (Catalina-PANSTARRS) unp + PK13R03b 2024 03 20.8864 2.193234 0.277038 11.5103 341.8240 0.8656 20250607 9.0 4.0 P/2013 R3-B (Catalina-PANSTARRS) MPEC 2015-M77 + PK13T010 2027 10 12.9757 2.204063 0.623574 346.1733 10.0851 24.2694 20250607 16.5 4.0 P/2013 T1 (PANSTARRS) MPC 85835 + PK13T020 2026 06 11.3905 1.746153 0.500195 345.5649 0.8062 9.4468 20250607 16.0 4.0 P/2013 T2 (Schwartz) MPC 86643 + PK13W010 2027 03 15.9301 1.415444 0.593830 1.2454 117.8352 4.7000 20250607 17.5 4.0 P/2013 W1 (PANSTARRS) MPC 91613 + PK13Y46G 2023 01 18.8456 1.731822 0.469455 244.3077 47.0369 7.5578 20250607 10.0 4.0 P/2013 YG46 (Spacewatch) MPC101095 + PK14A020 2028 03 14.1665 2.092086 0.646684 356.2009 106.6562 24.5634 20250607 15.0 4.0 P/2014 A2 (Hill) MPC 89728 + PK14C010 2028 07 2.9813 2.646987 0.342335 188.2518 39.8494 3.2112 20250607 15.5 4.0 P/2014 C1 (TOTAS) MPEC 2024-F34 + CK14F030 2021 05 27.5683 5.731053 0.601747 5.1337 325.9777 6.5210 20250607 6.0 4.0 C/2014 F3 (Sheppard-Trujillo) MPEC 2022-WD2 + PK14L020 2030 05 26.3477 2.233338 0.646190 182.6910 149.3375 5.1905 20250607 12.0 4.0 P/2014 L2 (NEOWISE) MPC 98560 + PK14L030 2014 06 21.2414 1.873632 0.771059 178.6565 115.5303 6.2539 20250607 16.0 4.0 P/2014 L3 (Hill) MPC 90769 + PK14M040 2029 03 18.9566 2.368594 0.596002 148.1263 263.1999 3.3471 20250607 15.0 4.0 P/2014 M4 (PANSTARRS) MPC 91614 + PK14O030 2035 02 25.9971 4.685733 0.382432 204.6596 87.6245 7.7890 20250607 10.5 4.0 P/2014 O3 (PANSTARRS) MPC 98560 + CK14Od2G 2022 01 4.3116 9.984053 0.185391 255.3166 145.8258 9.0324 20250607 6.0 4.0 C/2014 OG392 (PANSTARRS) MPC182878 + PK14U040 2027 09 13.8687 1.883510 0.463730 347.8421 11.9266 6.4222 20250607 18.0 4.0 P/2014 U4 (PANSTARRS) MPC 91616 + CK14UR1N 2031 01 16.3616 10.960341 1.004214 326.0780 189.9605 95.4443 20250607 2.5 3.2 C/2014 UN271 (Bernardinelli-Bernstein) MPC184408 + PK14V010 2027 11 27.5749 2.557617 0.533410 177.6483 166.1812 22.4995 20250607 14.0 4.0 P/2014 V1 (PANSTARRS) MPC 95211 + PK14W040 2032 11 23.8926 4.243056 0.355118 67.7441 33.3049 15.2835 20250607 11.0 4.0 P/2014 W4 (PANSTARRS) MPC105542 + PK14X010 2030 06 14.9937 1.791810 0.710910 33.9522 61.5443 26.0486 20250607 15.0 4.0 P/2014 X1 (Elenin) MPC 94281 + PK15A030 2015 02 23.2702 1.165935 0.850837 249.6640 277.4863 172.5514 20250607 20.0 4.0 P/2015 A3 (PANSTARRS) MPC 92275 + PK15B010 2015 09 6.4760 5.997856 0.366905 188.6689 352.8499 18.0881 20250607 8.5 4.0 P/2015 B1 (PANSTARRS) MPC 99270 + PK15B040 2015 02 9.1014 3.719811 0.562610 227.0983 266.1369 1.7676 20250607 11.0 4.0 P/2015 B4 (Lemmon-PANSTARRS) MPC109141 + PK15C010 2032 02 2.6215 2.827617 0.568056 178.0452 348.7525 13.8943 20250607 12.5 4.0 P/2015 C1 (TOTAS-Gibbs) MPC101096 + PK15D050 2014 04 10.4649 4.544583 0.491895 39.6263 74.0873 20.5513 20250607 9.0 4.0 P/2015 D5 (Kowalski) MPC109141 + PK15D060 2034 07 1.5480 4.537333 0.362660 125.8972 45.3907 20.3017 20250607 10.5 4.0 P/2015 D6 (Lemmon-PANSTARRS) MPEC 2024-R10 + PK15K050 2032 11 2.8651 3.016874 0.551598 106.0976 134.3107 39.9256 20250607 13.5 4.0 P/2015 K5 (PANSTARRS) MPC 95213 + PK15M020 2015 08 31.0927 5.966040 0.177686 225.7394 86.6990 3.9678 20250607 8.5 4.0 P/2015 M2 (PANSTARRS) MPC107684 + PK15P040 2030 12 11.5230 2.509921 0.585033 280.7421 104.6759 8.7222 20250607 14.0 4.0 P/2015 P4 (PANSTARRS) MPC 99819 + PK15PM9D 2034 12 14.9145 4.864313 0.325090 352.6811 342.7489 2.0202 20250607 11.5 2.0 P/2015 PD229 (Cameron-ISON) MPEC 2022-K19 + PK15Q020 2015 09 13.2728 1.820502 0.752251 244.6449 228.5277 146.5501 20250607 15.5 4.0 P/2015 Q2 (Pimentel) MPC 96867 + PK15R010 2029 10 7.6452 2.160385 0.632891 300.5112 48.3912 22.6813 20250607 14.0 4.0 P/2015 R1 (PANSTARRS) MPC 98562 + PK15R020 2024 12 15.7150 2.454967 0.451987 149.8745 168.6021 15.4827 20250607 14.5 4.0 P/2015 R2 (PANSTARRS) MPC 95734 + PK15T19O 2025 11 23.5299 2.911400 0.359598 89.3407 321.6615 6.5055 20250607 14.0 4.0 P/2015 TO19 (Lemmon-PANSTARRS) MPC102953 + PK15TK0P 2016 11 3.4497 3.359965 0.537358 82.5966 6.9062 8.7784 20250607 11.0 4.0 P/2015 TP200 (LINEAR) MPC110080 + PK15W020 2015 10 8.5391 2.660623 0.635215 117.7154 294.0712 11.6206 20250607 13.0 4.0 P/2015 W2 (Catalina) MPC101098 + PK15X030 2026 10 23.6322 2.799444 0.439846 306.9750 77.2550 24.4222 20250607 15.0 4.0 P/2015 X3 (PANSTARRS) MPEC 2023-J29 + PK15X060 2025 05 11.3915 2.273712 0.174120 329.7154 106.9299 4.5658 20250607 16.0 4.0 P/2015 X6 (PANSTARRS) MPC115881 + PK16A030 2017 04 26.6068 4.822033 0.387088 340.8015 187.1299 8.5213 20250607 10.0 4.0 P/2016 A3 (PANSTARRS) MPEC 2022-OB6 + PK16A070 2027 05 27.8262 2.181421 0.569669 352.7835 220.6216 16.2782 20250607 16.0 4.0 P/2016 A7 (PANSTARRS) MPC102098 + PK16G010 2025 05 16.1423 2.041076 0.210032 111.0871 204.0104 10.9699 20250607 14.0 4.0 P/2016 G1 (PANSTARRS) MPEC 2021-P47 + CK16J020 2016 04 12.7304 1.496302 1.000364 318.2637 186.2734 130.3741 20250607 17.0 4.0 C/2016 J2 (Denneau) MPEC 2024-C04 + PK16P010 2027 03 5.9567 2.283277 0.287314 271.0395 319.0256 24.4452 20250607 15.0 4.0 P/2016 P1 (PANSTARRS) MPC102099 + PK16P050 2023 05 22.2692 4.430991 0.057299 33.8740 185.3765 7.0379 20250607 13.2 4.0 P/2016 P5 (COIAS) MPC184408 + CK16Q020 2021 05 11.6394 7.079919 1.002407 84.5284 322.3491 109.3264 20250607 6.0 4.0 C/2016 Q2 (PANSTARRS) MPEC 2024-H50 + PK16R040 2028 11 19.4852 2.803744 0.474735 174.0998 168.2668 10.8638 20250607 12.5 4.0 P/2016 R4 (Gibbs) MPEC 2022-K19 + PK16S010 2017 03 20.5657 2.380071 0.712074 273.1590 227.6434 94.7320 20250607 12.0 4.0 P/2016 S1 (PANSTARRS) MPC105543 + PK16W48M 2017 02 27.5582 1.764110 0.784169 36.1801 59.9454 117.6184 20250607 15.0 4.0 P/2016 WM48 (Lemmon) MPC106345 + CK16X010 2019 04 30.7500 7.560500 0.997211 224.6120 256.3011 26.4694 20250607 6.0 4.0 C/2016 X1 (Lemmon) MPEC 2021-P47 + CK17B030 2019 01 30.1130 3.933162 0.998824 284.7625 2.2458 54.2231 20250607 6.0 4.0 C/2017 B3 (LINEAR) MPEC 2022-OB6 + PK17B040 2017 01 5.8178 2.800894 0.364952 11.0197 121.4578 20.0584 14.5 4.0 P/2017 B4 (PANSTARRS) MPC103847 + PK17D010 2027 01 30.9520 2.710914 0.437817 8.0825 82.1923 20.7713 20250607 14.0 4.0 P/2017 D1 (Fuls) MPEC 2022-OB6 + PK17D040 2016 09 10.7516 2.785804 0.630626 212.1330 264.9132 10.5614 20250607 13.0 4.0 P/2017 D4 (PANSTARRS) MPEC 2022-OB6 + PK17F36L 2025 08 8.5709 2.830976 0.032725 90.1943 313.4516 15.6870 20250607 14.7 4.0 P/2017 FL36 (PANSTARRS) MPC184408 + PK17G010 2016 04 21.1123 2.511165 0.650855 225.2545 247.1370 5.1551 20250607 13.5 4.0 P/2017 G1 (PANSTARRS) MPEC 2024-C04 + PK17G020 2017 06 10.3877 2.821261 0.648903 105.2091 79.8960 47.9682 20250607 13.0 4.0 P/2017 G2 (PANSTARRS) MPC108595 + CK17K020 2022 12 18.5999 1.799832 0.999017 236.1748 88.2219 87.6439 20250607 1.5 4.0 C/2017 K2 (PANSTARRS) MPC184408 + PK17K030 2030 07 31.1385 2.351476 0.579118 253.2878 354.1866 4.2723 20250607 14.5 4.0 P/2017 K3 (Gasparovic) MPEC 2021-N06 + CK17K050 2020 03 25.5273 7.677590 1.002952 171.9401 102.4575 82.2791 20250607 5.0 4.0 C/2017 K5 (PANSTARRS) MPEC 2021-P47 + CK17M040 2019 01 17.6387 3.236150 1.000194 167.4132 66.0122 105.6271 20250607 6.0 4.0 C/2017 M4 (ATLAS) MPEC 2022-OB6 + PK17P010 2018 06 19.1403 5.473277 0.309012 122.7747 221.4693 7.6880 20250607 10.0 4.0 P/2017 P1 (PANSTARRS) MPC114599 + PK17S080 2027 05 4.5027 1.691831 0.391131 254.9201 191.5086 29.8401 20250607 16.0 4.0 P/2017 S8 (PANSTARRS) MPEC 2022-OB6 + CK17T020 2020 05 6.0385 1.603945 0.998995 92.7794 64.4369 57.2844 20250607 5.0 4.0 C/2017 T2 (PANSTARRS) MPEC 2024-A43 + PK17T13W 2018 06 23.7542 2.065164 0.710659 120.0174 322.1231 44.8832 20250607 15.0 2.0 P/2017 TW13 (Lemmon) MPC115882 + PK17U030 2030 03 15.7510 4.423528 0.100836 296.4524 165.0570 15.9222 20250607 11.0 4.0 P/2017 U3 (PANSTARRS) MPEC 2022-K19 + CK17U070 2019 09 16.2385 6.419353 1.002731 326.4189 276.3203 142.6394 20250607 8.3 2.0 C/2017 U7 (PANSTARRS) MPEC 2023-A50 + PK17W030 2018 02 26.6644 3.854171 0.507046 327.7722 210.0686 18.1881 20250607 10.5 4.0 P/2017 W3 (Gibbs) MPC114601 + CK17Y020 2020 11 4.9168 4.621500 1.001077 147.8089 66.0298 128.4479 20250607 15.0 4.0 C/2017 Y2 (PANSTARRS) MPEC 2024-DC6 + PK17Y030 2018 02 6.3762 1.276999 0.869622 67.3287 154.0206 27.6300 20250607 16.5 4.0 P/2017 Y3 (Leonard) MPC111770 + CK18A030 2019 01 8.6721 3.293329 0.990471 86.5118 194.3574 139.6082 20250607 8.5 4.0 C/2018 A3 (ATLAS) MPEC 2021-P47 + PK18A050 2031 01 31.2907 2.674393 0.524494 359.5535 87.7836 23.6241 20250607 15.0 4.0 P/2018 A5 (PANSTARRS) MPC109147 + CK18A060 2019 07 10.2877 3.016795 0.798837 264.2674 340.4579 77.1597 20250607 9.0 4.0 C/2018 A6 (Gibbs) MPEC 2024-JU4 + PK18C010 2031 07 31.0591 2.640219 0.532661 235.8064 270.1941 5.1014 20250607 13.5 4.0 P/2018 C1 (Lemmon-Read) MPC114601 + CK18D04O 2019 08 17.0981 2.421737 0.905123 176.4219 251.3950 160.4453 20250607 11.0 4.0 C/2018 DO4 (Lemmon) MPEC 2022-M88 + CK18F010 2018 12 10.1367 2.991277 0.986220 71.4247 177.3216 46.1741 20250607 11.5 4.0 C/2018 F1 (Grauer) MPEC 2021-R75 + CK18F040 2019 11 30.8722 3.448581 0.998027 263.1952 26.5384 78.1374 20250607 11.0 6.0 C/2018 F4 (PANSTARRS) MPEC 2023-A50 + CK18F04a 2019 11 30.8603 3.448449 0.997974 263.1919 26.5386 78.1376 20250607 11.0 6.0 C/2018 F4-A MPEC 2021-Y10 + CK18F04b 2019 11 30.7971 3.448266 0.998063 263.1777 26.5380 78.1386 20250607 11.0 6.0 C/2018 F4-B MPEC 2023-D41 + PK18H020 2027 03 18.2732 2.028743 0.539854 119.1890 67.9854 7.4169 20250607 16.6 2.0 P/2018 H2 (PANSTARRS) MPC114602 + CK18K03J 2019 09 8.7371 3.617435 0.994796 217.5340 91.6952 136.6205 20250607 12.2 2.0 C/2018 KJ3 (Lemmon) MPEC 2021-R75 + CK18L020 2018 11 29.5042 1.721614 0.992696 56.3444 242.9899 67.2171 20250607 10.0 4.0 C/2018 L2 (ATLAS) MPEC 2021-P47 + PK18L040 2029 07 28.5976 1.691044 0.658289 140.5037 145.2212 26.5944 20250607 17.5 4.0 P/2018 L4 (PANSTARRS) MPC114603 + CK18N020 2019 11 12.0841 3.135556 1.002015 25.3242 24.5271 77.4962 20250607 6.0 4.0 C/2018 N2 (ASASSN) MPEC 2022-YN2 + PK18P040 2018 11 6.9803 3.689153 0.449038 8.5163 353.1586 23.0782 20250607 12.0 4.0 P/2018 P4 (PANSTARRS) MPC114603 + CK18P050 2019 02 25.6615 4.603604 0.641580 132.0336 216.2708 7.2465 20250607 11.0 4.0 C/2018 P5 (PANSTARRS) MPEC 2021-P47 + CK18R030 2019 06 8.0040 1.284393 0.999284 112.8064 324.3614 69.6873 20250607 9.5 4.0 C/2018 R3 (Lemmon) MPC118841 + CK18R050 2019 01 10.7774 3.637852 0.841696 178.2719 171.2693 103.6829 20250607 11.5 4.0 C/2018 R5 (Lemmon) MPC114603 + CK18S020 2018 11 5.3549 5.491210 0.617860 290.9505 85.1076 64.1107 20250607 7.5 4.0 C/2018 S2 (TESS) MPEC 2022-QC6 + CK18U010 2021 11 2.1430 4.985979 1.000137 180.3529 75.5139 108.3258 20250607 5.0 4.0 C/2018 U1 (Lemmon) MPC184408 + CK18V010 2018 12 4.1309 0.390689 1.000461 89.5771 129.6073 144.2018 20250607 12.0 4.0 C/2018 V1 (Machholz-Fujikawa-Iwamoto) MPC114604 + CK18V020 2018 11 26.3883 2.492213 0.901297 319.2890 357.2235 159.1614 20250607 15.0 4.0 C/2018 V2 (ATLAS) MPC115884 + PK18V02N 2026 08 15.7390 2.119325 0.478155 138.9250 226.4381 18.2569 20250607 15.0 4.0 P/2018 VN2 (Leonard) MPEC 2025-A40 + AK18V030 2019 09 10.4700 1.329916 0.989547 3.5754 308.8207 164.9131 20250607 15.7 2.0 A/2018 V3 MPEC 2025-A40 + CK18V040 2019 03 2.3988 3.203854 0.985176 0.0990 78.2467 69.0427 20250607 12.5 4.0 C/2018 V4 (Africano) MPEC 2022-M21 + PK18V050 2018 10 6.1754 4.708263 0.475773 260.8902 171.2921 10.5775 20250607 12.5 4.0 P/2018 V5 (Trujillo-Sheppard) MPEC 2021-P47 + CK18W010 2019 05 13.9091 1.351473 0.937839 251.1664 233.6321 83.3960 20250607 15.5 2.0 C/2018 W1 (Catalina) MPEC 2021-P47 + CK18W020 2019 09 5.7173 1.465415 1.000942 158.2375 181.9813 116.5371 20250607 9.5 4.0 C/2018 W2 (Africano) MPEC 2021-P47 + AK18W030 2021 04 13.1623 4.281970 0.993893 313.8642 251.6879 104.8380 20250607 10.7 2.0 A/2018 W3 MPEC 2023-M14 + CK18X020 2019 07 9.8325 2.111030 0.985017 162.0079 340.6351 23.1075 20250607 12.0 4.0 C/2018 X2 (Fitzsimmons) MPC119996 + CK18X030 2019 01 1.6370 2.694627 0.782903 359.8669 78.7968 43.4258 20250607 14.5 4.0 C/2018 X3 (PANSTARRS) MPC114604 + CK18Y010 2019 02 3.3789 1.293307 0.989765 357.8669 147.3364 160.4824 20250607 11.5 4.0 C/2018 Y1 (Iwamoto) MPEC 2024-A43 + PK18Y020 2019 01 4.6154 3.877713 0.480016 162.3886 297.1170 11.6953 20250607 11.5 4.0 P/2018 Y2 (Africano) MPC114605 + PK19A010 2030 05 6.9099 2.196809 0.570301 150.7861 312.2107 13.7719 20250607 16.0 4.0 P/2019 A1 (PANSTARRS) MPC114605 + PK19A020 2018 11 24.2564 3.521740 0.383282 323.9571 139.3670 14.8735 20250607 10.5 4.0 P/2019 A2 (ATLAS) MPEC 2021-P47 + PK19A030 2024 03 2.7533 2.304560 0.267513 325.6567 31.2701 15.3555 20250607 16.0 4.0 P/2019 A3 (PANSTARRS) MPEC 2022-M21 + PK19A040 2027 05 26.8446 2.385964 0.087418 343.2376 119.3537 13.3058 20250607 15.0 4.0 P/2019 A4 (PANSTARRS) MPEC 2022-L66 + CK19A050 2019 06 7.0260 6.312613 0.706451 355.8263 146.5139 67.5511 20250607 9.5 4.0 C/2019 A5 (PANSTARRS) MPEC 2021-P47 + PK19A060 2031 01 25.5628 1.926517 0.640361 156.2505 280.1736 33.2982 20250607 16.0 4.0 P/2019 A6 (Lemmon-PANSTARRS) MPC114605 + CK19A090 2019 07 27.2174 1.426565 0.963709 237.8789 278.4704 84.3987 20250607 15.0 4.0 C/2019 A9 (PANSTARRS) MPC118842 + CK19B010 2019 03 18.2587 1.603638 0.988521 174.8265 290.2340 123.4919 20250607 16.0 4.0 C/2019 B1 (Africano) MPEC 2022-L66 + PK19B020 2027 02 24.3398 2.523184 0.357708 0.5964 175.6527 16.9514 20250607 14.5 4.0 P/2019 B2 (Groeller) MPC115885 + CK19B030 2021 01 19.5922 6.829860 0.998140 263.9977 358.4023 66.6036 20250607 5.5 4.0 C/2019 B3 (PANSTARRS) MPEC 2024-JU4 + CK19C010 2020 05 4.5580 6.567327 0.990459 319.0168 212.3696 36.0382 20250607 10.0 4.0 C/2019 C1 (ATLAS) MPEC 2021-P47 + CK19D010 2019 05 8.8149 1.592131 0.988339 70.7163 231.6664 34.0111 20250607 13.0 4.0 C/2019 D1 (Flewelling) MPEC 2022-O08 + CK19E030 2023 11 15.6281 10.313267 0.998094 280.7189 347.1958 84.3147 20250607 2.5 4.0 C/2019 E3 (ATLAS) MPC182878 + CK19F010 2021 06 21.1716 3.608383 1.000313 251.3041 38.6641 54.2523 20250607 5.5 4.0 C/2019 F1 (ATLAS-Africano) MPEC 2024-GJ3 + CK19F020 2019 09 7.7544 2.239065 0.864765 11.6106 175.3470 19.3344 20250607 12.0 4.0 C/2019 F2 (ATLAS) MPEC 2025-A40 + CK19G020 2019 12 6.4882 2.305763 0.994256 82.7815 208.2360 159.2528 20250607 15.0 4.0 C/2019 G2 (PANSTARRS) MPEC 2024-E01 + AK19G030 2018 12 3.6909 2.836511 0.834271 161.7303 49.8933 156.8086 20250607 17.1 2.0 A/2019 G3 MPEC 2022-VC5 + PK19G21G 2019 05 9.6453 3.946111 0.471650 208.5911 340.5655 6.0831 20250607 12.0 4.0 P/2019 GG21 (PANSTARRS) MPC114607 + CK19H010 2019 04 26.8796 1.839938 0.991933 19.2422 269.3120 104.3575 20250607 15.5 4.0 C/2019 H1 (NEOWISE) MPEC 2022-M21 + CK19J010 2019 04 5.9084 2.481788 0.962673 167.5701 98.2355 24.5224 20250607 12.0 4.0 C/2019 J1 (Lemmon) MPEC 2023-A50 + CK19J020 2019 07 21.1460 1.714287 0.989295 98.5503 25.4646 105.2137 20250607 13.0 4.0 C/2019 J2 (Palomar) MPEC 2021-R75 + CK19J030 2019 08 1.9360 2.361675 0.999899 16.4923 270.6554 131.2940 20250607 13.5 4.0 C/2019 J3 (ATLAS) MPC117071 + CK19J06U 2019 06 2.8910 2.031730 0.999865 94.7738 21.6881 148.2998 20250607 14.5 4.0 C/2019 JU6 (ATLAS) MPEC 2022-M21 + CK19K010 2020 02 10.9125 2.021314 0.999316 265.7810 73.3114 87.0181 20250607 10.0 4.0 C/2019 K1 (ATLAS) MPEC 2022-O08 + CK19K040 2019 06 15.2946 2.275831 0.998603 140.0207 180.2964 105.2880 20250607 12.5 4.0 C/2019 K4 (Ye) MPC119997 + CK19K050 2019 06 21.3378 2.054940 0.987793 175.1427 177.2762 15.2926 20250607 13.0 4.0 C/2019 K5 (Young) MPEC 2021-P47 + CK19K060 2020 05 18.5745 3.917397 0.995796 187.4327 42.9796 132.3893 20250607 11.5 4.0 C/2019 K6 (PANSTARRS) MPEC 2021-P47 + CK19K070 2020 06 17.1324 4.474306 1.000350 27.3577 308.0355 103.4781 20250607 6.0 4.0 C/2019 K7 (Smith) MPEC 2024-GJ3 + CK19K080 2019 07 20.1988 3.198434 0.998094 85.3722 290.9898 93.0493 20250607 11.5 4.0 C/2019 K8 (ATLAS) MPEC 2021-R75 + CK19L010 2019 08 7.1551 2.905220 0.704097 50.0115 254.4272 9.9738 20250607 13.5 4.0 C/2019 L1 (PANSTARRS) MPEC 2023-A50 + CK19L020 2019 04 3.8262 1.621031 0.935537 18.8489 12.5816 152.1494 20250607 16.0 4.0 C/2019 L2 (NEOWISE) MPC115886 + PK19L02D 2020 01 30.8495 4.491880 0.131061 116.4901 178.7603 11.6100 20250607 8.5 4.0 P/2019 LD2 (ATLAS) MPEC 2024-GJ3 + CK19L030 2022 01 10.1130 3.558530 1.003131 171.7472 290.7181 48.3457 20250607 4.5 4.0 C/2019 L3 (ATLAS) MPC184408 + PK19L04M 2019 06 19.9686 2.360036 0.586138 68.2081 72.8893 36.4164 20250607 9.5 4.0 P/2019 LM4 (Palomar) MPEC 2024-YC7 + CK19L07B 2019 03 27.5408 2.494982 0.928766 336.7737 4.0006 164.2792 20250607 17.0 4.0 C/2019 LB7 (Kleyna) MPC118095 + CK19M030 2018 12 31.4276 2.424744 0.999514 87.9348 155.0477 99.6477 20250607 12.2 4.0 C/2019 M3 (ATLAS) MPC118095 + CK19M040 2019 09 9.6901 9.191044 1.000464 260.3428 52.6427 65.6901 20250607 5.0 4.0 C/2019 M4 (TESS) MPEC 2023-JA2 + CK19N010 2020 11 30.5348 1.703133 0.998252 193.3450 13.5150 82.5267 20250607 7.5 4.0 C/2019 N1 (ATLAS) MPEC 2023-C45 + AK19N020 2019 08 22.4476 1.940413 0.998304 347.0719 276.2229 89.3219 20250607 12.5 2.0 A/2019 N2 MPEC 2023-CD8 + CK19N03J 2020 10 22.2849 4.362925 1.001466 246.8732 142.4921 99.3378 20250607 9.0 4.0 C/2019 NJ3 (Lemmon) MPEC 2022-A21 + CK19O020 2023 04 6.0927 9.681030 0.835173 129.5768 48.2626 93.3005 20250607 5.0 4.0 C/2019 O2 (PANSTARRS) MPC184408 + CK19O030 2021 03 8.4843 8.820771 1.002797 60.1021 300.4753 89.7968 20250607 3.5 4.0 C/2019 O3 (Palomar) MPC182878 + AK19O040 2020 02 11.1386 3.642513 0.890395 61.8267 354.9267 115.0075 20250607 15.5 2.0 A/2019 O4 MPEC 2021-P47 + CK19Q010 2020 07 22.1516 5.002964 1.002371 56.2554 42.4664 155.7220 20250607 8.5 4.0 C/2019 Q1 (Lemmon) MPEC 2024-EF7 + AK19Q020 2019 07 23.6013 1.261031 0.978545 176.5074 188.1204 158.9738 20250607 18.0 2.0 A/2019 Q2 MPC117072 + PK19S020 2029 06 21.4470 3.775654 0.204677 216.9392 93.1805 10.4637 20250607 13.5 4.0 P/2019 S2 (PANSTARRS) MPC117072 + PK19S030 2025 12 19.1649 1.807089 0.470760 213.0946 150.1411 8.6940 20250607 18.3 4.0 P/2019 S3 (PANSTARRS) MPEC 2022-CN4 + CK19S040 2020 04 9.3386 3.439256 0.986161 71.3710 63.1561 92.0969 20250607 11.0 4.0 C/2019 S4 (Lemmon) MPEC 2021-S45 + AK19T010 2021 01 14.9521 4.274970 0.889713 90.9858 6.9309 120.8229 20250607 13.0 2.0 A/2019 T1 MPEC 2023-N01 + CK19T020 2021 04 22.5340 2.643422 0.999247 239.3889 155.6549 111.3753 20250607 9.0 4.0 C/2019 T2 (Lemmon) MPEC 2023-R20 + CK19T030 2021 03 4.6965 5.953506 0.998677 112.4875 139.5427 121.8729 20250607 6.8 4.0 C/2019 T3 (ATLAS) MPEC 2023-UR6 + CK19T040 2022 06 8.6611 4.237680 0.995185 351.1092 199.9039 53.6247 20250607 5.0 4.0 C/2019 T4 (ATLAS) MPC182878 + PK19T050 2019 08 3.4061 1.523141 0.809784 189.6222 247.6125 33.4937 20250607 15.0 4.0 P/2019 T5 (ATLAS) MPEC 2021-P47 + PK19T060 2019 11 8.9102 2.054685 0.622490 329.0578 71.2472 18.6988 20250607 15.5 4.0 P/2019 T6 (PANSTARRS) MPEC 2021-P47 + PK19U040 2026 04 28.5197 1.844757 0.475757 181.0805 200.0024 11.6954 20250607 19.0 4.0 P/2019 U4 (PANSTARRS) MPC118096 + CK19U050 2023 03 29.4647 3.624215 1.000219 181.4509 2.6141 113.5124 20250607 4.5 4.0 C/2019 U5 (PANSTARRS) MPC184408 + CK19U060 2020 06 18.3121 0.906750 0.997020 329.4329 235.7536 60.9844 20250607 10.0 4.0 C/2019 U6 (Lemmon) MPEC 2022-H04 + CK19V010 2020 07 17.5265 3.092879 0.998798 51.1918 83.1481 61.9482 20250607 11.0 4.0 C/2019 V1 (Borisov) MPEC 2022-N37 + PK19V020 2020 10 17.1943 5.007689 0.331847 335.6322 189.1399 11.8069 20250607 10.0 4.0 P/2019 V2 (Groeller) MPEC 2022-L66 + PK19W010 2029 01 22.2549 3.333179 0.267202 18.8852 35.3627 23.4670 20250607 12.9 4.0 P/2019 W1 (PANSTARRS) MPEC 2023-A50 + PK19X010 2019 07 24.6454 4.301760 0.303843 36.9831 43.6774 10.2460 20250607 10.4 4.0 P/2019 X1 (Pruyne) MPEC 2021-P47 + PK19X020 2026 11 15.2893 1.815397 0.500464 213.5123 250.8318 15.8947 20250607 18.0 4.0 P/2019 X2 (Pan-STARRS) MPEC 2020-C98 + CK19Y010 2020 03 17.1646 0.826439 0.990624 57.9144 31.4813 73.2852 20250607 13.7 4.0 C/2019 Y1 (ATLAS) MPC119999 + CK19Y040 2020 05 29.7096 0.257205 0.999224 177.4116 120.7883 44.9416 20250607 11.8 6.0 C/2019 Y4 (ATLAS) MPEC 2024-A43 + CK19Y04a 2020 05 29.7621 0.255360 1.001366 177.2438 121.1559 45.3766 20250607 11.6 6.0 C/2019 Y4-A (ATLAS) MPEC 2020-L06 + CK19Y04b 2020 05 29.7179 0.256893 0.999813 177.3707 120.8515 45.0231 20250607 12.1 6.0 C/2019 Y4-B (ATLAS) MPEC 2025-CE3 + CK19Y04c 2020 05 29.7157 0.256432 1.002095 177.2766 120.8832 45.1603 20250607 12.7 6.0 C/2019 Y4-C (ATLAS) MPEC 2020-L06 + CK19Y04d 2020 05 29.8045 0.255753 0.996202 177.4194 121.2451 45.2131 20250607 12.5 6.0 C/2019 Y4-D (ATLAS) MPEC 2020-L06 + CK19Y050 2019 08 16.6201 4.933453 0.992834 303.6621 51.7653 82.7732 20250607 11.0 4.0 C/2019 Y5 (PANSTARRS) MPEC 2023-A50 + AK20A010 2019 11 30.2879 1.671333 0.934371 302.4018 119.0673 149.0316 20250607 18.0 2.0 A/2020 A1 MPEC 2023-A50 + CK20A020 2020 01 7.1876 0.975117 0.998998 68.0146 286.1913 120.5076 20250607 13.5 4.0 C/2020 A2 (Iwamoto) MPEC 2022-YN2 + CK20A030 2019 06 26.9725 5.753209 0.998928 268.2389 120.7989 146.6221 20250607 8.0 4.0 C/2020 A3 (ATLAS) MPEC 2023-A50 + PK20A040 2019 11 24.4237 2.834211 0.654471 144.8988 312.2840 25.0022 20250607 15.0 4.0 P/2020 A4 (PANSTARRS-Lemmon) MPEC 2022-P91 + AK20B010 2019 12 27.6151 1.739119 0.966596 154.8721 309.8077 18.5397 20250607 21.0 2.0 A/2020 B1 MPEC 2020-N08 + CK20B020 2020 01 27.2646 2.756092 0.959396 143.6251 354.1828 55.7547 20250607 10.0 4.0 C/2020 B2 (Lemmon) MPEC 2020-HN5 + CK20B030 2019 10 20.7192 3.327567 0.996811 324.9263 185.7510 20.7068 20250607 13.0 4.0 C/2020 B3 (Rankin) MPEC 2022-N37 + PK20B040 2021 11 19.2169 6.435416 0.192857 342.0445 185.9505 11.6032 20250607 10.5 4.0 P/2020 B4 (Sheppard) MPEC 2023-KD6 + CK20F020 2022 07 12.5842 8.813556 1.002706 48.2395 250.3012 163.5896 20250607 4.5 4.0 C/2020 F2 (ATLAS) MPC184409 + CK20F030 2020 07 4.8900 0.293591 0.999268 37.3522 61.0792 129.1187 20250607 7.5 5.2 C/2020 F3 (NEOWISE) MPEC 2021-O56 + CK20F050 2021 03 16.2291 4.326248 0.973705 310.6213 350.5390 52.2309 20250607 6.5 3.2 C/2020 F5 (MASTER) MPEC 2024-UQ8 + CK20F060 2020 04 10.4152 3.498242 0.989826 344.3409 207.8439 174.5841 20250607 14.5 2.8 C/2020 F6 (PANSTARRS) MPEC 2020-L06 + CK20F070 2021 11 13.8481 5.334768 0.990629 227.9809 321.8236 93.9809 20250607 7.0 4.0 C/2020 F7 (Lemmon) MPEC 2024-A43 + CK20F080 2020 05 25.8895 0.432547 1.000069 68.1080 259.8021 110.5559 20250607 10.0 4.0 C/2020 F8 (SWAN) MPEC 2023-J29 + PK20G010 2027 01 24.2683 0.501998 0.860811 207.6459 240.0998 18.5075 20250607 17.0 4.0 P/2020 G1 (Pimentel) MPEC 2020-L06 + CK20H020 2020 04 26.9455 0.828532 0.995332 26.5869 277.6716 124.7810 20250607 14.0 3.2 C/2020 H2 (Pruyne) MPEC 2022-YB4 + CK20H030 2020 06 5.7161 2.300288 1.000000 30.4456 270.6227 62.5292 13.5 4.0 C/2020 H3 (Wierzchos) MPEC 2020-HM1 + CK20H040 2020 08 29.2557 0.927286 0.980619 117.5733 307.4623 84.4946 20250607 15.0 3.2 C/2020 H4 (Leonard) MPEC 2020-L06 + CK20H050 2020 12 9.9597 9.335266 0.998411 326.2665 210.6156 70.2305 20250607 5.0 4.0 C/2020 H5 (Robinson) MPC184409 + CK20H060 2021 09 29.6102 4.697042 0.997678 20.1959 213.6939 79.9878 20250607 8.0 3.2 C/2020 H6 (ATLAS) MPEC 2024-JU4 + CK20H070 2020 06 2.9509 4.419545 0.996854 82.6780 323.5194 135.9235 11.0 4.0 C/2020 H7 (Lemmon) MPEC 2020-KB7 + CK20H080 2020 06 4.7787 4.663848 0.992112 128.8241 68.4393 99.7033 20250607 10.5 4.0 C/2020 H8 (PANSTARRS) MPEC 2021-N06 + AK20H090 2019 12 21.8026 2.562294 0.992524 312.6276 213.1236 137.8740 20250607 18.0 2.0 A/2020 H9 MPEC 2022-ED3 + CK20H110 2020 09 12.6500 7.621066 0.999846 91.3687 303.0568 151.3741 20250607 8.5 4.0 C/2020 H11 (PANSTARRS-Lemmon) MPEC 2023-HN7 + CK20J010 2021 04 18.0746 3.345343 0.999707 341.5855 226.5878 142.3071 20250607 8.5 3.2 C/2020 J1 (SONEAR) MPEC 2023-KD6 + CK20K010 2023 05 8.7823 3.073945 0.998791 213.9710 94.3662 89.6715 20250607 5.5 4.0 C/2020 K1 (PANSTARRS) MPC184409 + CK20K020 2020 08 4.5239 8.880282 1.001071 67.3121 288.4330 90.9896 20250607 10.8 4.0 C/2020 K2 (PANSTARRS) MPEC 2021-N06 + CK20K030 2020 06 1.0031 1.583069 1.000000 64.4924 28.3546 129.0152 14.5 4.0 C/2020 K3 (Leonard) MPEC 2020-KF9 + CK20K040 2020 03 4.9542 1.744399 0.927098 308.7891 264.2742 125.5850 20250607 16.5 4.0 C/2020 K4 (PANSTARRS) MPEC 2020-L06 + CK20K050 2021 06 4.3091 1.540542 1.000824 249.6409 86.1419 67.0689 20250607 11.0 4.0 C/2020 K5 (PANSTARRS) MPEC 2021-R75 + CK20K060 2021 09 14.7971 5.866220 1.002202 44.2810 291.5985 103.6312 20250607 8.0 4.0 C/2020 K6 (Rankin) MPEC 2023-N01 + CK20K070 2019 10 25.3870 6.388756 0.932568 358.0878 286.1313 32.0444 20250607 8.0 4.0 C/2020 K7 (PANSTARRS) MPEC 2023-A50 + CK20K080 2020 09 15.6813 0.471455 1.000315 260.1502 181.3120 31.3845 20250607 15.0 3.2 C/2020 K8 (Catalina-ATLAS) MPEC 2021-P47 + PK20K090 2029 09 29.3024 2.860221 0.320166 197.0913 166.3114 23.1909 20250607 12.5 4.0 P/2020 K9 (Lemmon-PANSTARRS) MPEC 2021-BE3 + PK20M010 2019 12 23.2357 2.796900 0.473479 72.4980 142.6142 8.5345 20250607 14.5 4.0 P/2020 M1 (PANSTARRS) MPEC 2023-C45 + CK20M030 2020 10 25.7689 1.274863 0.953304 328.6658 71.1752 23.4705 20250607 14.5 4.0 C/2020 M3 (ATLAS) MPEC 2022-H30 + AK20M040 2020 11 22.8486 5.941110 0.999816 104.4856 348.6151 160.1033 20250607 14.5 2.0 A/2020 M4 MPEC 2023-N01 + PK20M04K 2027 04 18.3303 6.130381 0.015009 93.5441 0.6661 6.7816 20250607 8.0 4.0 P/2020 MK4 (PANSTARRS) MPEC 2024-NE4 + CK20M050 2021 08 19.7621 2.999886 1.000129 126.2459 352.0226 93.1751 20250607 9.0 4.0 C/2020 M5 (ATLAS) MPEC 2023-FK0 + CK20N010 2021 03 13.1169 1.317532 1.000850 186.8327 279.8579 29.7650 20250607 12.5 4.0 C/2020 N1 (PANSTARRS) MPEC 2022-GA9 + CK20N020 2020 08 24.3176 1.784198 0.982413 331.2079 257.1800 161.0386 20250607 16.0 3.2 C/2020 N2 (ATLAS) MPEC 2021-P47 + CK20O020 2021 08 27.3240 4.856870 0.999663 10.1789 256.7916 71.7622 20250607 8.0 3.2 C/2020 O2 (Amaral) MPEC 2024-JU4 + PK20O030 2021 01 25.1742 4.170403 0.102411 81.2177 266.8184 8.4445 20250607 12.0 4.0 P/2020 O3 (PANSTARRS) MPEC 2023-C45 + CK20P010 2020 10 21.1886 0.341720 1.000434 8.9310 53.4868 45.1169 20250607 14.0 3.2 C/2020 P1 (NEOWISE) MPEC 2021-BE3 + CK20P030 2021 04 22.8871 6.815891 1.003658 82.3472 19.4835 61.8572 20250607 6.0 4.0 C/2020 P3 (ATLAS) MPEC 2024-JU4 + CK20P06V 2021 09 25.8366 2.291157 0.945027 71.2847 329.1296 128.1565 20250607 10.0 4.0 C/2020 PV6 (PANSTARRS) MPEC 2022-PB4 + CK20Q010 2020 08 15.2711 1.319407 0.978829 10.0270 52.4106 142.9250 20250607 14.0 4.0 C/2020 Q1 (Borisov) MPEC 2022-L66 + CK20Q020 2020 01 24.9635 5.419456 0.488881 118.2130 179.8263 3.3357 20250607 12.0 3.2 C/2020 Q2 (PANSTARRS) MPEC 2023-CD7 + CK20R020 2022 02 25.3601 4.699062 0.989085 211.8826 195.1252 53.2165 20250607 9.0 4.0 C/2020 R2 (PANSTARRS) MPEC 2024-F34 + CK20R040 2021 03 2.2325 1.020830 0.989514 46.5186 323.2349 164.4053 20250607 13.5 4.0 C/2020 R4 (ATLAS) MPEC 2022-K19 + PK20R050 2020 05 27.5669 3.429509 0.313162 82.7558 272.9389 11.4395 20250607 9.5 6.0 P/2020 R5 (PANSTARRS) MPEC 2023-C45 + CK20R060 2019 09 6.8647 3.139364 0.989227 271.9984 12.2325 82.8877 20250607 11.0 4.0 C/2020 R6 (Rankin) MPEC 2021-Y10 + CK20R070 2022 09 16.0471 2.952033 0.999679 347.7650 268.3095 114.9031 20250607 7.0 3.2 C/2020 R7 (ATLAS) MPEC 2024-PC5 + PK20S010 2021 01 16.9719 2.959494 0.506899 255.1596 129.4919 13.7151 20250607 14.0 4.0 P/2020 S1 (PANSTARRS) MPEC 2021-BE3 + CK20S020 2020 12 22.0656 1.763558 0.827952 202.4217 197.7088 22.3764 20250607 17.0 4.0 C/2020 S2 (PANSTARRS) MPEC 2022-ST7 + CK20S030 2020 12 11.3810 0.392767 0.997224 350.0482 222.5234 20.0630 20250607 13.5 3.2 C/2020 S3 (Erasmus) MPEC 2024-JU4 + CK20S040 2023 02 9.5609 3.370380 1.002706 21.0567 117.6836 20.5699 20250607 8.5 3.2 C/2020 S4 (PANSTARRS) MPEC 2024-N80 + PK20S050 2028 10 11.2856 2.689218 0.337365 53.2759 316.0220 12.3403 20250607 14.5 4.0 P/2020 S5 (PANSTARRS) MPEC 2021-BE3 + PK20S070 2020 11 17.6246 2.973947 0.409541 40.6622 328.0835 16.0706 20250607 14.5 4.0 P/2020 S7 (PANSTARRS) MPEC 2021-BE3 + CK20S080 2021 04 10.3819 2.355765 0.990170 160.1328 24.0117 108.5424 20250607 12.5 4.0 C/2020 S8 (Lemmon) MPEC 2021-P47 + CK20T020 2021 07 10.5659 2.052772 0.992398 150.3491 83.0362 27.8394 20250607 11.0 3.2 C/2020 T2 (Palomar) MPEC 2022-TD3 + PK20T030 2027 08 27.4402 1.433037 0.592438 357.0787 73.9920 7.2986 20250607 18.0 3.2 P/2020 T3 (PANSTARRS) MPEC 2021-N06 + CK20T040 2021 07 6.0639 2.187751 1.000638 79.5710 50.6081 83.8300 20250607 13.0 3.2 C/2020 T4 (PANSTARRS) MPEC 2021-N06 + CK20T050 2020 10 7.7922 1.897722 0.996890 90.3835 237.8420 66.5562 20250607 16.0 4.0 C/2020 T5 (Lemmon) MPEC 2021-BE3 + PK20U020 2028 05 1.4483 1.846095 0.511341 84.7672 342.8188 6.4197 20250607 18.0 4.0 P/2020 U2 (PANSTARRS) MPEC 2021-N06 + CK20U030 2021 02 6.0276 2.285339 0.966218 124.5097 282.6018 30.1389 20250607 15.0 4.0 C/2020 U3 (Rankin) MPEC 2021-W31 + CK20U040 2022 04 9.9863 5.361749 1.001188 70.1722 120.4058 167.0033 20250607 7.0 4.0 C/2020 U4 (PANSTARRS) MPEC 2024-TD8 + CK20U050 2022 04 28.3593 3.756862 0.999633 75.4656 107.3132 97.3110 20250607 8.0 4.0 C/2020 U5 (PANSTARRS) MPEC 2024-GJ3 + CK20V020 2023 05 8.5206 2.229212 1.001042 162.4545 212.3975 131.6124 20250607 4.9 4.0 C/2020 V2 (ZTF) MPC184409 + PK20V030 2021 02 15.5037 6.239314 0.257887 249.7916 198.2685 23.0217 20250607 8.3 4.0 P/2020 V3 (PANSTARRS) MPEC 2023-D72 + PK20V040 2021 07 20.6315 5.153716 0.451584 257.2447 203.4888 14.2373 20250607 9.0 4.0 P/2020 V4 (Rankin) MPEC 2024-F34 + PK20W010 2020 04 10.4063 5.307350 0.265509 265.3900 124.3865 10.7773 20250607 10.0 4.0 P/2020 W1 (Rankin) MPEC 2021-BE3 + CK20W050 2020 11 30.9038 3.370670 1.002128 24.6030 75.4670 88.6158 20250607 15.0 4.0 C/2020 W5 (Lemmon) MPEC 2021-BE3 + PK20W05J 2021 06 30.5050 4.980199 0.172110 338.0844 177.7654 22.2881 20250607 8.5 4.0 P/2020 WJ5 (Lemmon) MPEC 2024-PC5 + PK20X010 2030 03 18.7650 2.882991 0.364433 323.5275 55.9872 31.6920 20250607 13.0 4.0 P/2020 X1 (ATLAS) MPEC 2024-F34 + CK20X020 2020 11 17.1666 3.832050 0.768311 347.5642 105.3570 18.1865 20250607 10.6 4.0 C/2020 X2 (ATLAS) MPEC 2024-A43 + CK20X040 2020 11 15.4578 5.224125 0.871305 140.2938 161.9526 80.6570 20250607 9.0 4.0 C/2020 X4 (Leonard) MPEC 2021-S45 + CK20Y020 2022 06 17.7974 3.146147 0.997554 266.4142 26.5385 101.2102 20250607 6.5 4.0 C/2020 Y2 (ATLAS) MPEC 2024-YC7 + CK20Y030 2020 12 3.2291 1.990414 0.985532 341.8517 191.3492 83.1414 20250607 13.5 4.0 C/2020 Y3 (ATLAS) MPEC 2021-R75 + CK21A010 2022 01 3.7850 0.615434 1.000239 225.1377 255.9115 132.7545 20250607 8.5 4.0 C/2021 A1 (Leonard) MPEC 2025-A40 + CK21A020 2021 01 21.8903 1.416044 0.993824 338.7973 125.0653 107.0525 20250607 13.5 4.0 C/2021 A2 (NEOWISE) MPEC 2025-A40 + CK21A040 2021 03 19.5685 1.150267 0.972946 204.7523 307.0900 111.6437 20250607 16.0 4.0 C/2021 A4 (NEOWISE) MPEC 2022-ED3 + PK21A050 2026 03 11.2539 2.620536 0.139804 61.5301 328.8096 18.1893 20250607 15.0 4.0 P/2021 A5 (PANSTARRS) MPEC 2021-BE3 + CK21A060 2021 05 3.0564 7.924680 0.999336 351.6242 164.0269 75.5646 20250607 7.0 4.0 C/2021 A6 (PANSTARRS) MPEC 2024-P23 + CK21A070 2021 07 15.1561 1.965149 0.998954 355.9994 154.4051 78.2156 20250607 10.0 4.0 C/2021 A7 (NEOWISE) MPEC 2022-M88 + CK21A090 2023 12 3.9478 7.763607 1.000154 211.6327 314.8532 158.0180 20250607 6.0 4.0 C/2021 A9 (PANSTARRS) MPC182879 + CK21A100 2021 03 14.7256 1.266610 0.985875 82.6383 188.8361 151.9933 20250607 19.0 4.0 C/2021 A10 (NEOWISE) MPEC 2021-N06 + CK21B020 2021 05 4.8409 2.514785 0.993828 335.1139 120.4407 38.0867 20250607 14.0 4.0 C/2021 B2 (PANSTARRS) MPEC 2022-L66 + CK21B030 2021 03 9.3261 2.168021 0.936650 293.6002 67.2814 119.4773 20250607 13.5 4.0 C/2021 B3 (NEOWISE) MPEC 2021-N06 + CK21C010 2020 12 5.7748 3.472916 0.998138 336.0629 186.8297 143.0429 20250607 11.5 4.0 C/2021 C1 (Rankin) MPEC 2023-KD6 + PK21C020 2021 02 24.5824 4.883788 0.488355 78.7211 66.4555 21.9385 20250607 12.0 4.0 P/2021 C2 (PANSTARRS) MPEC 2021-U31 + CK21C030 2021 02 11.1312 2.274046 0.962378 356.9768 181.8551 122.2061 20250607 14.0 4.0 C/2021 C3 (Catalina) MPEC 2024-M41 + CK21C040 2021 01 16.2019 4.493582 0.998850 320.0296 194.2305 132.8322 20250607 9.0 4.0 C/2021 C4 (ATLAS) MPEC 2022-M88 + CK21C050 2023 02 10.9796 3.240446 0.998104 270.8909 323.6735 50.8026 20250607 9.0 4.0 C/2021 C5 (PANSTARRS) MPEC 2024-N80 + CK21C060 2021 11 11.9242 3.284186 0.998783 203.8555 332.3268 164.6090 20250607 12.0 4.0 C/2021 C6 (Lemmon) MPEC 2022-YB4 + CK21D010 2021 02 27.3662 0.907968 0.991101 72.4544 311.1656 31.3577 20250607 13.0 4.0 C/2021 D1 (SWAN) MPEC 2022-F14 + CK21D020 2022 02 3.6634 2.949390 1.001436 125.0656 305.6295 83.7726 20250607 9.0 4.0 C/2021 D2 (ZTF) MPEC 2023-J29 + AK21E020 2020 12 8.9898 2.282957 0.988626 342.2234 190.7533 167.4935 20250607 15.0 2.0 A/2021 E2 MPEC 2022-UY9 + CK21E030 2022 06 11.1741 1.777480 0.999881 228.8021 104.4839 112.5254 20250607 8.5 4.0 C/2021 E3 (ZTF) MPEC 2024-GJ3 + AK21E040 2022 04 24.8335 4.679671 0.990725 48.2813 171.1423 116.3804 20250607 13.5 2.0 A/2021 E4 MPEC 2024-N80 + CK21F010 2022 04 6.7370 0.999184 0.995975 146.9431 203.5451 107.2924 20250607 13.5 4.0 C/2021 F1 (Lemmon-PANSTARRS) MPEC 2022-QD9 + CK21G010 2021 07 20.3922 3.427670 0.951791 107.4342 270.6978 131.5470 20250607 14.0 4.0 C/2021 G1 (Leonard) MPEC 2021-J72 + CK21G020 2024 09 9.1381 4.982300 1.000710 343.2670 221.0948 48.4673 20250607 5.5 4.0 C/2021 G2 (ATLAS) MPC184409 + CK21G030 2021 10 17.8526 5.182408 0.999409 10.5966 147.3473 102.8725 20250607 10.5 4.0 C/2021 G3 (PANSTARRS) MPEC 2022-X67 + PK21H00S 2021 08 4.8271 0.799110 0.809438 46.1195 262.3586 12.1545 20250607 22.0 4.0 P/2021 HS (PANSTARRS) MPEC 2021-Y10 + CK21J010 2021 02 19.4231 1.734109 0.933816 147.2016 88.4319 92.7078 20250607 15.5 4.0 C/2021 J1 (Maury-Attard) MPEC 2022-C56 + CK21J020 2021 09 20.8236 4.701472 0.958003 171.8860 23.3100 156.2116 20250607 12.0 4.0 C/2021 J2 (PANSTARRS) MPEC 2023-XP6 + PK21J030 2019 06 30.4082 4.895591 0.449374 125.6376 111.0061 14.5154 20250607 7.0 4.0 P/2021 J3 (ATLAS) MPEC 2024-F34 + CK21K010 2021 05 2.4345 2.502070 0.801523 184.2254 140.9236 16.2713 20250607 11.0 4.0 C/2021 K1 (ATLAS) MPEC 2022-O08 + CK21K020 2021 09 9.2652 5.463955 1.000476 343.2804 282.3370 100.8710 20250607 8.0 4.0 C/2021 K2 (MASTER) MPEC 2022-O01 + CK21K030 2022 02 3.6622 5.227832 1.004214 182.0155 114.6072 134.7805 20250607 10.0 4.0 C/2021 K3 (Catalina) MPEC 2022-L66 + PK21L020 2021 07 22.8578 1.939570 0.520801 51.4342 266.6533 21.0645 20250607 17.0 4.0 P/2021 L2 (Leonard) MPEC 2021-W31 + CK21L030 2022 02 14.9876 8.460199 1.004560 91.6503 345.0163 78.5393 20250607 6.0 4.0 C/2021 L3 (Borisov) MPEC 2024-H50 + PK21N010 2026 07 27.8496 0.966249 0.675728 21.2263 301.1355 11.4856 20250607 19.0 4.0 P/2021 N1 (ZTF) MPEC 2022-TA0 + PK21N020 2021 11 14.1845 3.805684 0.452162 177.6277 221.7427 13.0601 20250607 9.5 4.0 P/2021 N2 (Fuls) MPEC 2024-GJ3 + CK21N030 2020 08 16.9598 5.712295 0.959379 304.6036 337.5252 26.7630 20250607 8.5 4.0 C/2021 N3 (PANSTARRS) MPEC 2022-YB4 + CK21O010 2021 08 14.7476 0.782771 0.999837 74.4253 41.5444 27.5716 20250607 10.5 4.0 C/2021 O1 (Nishimura) MPEC 2022-A21 + CK21O030 2022 04 21.2790 0.285132 1.000051 300.0165 188.7945 56.8265 20250607 10.5 4.0 C/2021 O3 (PANSTARRS) MPEC 2022-L66 + CK21P010 2022 06 2.5785 4.379569 0.998387 40.5251 359.7108 51.6209 20250607 11.0 4.0 C/2021 P1 (PANSTARRS) MPEC 2024-F34 + CK21P020 2023 01 23.0778 5.068062 0.999611 76.7165 32.0943 150.0554 20250607 9.0 4.0 C/2021 P2 (PANSTARRS) MPC184409 + PK21P030 2021 05 28.3744 2.919184 0.338380 334.0109 358.2483 27.1602 20250607 14.0 4.0 P/2021 P3 (PANSTARRS) MPEC 2024-GJ3 + CK21P040 2022 07 30.4213 1.078644 0.996357 175.8072 348.0099 56.3727 20250607 9.5 4.0 C/2021 P4 (ATLAS) MPEC 2023-A50 + PK21P20E 2028 09 4.5434 1.236315 0.669952 210.4345 99.6248 20.0000 20250607 17.0 4.0 P/2021 PE20 (ATLAS) MPEC 2023-E68 + CK21Q030 2022 01 26.0869 5.208699 0.930647 114.1449 307.9094 77.7168 20250607 8.0 4.0 C/2021 Q3 (ATLAS) MPEC 2023-FK0 + CK21Q040 2023 06 11.1267 7.565158 1.001761 147.0577 183.3291 71.5308 20250607 6.0 4.0 C/2021 Q4 (Fuls) MPEC 2025-A40 + PK21Q050 2027 08 16.9857 1.234013 0.624570 180.9568 239.7555 10.7383 20250607 15.0 4.0 P/2021 Q5 (ATLAS) MPEC 2022-C56 + CK21Q060 2024 03 25.2207 8.707743 1.002785 141.0643 133.5742 161.8260 20250607 6.0 4.0 C/2021 Q6 (PANSTARRS) MPEC 2024-UA9 + CK21Q45M 2022 08 13.6825 2.778020 0.993202 72.9193 354.5964 22.7994 20250607 11.0 4.0 C/2021 QM45 (PANSTARRS) MPEC 2023-FK0 + PK21R010 2021 12 8.8778 4.884484 0.408246 220.0466 143.1106 5.5325 20250607 11.0 4.0 P/2021 R1 (PANSTARRS) MPEC 2022-X67 + CK21R020 2021 12 28.4483 7.316511 0.999301 32.5514 16.3366 134.4823 20250607 7.5 4.0 C/2021 R2 (PANSTARRS) MPEC 2022-X67 + PK21R030 2028 09 17.7153 2.519654 0.331530 2.5905 304.1942 19.9414 20250607 16.0 4.0 P/2021 R3 (PANSTARRS) MPEC 2021-W31 + PK21R040 2021 10 13.4411 2.333838 0.585290 56.7759 321.2822 21.0120 20250607 16.0 4.0 P/2021 R4 (Wierzchos) MPEC 2021-W31 + PK21R050 2022 01 12.4133 3.329986 0.305959 167.6057 219.9619 7.8538 20250607 12.0 4.0 P/2021 R5 (Rankin) MPEC 2024-JU4 + PK21R060 2021 10 31.9429 2.559320 0.593047 220.8794 176.1617 34.8921 20250607 14.5 4.0 P/2021 R6 (Groeller) MPEC 2021-W31 + CK21R070 2021 04 17.3065 5.654602 0.994322 140.3960 170.2005 158.8748 20250607 10.5 4.0 C/2021 R7 (PANSTARRS) MPEC 2022-X67 + PK21R080 2027 01 5.7856 2.136640 0.292557 190.8203 167.0660 2.2027 20250607 18.5 4.0 P/2021 R8 (Sheppard) MPEC 2021-Y10 + CK21S010 2022 03 1.9959 6.124948 1.002894 148.3065 299.8565 52.0384 20250607 7.0 4.0 C/2021 S1 (ATLAS) MPEC 2023-J29 + CK21S030 2024 02 14.6735 1.319790 1.000019 6.8372 215.6084 58.5389 20250607 5.5 4.0 C/2021 S3 (PANSTARRS) MPC184409 + CK21S040 2024 01 3.8162 6.691686 0.957228 73.0398 5.4532 17.4795 20250607 6.5 4.0 C/2021 S4 (Tsuchinshan) MPC184409 + CK21T010 2021 10 14.8469 3.060410 0.998910 51.5821 56.8478 140.3528 20250607 12.5 4.0 C/2021 T1 (Lemmon) MPEC 2022-OB6 + CK21T020 2022 06 8.3198 1.244243 1.000537 263.5303 223.2090 117.5134 20250607 12.0 4.0 C/2021 T2 (Fuls) MPEC 2023-A50 + CK21T040 2023 07 31.5176 1.481561 0.999707 329.7726 257.8897 160.7784 20250607 7.5 4.0 C/2021 T4 (Lemmon) MPC184409 + PK21T81R 2022 04 3.5989 1.464864 0.833029 272.0071 220.1771 36.8148 20250607 15.6 4.0 P/2021 TR81 (Lemmon) MPC184409 + PK21U010 2021 09 30.7736 2.453771 0.712665 145.2354 246.7942 30.5513 20250607 14.5 4.0 P/2021 U1 (Wierzchos) MPEC 2022-ED3 + PK21U030 2021 10 24.8639 1.891077 0.549418 335.3243 75.0940 69.9617 20250607 15.5 4.0 P/2021 U3 (Attard-Maury) MPEC 2022-L66 + CK21U040 2021 12 22.5427 1.787379 0.960707 237.3244 241.8058 152.8830 20250607 17.0 4.0 C/2021 U4 (Leonard) MPEC 2021-W31 + CK21U050 2022 01 26.9766 2.359144 0.989386 321.4594 182.6792 39.0401 20250607 13.0 4.0 C/2021 U5 (Catalina) MPEC 2022-WQ9 + CK21V010 2022 04 30.6156 3.019101 0.995790 195.2151 207.6973 71.4363 20250607 13.0 4.0 C/2021 V1 (Rankin) MPEC 2022-CN4 + PK21V020 2023 01 21.9705 3.497344 0.615254 259.9036 232.2763 12.6929 20250607 10.0 4.0 P/2021 V2 (Fuls) MPEC 2024-JU4 + CK21X010 2023 05 27.2796 3.234567 1.000590 334.6147 10.6146 140.1069 20250607 7.0 4.0 C/2021 X1 (Maury-Attard) MPEC 2024-TD8 + CK21X020 2022 07 8.3674 2.997954 1.001506 193.3838 228.8412 137.1542 20250607 13.0 4.0 C/2021 X2 (Bok) MPEC 2024-E08 + CK21Y010 2023 04 30.9232 2.032495 1.001576 245.8489 244.7667 77.1878 20250607 7.0 4.0 C/2021 Y1 (ATLAS) MPEC 2024-GJ3 + CK22A010 2022 01 31.1313 1.256062 0.996614 201.2816 285.4933 116.5716 20250607 18.0 4.0 C/2022 A1 (Sarneczky) MPEC 2022-YN2 + CK22A020 2023 02 18.1853 1.735370 1.000067 88.3667 171.6034 108.1677 20250607 9.5 4.0 C/2022 A2 (PANSTARRS) MPEC 2024-P23 + CK22A030 2023 09 28.9560 3.704365 0.995858 234.8705 325.4581 88.3494 20250607 8.0 4.0 C/2022 A3 (Lemmon-ATLAS) MPEC 2024-UQ8 + PK22B010 2022 02 25.9985 1.894403 0.653624 148.9349 325.3836 10.9943 20250607 16.5 4.0 P/2022 B1 (Wierzchos) MPEC 2022-K19 + AK22B030 2022 01 16.7301 3.704100 0.994170 150.7174 286.1765 132.0508 20250607 16.5 2.0 A/2022 B3 MPEC 2022-YB4 + CK22B040 2022 01 30.4291 1.375962 0.996607 153.0203 340.5189 20.0569 20250607 21.0 4.0 C/2022 B4 (Bok) MPEC 2022-GA9 + PK22B09V 2029 12 6.0502 3.346023 0.233561 16.3119 337.3087 11.9240 20250607 9.5 4.0 P/2022 BV9 (Lemmon) MPEC 2023-J29 + PK22C010 2021 11 5.4727 3.985092 0.449125 9.4570 113.0998 4.7631 20250607 12.0 4.0 P/2022 C1 (PANSTARRS) MPEC 2023-J29 + PK22C020 2022 08 5.8979 3.366634 0.441979 89.1385 135.2629 9.9848 20250607 12.5 4.0 P/2022 C2 (PANSTARRS) MPEC 2023-VM5 + PK22C030 2022 06 30.2059 4.370540 0.545491 93.8063 139.0407 12.8248 20250607 11.5 4.0 P/2022 C3 (PANSTARRS) MPEC 2023-UR6 + PK22D010 2021 08 28.7708 3.347542 0.547980 88.6628 47.9484 44.0670 20250607 12.5 4.0 P/2022 D1 (PANSTARRS) MPEC 2022-K19 + CK22D020 2022 03 28.0346 1.552672 0.996094 177.8525 312.3620 22.6800 20250607 17.0 4.0 C/2022 D2 (Kowalski) MPEC 2022-K19 + PK22E010 2022 06 9.3482 2.944576 0.220581 114.9011 113.3416 19.0070 20250607 13.5 4.0 P/2022 E1 (Christensen) MPEC 2022-L66 + CK22E020 2024 09 14.1400 3.666461 1.000390 41.7481 125.3976 137.1410 20250607 5.0 4.0 C/2022 E2 (ATLAS) MPC184409 + CK22E030 2023 01 12.5247 1.114104 0.999994 145.8268 302.5099 109.1749 20250607 7.5 4.0 C/2022 E3 (ZTF) MPEC 2024-GJ3 + CK22F010 2022 08 5.8226 5.977350 0.999413 278.3443 350.6346 58.0037 20250607 7.0 4.0 C/2022 F1 (ATLAS) MPEC 2024-PC5 + CK22F020 2022 03 22.3816 1.589437 0.933143 200.5932 58.7821 97.3170 20250607 14.5 4.0 C/2022 F2 (NEOWISE) MPEC 2022-QD9 + CK22H010 2024 01 18.6537 7.689230 0.990991 246.2917 6.3275 49.8600 20250607 6.0 4.0 C/2022 H1 (PANSTARRS) MPEC 2024-JU4 + CK22J010 2022 02 19.3331 1.600207 0.966312 305.6124 280.8021 105.9594 20250607 14.9 4.0 C/2022 J1 (Maury-Attard) MPEC 2022-VC5 + CK22J020 2022 10 26.7121 1.828181 0.979687 133.1453 252.6822 149.1415 20250607 9.0 4.0 C/2022 J2 (Bok) MPEC 2023-M14 + CK22J05K 2023 04 28.9763 2.695488 0.938604 247.3840 59.6519 16.8249 20250607 11.0 4.0 C/2022 JK5 (PANSTARRS) MPEC 2024-YC7 + CK22K010 2021 12 16.6229 3.986046 1.000876 142.5492 136.3589 41.9740 20250607 11.0 4.0 C/2022 K1 (Leonard) MPEC 2022-ST7 + CK22L010 2022 09 27.7531 1.591070 0.996279 59.8046 300.0319 123.4391 20250607 15.8 4.0 C/2022 L1 (Catalina) MPEC 2023-CD7 + CK22L020 2024 03 12.2038 2.693298 1.000868 199.9230 39.2435 129.3128 20250607 6.5 4.0 C/2022 L2 (ATLAS) MPC184409 + PK22L030 2022 10 29.8615 2.423858 0.627457 10.4121 29.8231 21.5377 20250607 16.5 4.0 P/2022 L3 (ATLAS) MPEC 2024-DC6 + CK22L040 2021 12 9.0718 3.008856 0.989335 125.2537 66.0616 141.2437 20250607 14.0 4.0 C/2022 L4 (PANSTARRS) MPEC 2022-N37 + CK22N010 2022 09 9.7789 1.479161 0.959613 40.9970 301.8787 164.7269 20250607 16.9 4.0 C/2022 N1 (Attard-Maury) MPEC 2024-GJ3 + CK22N020 2025 07 31.7948 3.825375 1.003302 75.3967 319.7401 5.5029 20250607 6.0 4.0 C/2022 N2 (PANSTARRS) MPC184410 + CK22O010 2022 02 15.4141 7.434842 1.001362 268.9419 49.9114 71.0506 20250607 6.0 4.0 C/2022 O1 (ATLAS) MPEC 2024-A43 + PK22O020 2023 01 6.7445 1.759350 0.720970 48.6668 330.4915 9.4187 20250607 16.2 4.0 P/2022 O2 (PANSTARRS) MPEC 2023-HD1 + CK22P010 2022 11 28.7012 1.592406 0.913784 249.8778 205.0694 154.5877 20250607 13.0 4.0 C/2022 P1 (NEOWISE) MPEC 2023-N01 + PK22P020 2022 07 11.0352 1.985286 0.558007 137.7713 291.1745 12.4409 20250607 12.5 4.0 P/2022 P2 (ZTF) MPEC 2023-XP6 + CK22P030 2022 07 27.5272 2.566240 0.990252 0.2182 72.2187 59.5163 20250607 9.0 4.0 C/2022 P3 (ZTF) MPEC 2023-HD1 + CK22Q020 2023 01 31.7222 1.641752 0.949932 44.0329 352.9616 151.4593 20250607 13.0 4.0 C/2022 Q2 (ATLAS) MPEC 2023-R20 + CK22Q78E 2025 09 11.5622 5.475978 1.003130 0.5781 119.8897 36.6127 20250607 5.0 4.0 C/2022 QE78 (ATLAS) MPC184410 + PK22R010 2023 10 4.3554 3.565587 0.501046 221.7894 175.6706 7.3777 20250607 11.5 4.0 P/2022 R1 (PANSTARRS) MPEC 2024-M41 + CK22R020 2022 10 25.5443 0.630268 0.998563 78.3208 60.3936 52.8938 20250607 17.0 4.0 C/2022 R2 (ATLAS) MPEC 2022-Y15 + CK22R030 2023 03 5.9140 5.131984 1.001524 72.9325 8.2588 43.0722 20250607 9.0 4.0 C/2022 R3 (Leonard) MPC184410 + PK22R040 2022 07 9.8981 1.959690 0.489471 197.4954 176.6351 21.0094 20250607 16.5 4.0 P/2022 R4 (PANSTARRS) MPEC 2022-X67 + PK22R050 2027 10 12.0615 2.472044 0.194743 240.5411 115.0432 15.2924 20250607 16.0 4.0 P/2022 R5 (PANSTARRS) MPEC 2022-WQ9 + CK22R060 2025 08 26.1862 6.565553 1.005023 319.9142 150.7855 57.0193 20250607 5.0 4.0 C/2022 R6 (PANSTARRS) MPC184410 + PK22S010 2022 08 19.0352 3.155498 0.507633 262.8458 136.0901 34.5672 20250607 15.1 4.0 P/2022 S1 (PANSTARRS) MPEC 2023-HD1 + CK22S030 2023 01 21.6281 0.838755 1.000385 267.9860 157.2527 78.4839 20250607 17.0 4.0 C/2022 S3 (PANSTARRS) MPEC 2022-VC5 + CK22S040 2024 07 18.7805 2.761844 0.998042 268.5621 220.1784 101.2157 20250607 8.0 4.0 C/2022 S4 (Lemmon) MPEC 2024-PC5 + CK22S050 2022 11 27.7762 2.177998 0.893851 232.8002 214.8652 136.5121 20250607 16.3 4.0 C/2022 S5 (PANSTARRS) MPEC 2023-HD1 + CK22T010 2024 02 17.4410 3.444329 1.000363 324.2933 236.9158 22.5422 20250607 9.0 4.0 C/2022 T1 (Lemmon) MPEC 2024-O39 + CK22U010 2024 03 26.0875 4.202263 1.000199 78.6124 72.5278 128.1481 20250607 8.5 4.0 C/2022 U1 (Leonard) MPC184410 + CK22U020 2023 01 14.2726 1.329591 0.986468 148.0078 304.4056 48.2495 20250607 16.0 4.0 C/2022 U2 (ATLAS) MPEC 2023-VM5 + CK22U030 2024 07 28.6616 4.826803 1.000196 189.1323 272.7883 33.6618 20250607 7.5 4.0 C/2022 U3 (Bok) MPC182880 + CK22U040 2023 08 3.6417 2.897353 0.998995 88.9862 132.9162 52.0525 20250607 10.5 4.0 C/2022 U4 (Bok) MPEC 2023-W26 + CK22V020 2023 11 1.8576 2.064184 0.943676 168.9544 332.8554 98.9020 20250607 12.0 4.0 C/2022 V2 (Lemmon) MPEC 2024-H50 + PK22W010 2022 09 16.1339 3.372687 0.516485 17.9288 38.8292 13.4641 20250607 12.5 4.0 P/2022 W1 (Rankin) MPEC 2023-CD7 + CK22W020 2023 03 8.7422 3.124810 0.990885 123.3139 320.4369 63.5026 20250607 11.5 4.0 C/2022 W2 (ATLAS) MPEC 2024-EF7 + CK22W030 2023 06 22.8205 1.396931 0.994975 116.5130 132.3023 103.5810 20250607 13.0 4.0 C/2022 W3 (Leonard) MPEC 2024-C04 + CK22Y010 2022 11 27.6753 2.960457 0.765304 174.8794 285.8772 18.8558 20250607 9.0 4.0 C/2022 Y1 (Hogan) MPEC 2023-M14 + CK22Y020 2023 03 22.4194 2.542047 0.871120 105.4732 216.3700 165.8910 20250607 13.5 4.0 C/2022 Y2 (Lemmon) MPEC 2023-TM6 + CK23A010 2023 03 18.5915 1.836022 0.991702 159.2631 318.2670 94.7412 20250607 14.5 4.0 C/2023 A1 (Leonard) MPEC 2024-GJ3 + CK23A020 2023 01 20.3647 0.945072 0.997681 142.4955 94.5082 94.7064 20250607 13.5 4.0 C/2023 A2 (SWAN) MPEC 2023-J95 + CK23A030 2024 09 27.7432 0.391505 1.000120 308.5071 21.5730 139.1112 20250607 6.5 3.2 C/2023 A3 (Tsuchinshan-ATLAS) MPC184410 + PK23B010 2023 05 3.7462 6.140625 0.130927 81.7065 78.5600 14.5884 20250607 5.5 4.0 P/2023 B1 (PANSTARRS) MPEC 2024-F34 + CK23B020 2023 03 10.6028 1.740681 0.997082 317.3632 218.0912 40.7669 20250607 14.5 4.0 C/2023 B2 (ATLAS) MPEC 2023-XP6 + PK23B030 2020 09 5.9334 3.993422 0.122381 240.3778 153.9861 9.1566 20250607 10.5 4.0 P/2023 B3 (PANSTARRS) MPEC 2023-F81 + CK23C020 2024 11 16.7867 2.368523 0.999028 357.4473 301.0045 48.3217 20250607 7.0 4.0 C/2023 C2 (ATLAS) MPC184410 + CK23E010 2023 06 30.8676 1.027505 0.946637 105.9509 164.5185 38.2811 20250607 15.5 4.0 C/2023 E1 (ATLAS) MPEC 2024-D33 + CK23F010 2023 06 28.1013 1.710205 0.993040 216.7329 25.3074 131.6941 20250607 16.0 4.0 C/2023 F1 (PANSTARRS) MPEC 2023-N01 + CK23F030 2025 02 2.6254 5.190781 1.003422 265.5326 109.4653 145.9636 20250607 6.0 4.0 C/2023 F3 (ATLAS) MPC184410 + CK23H010 2024 11 28.6409 4.447598 0.994146 333.7522 292.6467 21.7827 20250607 8.5 4.0 C/2023 H1 (PANSTARRS) MPC184410 + CK23H020 2023 10 29.1601 0.895248 0.996380 150.6863 217.0716 113.7478 20250607 14.0 4.0 C/2023 H2 (Lemmon) MPEC 2024-GJ3 + CK23H030 2024 02 18.3674 5.231858 0.615754 193.2680 55.0903 2.4889 20250607 10.0 4.0 C/2023 H3 (PANSTARRS) MPEC 2023-R20 + AK23H040 2023 08 8.7096 2.124079 0.985062 65.0179 230.8265 76.5692 20250607 18.0 2.0 A/2023 H4 MPEC 2023-SQ0 + CK23H050 2025 06 30.2758 4.312581 1.000464 60.0993 159.4785 97.8554 20250607 7.0 4.0 C/2023 H5 (Lemmon) MPC184410 + PK23J16N 2024 12 30.7664 2.299770 0.146928 353.2040 11.8728 3.7022 20250607 14.0 4.0 P/2023 JN16 (Lemmon) MPEC 2024-UA9 + CK23K010 2023 09 7.5805 2.038748 0.996736 337.4197 223.6981 137.9976 20250607 13.0 4.0 C/2023 K1 (ATLAS) MPEC 2024-GJ3 + PK23M010 2023 12 14.3278 2.826670 0.586824 79.6994 216.8598 12.2889 20250607 13.5 4.0 P/2023 M1 (PANSTARRS) MPEC 2023-N01 + PK23M020 2023 07 27.5154 3.515609 0.370007 243.4716 83.2501 19.7274 20250607 12.5 4.0 P/2023 M2 (PANSTARRS) MPEC 2024-TD8 + PK23M040 2022 04 13.6725 3.927295 0.278931 320.5223 296.2840 7.5919 20250607 7.5 4.0 P/2023 M4 (ATLAS) MPEC 2024-TP3 + CK23P010 2023 09 17.6213 0.224427 0.996023 116.2527 66.8314 132.4779 20250607 10.0 4.0 C/2023 P1 (Nishimura) MPEC 2024-MB8 + CK23Q010 2024 12 1.1274 2.575799 1.004990 84.4181 7.1241 36.6448 20250607 10.0 4.0 C/2023 Q1 (PANSTARRS) MPC184410 + CK23Q020 2024 06 23.9492 3.209123 0.990691 171.6918 92.6797 104.0618 20250607 11.5 4.0 C/2023 Q2 (PANSTARRS) MPEC 2024-N80 + CK23R010 2026 04 13.4847 3.569816 1.002199 144.2738 62.5623 149.3169 20250607 6.0 4.0 C/2023 R1 (PANSTARRS) MPC184410 + CK23R020 2024 08 12.1588 0.905101 1.000281 337.3129 188.8999 30.6893 20250607 10.5 4.0 C/2023 R2 (PANSTARRS) MPEC 2024-L77 + AK23R030 2023 12 18.1806 1.358648 0.998106 86.9417 347.3415 12.0809 20250607 20.0 2.0 A/2023 R3 MPEC 2023-UR6 + CK23R03N 2023 01 20.5090 5.180351 0.490603 130.6078 207.0645 10.3516 20250607 7.5 4.0 C/2023 RN3 (ATLAS) MPEC 2024-YC7 + CK23R61S 2028 12 1.1026 7.998302 0.327816 119.4045 347.0200 19.9446 20250607 6.8 4.0 C/2023 RS61 MPC184411 + PK23S010 2025 02 24.1745 2.619711 0.318474 180.3056 317.2904 9.1578 20250607 11.5 4.0 P/2023 S1 (PANSTARRS) MPC184411 + CK23S020 2023 10 15.3902 1.061415 0.993640 78.9402 229.4757 19.6629 20250607 15.0 4.0 C/2023 S2 (ATLAS) MPEC 2023-XP6 + CK23S030 2024 01 19.6482 0.829344 0.970828 281.5339 233.8238 140.4936 20250607 16.0 4.0 C/2023 S3 (Lemmon) MPEC 2024-P23 + PK23T010 2024 05 22.8559 2.817608 0.333228 202.8625 249.5765 6.6123 20250607 14.0 4.0 P/2023 T1 (PANSTARRS) MPEC 2024-BE0 + CK23T020 2023 12 22.7504 1.996241 0.991091 111.2150 317.5274 48.5913 20250607 14.5 4.0 C/2023 T2 (Borisov) MPEC 2024-GJ3 + CK23T030 2025 01 25.3523 3.548327 0.995846 302.8473 246.0018 27.2215 20250607 8.5 4.0 C/2023 T3 (Fuls) MPC184411 + CK23T22D 2024 09 16.3013 2.356700 0.951269 32.5408 5.5636 170.4899 20250607 12.5 4.0 C/2023 TD22 (Lemmon) MPEC 2024-VB7 + CK23U010 2024 10 12.9159 4.973072 0.998074 255.6438 305.8043 108.1458 20250607 8.0 4.0 C/2023 U1 (Fuls) MPC184411 + CK23V010 2025 07 13.0442 5.092567 1.000368 103.3151 15.0419 102.0138 20250607 8.5 4.0 C/2023 V1 (Lemmon) MPC184411 + PK23V020 2024 02 3.6810 3.104147 0.570075 330.5189 95.4745 9.8884 20250607 13.5 4.0 P/2023 V2 (PANSTARRS) MPC184411 + CK23V030 2023 08 4.1338 4.488241 0.651749 291.8520 91.2924 40.7034 20250607 11.5 4.0 C/2023 V3 (PANSTARRS) MPEC 2024-A43 + CK23V040 2024 05 30.3897 1.121895 1.001154 50.8693 66.3269 67.1258 20250607 12.0 4.0 C/2023 V4 (Camarasa-Duszanowicz) MPEC 2024-UQ8 + CK23V050 2023 12 13.9052 0.846313 1.009422 56.9682 31.5157 73.5516 20250607 21.5 4.0 C/2023 V5 (Leonard) MPEC 2024-GJ3 + PK23V060 2022 12 2.3358 4.366339 0.175560 192.5347 189.6581 3.9721 20250607 11.5 4.0 P/2023 V6 (PANSTARRS) MPEC 2025-A40 + CK23X010 2023 10 17.9784 0.951047 0.993900 321.4681 136.9938 110.5883 20250607 13.5 3.2 C/2023 X1 (Leonard) MPEC 2024-GJ3 + CK23X020 2025 12 28.1548 5.088824 1.000125 64.7625 66.3037 76.9830 20250607 8.5 3.2 C/2023 X2 (Lemmon) MPC184411 + PK23X030 2024 04 22.1386 3.030701 0.286187 40.8657 62.0136 4.4833 20250607 15.5 4.0 P/2023 X3 (PANSTARRS) MPEC 2024-A43 + CK23X040 2024 05 25.0460 3.658390 0.631261 100.5894 28.7694 11.5936 20250607 12.0 4.0 C/2023 X4 (Hogan) MPC184411 + CK23X070 2025 05 15.2159 4.820336 1.002599 354.3996 119.1982 69.0877 20250607 9.0 4.0 C/2023 X7 (PANSTARRS) MPEC 2024-DA2 + PK23Y010 2023 11 29.9149 2.080081 0.445359 51.4774 78.8560 6.3839 20250607 17.0 4.0 P/2023 Y1 (Gibbs) MPEC 2024-JU4 + PK23Y020 2023 08 10.1019 2.277287 0.392275 16.9000 79.2289 6.9927 20250607 15.5 4.0 P/2023 Y2 (Gibbs) MPEC 2025-A40 + CK24A010 2025 06 13.6964 3.875294 1.002392 353.3092 112.1356 94.4631 20250607 7.0 4.0 C/2024 A1 (ATLAS) MPC184411 + CK24A020 2024 04 28.8177 1.879458 0.941806 295.4973 78.1655 119.1148 20250607 12.5 4.0 C/2024 A2 (ATLAS) MPC182881 + CK24B010 2024 10 7.7179 1.633798 1.001017 66.2166 79.1884 70.9030 20250607 13.0 4.0 C/2024 B1 (Lemmon) MPC184411 + CK24B020 2023 10 5.8847 4.078123 0.998026 130.3387 294.3851 99.8677 20250607 11.5 4.0 C/2024 B2 (Lemmon) MPEC 2025-A40 + CK24C010 2024 08 31.0529 4.412871 0.582962 94.4879 83.8096 14.2269 20250607 11.5 4.0 C/2024 C1 (PANSTARRS) MPC184412 + CK24C020 2025 03 11.1495 8.991369 0.445864 87.5706 66.4454 27.2844 20250607 6.0 4.0 C/2024 C2 (PANSTARRS) MPEC 2024-JU4 + CK24C030 2023 11 8.6924 6.712987 0.424616 159.6863 359.7063 22.4552 20250607 9.0 4.0 C/2024 C3 (PANSTARRS) MPC184412 + CK24C040 2024 01 30.1903 1.470563 0.982384 321.4999 220.6723 79.2832 20250607 14.5 4.0 C/2024 C4 (ATLAS) MPEC 2024-Q20 + CK24D010 2027 12 3.3820 6.693542 0.999258 125.7735 179.6622 132.4501 20250607 7.3 4.0 C/2024 D1 (Lemmon) MPC184412 + CK24E010 2026 01 20.7601 0.565965 1.000069 243.6336 108.0802 75.2390 20250607 7.0 4.0 C/2024 E1 (Wierzchos) MPC184412 + CK24E020 2023 10 25.0686 7.694709 0.850673 358.1286 135.6531 155.6492 20250607 8.0 4.0 C/2024 E2 (Bok) MPEC 2024-JU4 + PK24F010 2023 10 25.7705 1.859838 0.459978 229.5757 251.5413 7.0053 20250607 16.0 4.0 P/2024 F1 (PANSTARRS) MPEC 2024-JU4 + CK24F020 2024 07 28.9781 3.967951 0.601104 112.8898 138.9401 13.7428 20250607 11.0 4.0 C/2024 F2 (PANSTARRS) MPEC 2024-Q20 + PK24F09G 2024 05 20.3990 1.596496 0.509915 245.9331 253.0426 1.7312 20250607 14.0 4.0 P/2024 FG9 (Nanshan-Hahn) MPEC 2024-UA9 + CK24G010 2024 10 21.0733 3.930126 0.967829 128.2240 30.6051 95.3941 20250607 10.0 4.0 C/2024 G1 (Wierzchos) MPC184412 + CK24G020 2025 06 13.5331 5.348242 0.992717 328.7372 171.3965 122.1259 20250607 7.0 4.0 C/2024 G2 (ATLAS) MPC184412 + CK24G030 2025 01 13.4274 0.093546 1.000007 108.1261 220.3434 116.8475 20250607 9.0 4.0 C/2024 G3 (ATLAS) MPC184412 + CK24G040 2026 03 21.6212 4.900411 0.998461 131.4209 152.9824 33.0264 20250607 8.0 4.0 C/2024 G4 (PANSTARRS) MPC184412 + CK24G050 2024 09 7.0515 2.953025 0.994819 209.5786 316.3932 50.3869 20250607 13.0 4.0 C/2024 G5 (Leonard) MPEC 2024-JC6 + CK24G060 2026 02 20.7641 6.429739 1.002178 23.4411 250.9518 120.4557 20250607 5.5 4.0 C/2024 G6 (ATLAS) MPC184412 + CK24G070 2025 02 10.1152 6.027666 1.001914 289.6572 191.9622 131.5155 20250607 7.0 4.0 C/2024 G7 (ATLAS) MPC184412 + AK24G080 2024 06 15.5855 1.172464 0.991726 249.1574 11.2484 97.4125 20250607 20.0 2.0 A/2024 G8 MPEC 2024-Q05 + PK24J010 2023 11 11.3025 2.636673 0.307717 200.3646 321.9389 13.1590 20250607 14.5 4.0 P/2024 J1 (PANSTARRS) MPEC 2024-JU4 + CK24J020 2025 03 19.7844 1.810894 0.987709 143.1605 189.0592 79.2971 20250607 11.5 4.0 C/2024 J2 (Wierzchos) MPC182882 + CK24J030 2026 11 25.3218 3.865136 1.000768 74.0888 285.9612 75.6399 20250607 5.0 4.0 C/2024 J3 (ATLAS) MPC184412 + CK24J040 2025 04 25.9991 5.695164 0.999103 127.8577 19.3058 117.5302 20250607 8.0 4.0 C/2024 J4 (Lemmon) MPC184412 + PK24K010 2024 05 8.9505 3.455517 0.495180 351.9289 251.6894 1.7862 20250607 13.5 4.0 P/2024 K1 (PANSTARRS) MPEC 2024-LB4 + CK24L010 2025 04 23.1525 5.348148 0.533564 171.7954 45.1395 99.1660 20250607 10.0 4.0 C/2024 L1 (PANSTARRS) MPC184413 + CK24L020 2025 06 12.8314 8.326292 0.982348 345.6194 266.2859 139.4875 20250607 7.5 3.2 C/2024 L2 (PANSTARRS) MPEC 2024-P23 + CK24L030 2023 11 24.1774 6.857968 1.003905 59.0777 294.9946 111.5923 20250607 9.5 4.0 C/2024 L3 (PANSTARRS) MPEC 2024-RQ6 + CK24L050 2025 03 10.3957 3.432418 1.037147 290.5150 139.1771 166.5730 20250607 9.0 4.0 C/2024 L5 (ATLAS) MPC184413 + CK24M010 2024 11 19.9979 1.703230 0.942863 345.5849 76.2146 73.7096 20250607 12.0 4.0 C/2024 M1 (ATLAS) MPC184413 + CK24N010 2025 10 18.9212 4.398081 1.000755 91.2577 323.0177 88.7770 20250607 10.5 4.0 C/2024 N1 (PANSTARRS) MPEC 2024-RQ6 + CK24N030 2025 04 11.4366 5.014572 1.001350 86.8850 82.6088 88.7289 20250607 8.0 4.0 C/2024 N3 (Sarneczky) MPC184413 + CK24N040 2025 01 10.1649 5.397759 1.004393 116.7023 339.6578 49.7739 20250607 7.5 4.0 C/2024 N4 (Sarneczky) MPC184413 + CK24O010 2023 01 28.5633 6.606926 1.000681 349.8910 303.3411 59.0788 20250607 8.5 4.0 C/2024 O1 (PANSTARRS) MPEC 2024-PC5 + PK24O020 2024 04 20.1610 3.697669 0.499118 310.7859 6.8056 28.9766 20250607 12.0 4.0 P/2024 O2 (PANSTARRS) MPEC 2024-UA9 + PK24O02C 2024 10 9.3166 0.592871 0.774187 258.5377 136.6170 7.6713 20250607 20.5 4.0 P/2024 OC2 (PANSTARRS) MPEC 2025-A40 + CK24P07N 2024 12 6.4352 1.524565 0.977350 74.2736 358.5841 101.2096 20250607 15.2 4.0 C/2024 PN7 (PANSTARRS) MPC184413 + PK24Q010 2024 06 14.6311 1.637488 0.534878 284.5039 23.1195 5.0126 20250607 17.0 4.0 P/2024 Q1 (PANSTARRS) MPEC 2024-UQ8 + CK24Q030 2025 03 5.2201 2.091554 1.001497 70.1278 337.2871 121.3783 20250607 15.0 4.0 C/2024 Q3 (PANSTARRS) MPC184413 + CK24Q040 2024 11 12.1968 5.419054 0.992351 133.0471 324.2755 3.3145 20250607 10.0 4.0 C/2024 Q4 (PANSTARRS) MPC182882 + PK24R010 2024 06 15.8313 1.750903 0.493109 230.6717 84.9824 12.7361 20250607 18.0 4.0 P/2024 R1 (PANSTARRS) MPEC 2024-TP3 + PK24R020 2024 10 1.7590 2.303147 0.268695 203.9418 193.0159 15.1155 20250607 15.5 4.0 P/2024 R2 (PANSTARRS) MPC182883 + PK24R030 2024 05 8.3366 2.345714 0.267200 309.2846 33.2506 14.7194 20250607 15.0 4.0 P/2024 R3 (PANSTARRS) MPEC 2024-YC7 + CK24R040 2027 10 26.6109 4.409098 1.002653 108.9915 345.9343 95.3611 20250607 6.5 4.0 C/2024 R4 (PANSTARRS) MPC184413 + CK24S010 2024 10 28.4812 0.007982 0.999909 69.4522 347.5022 142.0003 20250607 15.5 4.0 C/2024 S1 (ATLAS) MPC182883 + PK24S020 2024 09 16.3025 2.047676 0.593608 49.1695 8.3392 7.5256 20250607 15.0 4.0 P/2024 S2 (Rankin) MPEC 2025-A40 + PK24T010 2024 09 30.3924 2.287001 0.653458 164.8648 279.7109 17.6202 20250607 14.5 4.0 P/2024 T1 (Rankin) MPC182883 + PK24T020 2024 12 8.3295 1.972292 0.680429 343.8267 113.0615 12.9290 20250607 16.0 4.0 P/2024 T2 (Rankin) MPC184413 + CK24T030 2025 03 15.2407 3.716172 0.956859 336.8865 74.8331 53.4767 20250607 11.5 4.0 C/2024 T3 (PANSTARRS) MPC182883 + CK24T050 2027 05 6.3483 3.842066 1.001944 352.4367 100.6819 52.3871 20250607 5.5 4.0 C/2024 T5 (ATLAS) MPC182883 + CK24U010 2024 06 30.4360 4.836142 0.990111 188.0802 270.2639 128.7552 20250607 10.0 4.0 C/2024 U1 (PANSTARRS) MPC182883 + AK24U020 2026 01 14.3739 8.180888 1.003415 29.7694 56.0699 120.6712 20250607 12.1 2.0 A/2024 U2 MPC182883 + CK24V010 2025 04 4.1127 2.318468 0.990059 168.6681 328.1946 54.6257 20250607 14.8 4.0 C/2024 V1 (Borisov) MPC184413 + CK24V020 2024 11 3.8244 1.243049 0.968360 13.7225 102.2019 95.9718 20250607 19.0 4.0 C/2024 V2 (Sarneczky) MPEC 2024-YC7 + CK24W010 2025 03 19.1032 2.560721 0.942928 256.7386 310.7275 83.2004 20250607 15.0 4.0 C/2024 W1 (PANSTARRS) MPC182883 + AK24W020 2025 02 27.4255 3.720676 1.002713 168.0046 241.9386 116.6177 20250607 15.6 2.0 A/2024 W2 MPC182883 + CK24X010 2025 08 3.5284 3.816633 0.597196 124.3433 352.0222 6.4625 20250607 11.3 4.0 C/2024 X1 (Fazekas) MPC182884 + CK24X020 2025 07 7.8765 3.676300 0.927289 315.7809 122.5228 109.2212 20250607 9.6 4.0 C/2024 X2 (ATLAS) MPC184413 + PK24X030 2024 09 5.7781 2.614203 0.626208 352.9445 113.3648 2.9723 20250607 14.6 4.0 P/2024 X3 (PANSTARRS) MPC184413 + CK24X040 2025 09 1.9043 3.604765 0.641702 153.2897 258.9431 34.6691 20250607 12.6 4.0 C/2024 X4 (PANSTARRS) MPEC 2025-A40 + CK24Y010 2024 11 26.8717 0.822294 0.986778 238.1426 112.5427 64.7619 20250607 17.6 4.0 C/2024 Y1 (Masek) MPC182884 + AK25A010 2027 03 12.2766 5.342567 1.004196 68.0618 101.3302 33.4390 20250607 11.8 2.0 A/2025 A1 MPC182884 + PK25A020 2024 10 5.6488 3.446368 0.322127 278.0443 189.3196 20.7339 20250607 13.2 4.0 P/2025 A2 (PANSTARRS) MPC184414 + CK25A030 2026 03 15.0350 5.792320 0.431718 222.3061 322.4335 9.9768 20250607 9.0 4.0 C/2025 A3 (Tsuchinshan) MPC184414 + CK25A040 2025 01 13.1641 3.824243 0.653948 102.7981 69.9134 32.0255 20250607 12.4 4.0 C/2025 A4 (PANSTARRS) MPC184414 + CK25A060 2025 11 8.5335 0.529955 0.995744 132.9600 108.0964 143.6616 20250607 13.2 4.0 C/2025 A6 (Lemmon) MPC184414 + AK25A070 2025 03 28.1089 2.883440 0.999342 195.5676 348.8445 133.6497 20250607 14.0 2.0 A/2025 A7 MPC184414 + CK25B010 2025 06 26.7741 3.530888 1.001036 23.5274 102.8409 39.6797 20250607 12.0 4.0 C/2025 B1 (PANSTARRS) MPC182885 + CK25B020 2026 09 9.9854 8.244896 1.000040 78.7280 84.8734 91.7517 20250607 6.2 4.0 C/2025 B2 (Borisov) MPC184414 + PK25C010 2025 02 6.5574 2.746051 0.345477 186.7991 9.1028 7.5170 20250607 10.8 4.0 P/2025 C1 (ATLAS) MPC184414 + CK25D010 2028 05 20.0519 14.118888 1.002955 185.8926 312.8984 84.4648 20250607 1.2 4.0 C/2025 D1 (Groeller) MPC184414 + PK25D020 2028 11 5.4532 7.326765 0.178734 314.0559 256.7342 5.3344 20250607 8.2 4.0 P/2025 D2 (PANSTARRS) MPC182885 + PK25D030 2024 07 25.7823 2.965720 0.252352 294.4845 186.6354 9.6443 20250607 14.7 4.0 P/2025 D3 (PANSTARRS) MPC184414 + PK25D040 2025 02 14.2866 3.254933 0.634404 332.8895 233.1200 15.9405 20250607 13.2 4.0 P/2025 D4 (ATLAS) MPC184414 + CK25D050 2025 05 13.2912 2.012171 0.999402 211.4927 0.7379 73.3811 20250607 17.6 4.0 C/2025 D5 (PANSTARRS) MPC184415 + CK25D060 2024 12 11.3848 2.503917 0.998432 285.4043 151.4874 145.7902 20250607 13.2 4.0 C/2025 D6 (ATLAS) MPC184415 + CK25E010 2026 09 23.7485 3.998179 0.997214 274.4213 344.5972 69.0661 20250607 9.7 4.0 C/2025 E1 (PANSTARRS) MPC184415 + CK25F010 2025 04 20.4725 1.069976 0.996413 334.2283 122.7043 109.2363 20250607 18.0 4.0 C/2025 F1 (ATLAS) MPC184415 + CK25F020 2025 05 1.1615 0.333494 1.000105 153.8372 329.8408 90.3649 20250607 11.2 4.0 C/2025 F2 (SWAN) MPC184415 + CK25J010 2026 06 11.7763 3.573081 0.999561 166.7598 273.9986 95.4403 20250607 9.1 4.0 C/2025 J1 (Borisov) MPC184415 + CK25K010 2025 10 8.3397 0.335178 1.001393 270.8238 97.4939 147.8989 20250607 12.2 4.0 C/2025 K1 (ATLAS) MPEC 2025-KB0 + CK25K020 2025 11 1.3769 2.834449 0.779321 233.6299 113.4440 113.2794 20250607 13.7 4.0 C/2025 K2 (PANSTARRS) MPEC 2025-L17 + CK25K030 2028 12 13.7688 3.468840 1.001673 188.5944 350.6172 104.9329 20250607 6.4 4.0 C/2025 K3 (PANSTARRS) MPEC 2025-L43 +0001P 2061 08 30.5535 0.583481 0.967338 112.5343 59.6243 162.2163 20250607 4.0 6.0 1P/Halley 98, 1083 +0002P 2023 10 22.5891 0.339116 0.847119 187.2796 334.0146 11.3441 20250607 11.5 6.0 2P/Encke MPEC 2024-TP3 +0003D 2025 06 26.1985 0.822720 0.767566 192.2940 276.1865 7.8877 20250607 11.0 6.0 3D/Biela 76, 1135 +0003D a 2024 12 2.1226 0.826862 0.767116 192.1273 276.6832 7.2156 20250607 11.0 6.0 3D-A/Biela 76, 1135 +0003D b 2025 06 28.0742 0.821835 0.767864 192.2552 276.2012 7.8798 20250607 11.0 6.0 3D-B/Biela 76, 1135 +0004P 2021 09 9.0132 1.622634 0.576330 207.1418 192.9114 8.0031 20250607 8.0 6.0 4P/Faye MPEC 2023-FK0 +0005D 2023 04 17.3329 0.512075 0.837872 20.3027 94.9065 18.6308 20250607 10.5 6.0 5D/Brorsen 27, 116 +0006P 2028 04 1.6672 1.357392 0.611917 178.0521 138.9508 19.4997 20250607 7.5 16.0 6P/d'Arrest MPEC 2022-WD2 +0007P 2027 08 30.9415 1.196667 0.647152 172.5187 93.2818 22.5914 20250607 10.0 6.0 7P/Pons-Winnecke MPEC 2023-A50 +0008P 2021 08 28.5768 1.023012 0.820694 207.4757 270.1769 54.9840 20250607 8.0 8.0 8P/Tuttle MPEC 2022-HC2 +0009P 2028 02 5.1454 1.729676 0.473611 184.4495 67.3300 10.6707 20250607 5.5 10.0 9P/Tempel MPEC 2024-YC7 +0010P 2026 08 2.1518 1.417388 0.537382 195.4930 117.8007 12.0274 20250607 5.0 10.0 10P/Tempel MPC184415 +0011P 2026 11 9.8611 1.387313 0.577455 168.0493 238.8631 14.4329 20250607 17.0 4.0 11P/Tempel-Swift-LINEAR MPEC 2024-R10 +0012P 2024 04 21.1391 0.781108 0.954663 199.0069 255.8565 74.1895 20250607 5.0 6.0 12P/Pons-Brooks MPC184415 +0013P 2024 06 30.0751 1.175457 0.930474 64.4223 85.8467 44.6658 20250607 5.0 6.0 13P/Olbers MPC184415 +0014P 2026 09 18.9958 2.738319 0.356681 159.1933 202.0241 27.9182 20250607 5.5 12.0 14P/Wolf MPC184415 +0015P 2028 02 9.7562 0.996655 0.716126 347.8663 13.7487 6.7874 20250607 12.0 4.0 15P/Finlay MPEC 2022-ED3 +0016P 2028 04 20.8950 1.883633 0.485635 245.3734 138.8262 3.0099 20250607 7.5 10.0 16P/Brooks MPEC 2022-X67 +0017P 2028 01 31.7112 2.089013 0.426332 24.6154 326.6091 19.0070 20250607 10.0 6.0 17P/Holmes MPEC 2023-J29 +0018D 2024 08 29.154 1.59307 0.58953 238.210 158.451 17.660 20250607 9.0 4.0 18D/Perrine-Mrkos 19, 80 +0019P 2022 02 2.3257 1.307044 0.637780 352.0066 74.2151 29.3157 20250607 4.5 10.0 19P/Borrelly MPEC 2024-YC7 +0021P 2025 03 25.3579 1.008949 0.711046 172.9342 195.3305 32.0499 20250607 9.0 6.0 21P/Giacobini-Zinner MPEC 2024-YC7 +0022P 2028 07 12.9693 1.509714 0.557815 162.9650 120.2190 4.8170 20250607 3.0 10.4 22P/Kopff MPEC 2024-L77 +0023P 2059 05 31.2679 0.464379 0.972585 129.9760 311.1868 19.4644 20250607 10.0 6.0 23P/Brorsen-Metcalf MPC 14747 +0024P 2026 01 8.3018 1.183862 0.708188 58.4005 78.3675 11.5063 20250607 6.5 14.0 24P/Schaumasse MPC110085 +0025D 2025 05 11.4149 1.448317 0.550412 244.7972 279.9717 2.8087 20250607 12.5 6.0 25D/Neujmin 2 NK 378 +0026P 2023 12 25.3161 1.083442 0.640602 2.1243 211.5319 22.4368 20250607 12.0 16.0 26P/Grigg-Skjellerup MPEC 2024-TP3 +0027P 2011 08 2.7004 0.737593 0.919644 195.8471 250.7051 29.4349 20250607 12.0 8.0 27P/Crommelin MPC 78188 +0028P 2021 03 10.2668 1.586807 0.772691 347.4510 346.4105 14.2930 20250607 8.5 6.0 28P/Neujmin MPEC 2025-A40 +0029P 2019 05 2.0054 5.794510 0.043299 52.0914 312.4038 9.3559 20250607 4.0 4.0 29P/Schwassmann-Wachmann MPC184415 +0030P 2024 08 17.2293 1.813881 0.514396 9.5134 117.2331 8.0533 20250607 9.5 6.0 30P/Reinmuth MPC184416 +0031P 2028 03 18.8222 3.412669 0.193417 17.9084 114.1133 4.5497 20250607 5.0 8.0 31P/Schwassmann-Wachmann MPEC 2025-A40 +0032P 2024 04 20.6863 2.025139 0.555304 54.7061 54.5323 9.9200 20250607 6.5 8.0 32P/ComasSola MPC184416 +0033P 2024 11 10.8875 2.242484 0.451957 20.2566 66.2801 22.2940 20250607 10.0 12.0 33P/Daniel MPC184416 +0034D 2026 08 25.2219 1.213842 0.758079 218.0338 57.8627 10.5825 20250607 9.0 4.0 34D/Gale 9, 314 +0035P 2092 04 9.189 0.73346 0.97430 29.215 356.190 64.541 20250607 9.0 4.0 35P/Herschel-Rigollet 15, 452 +0036P 2028 11 4.9679 3.030774 0.268144 201.2039 181.8272 9.9460 20250607 8.5 6.0 36P/Whipple MPEC 2023-RF3 +0037P 2024 10 11.2372 1.617830 0.532663 330.0613 314.5487 8.9478 20250607 10.5 4.8 37P/Forbes MPC184416 +0038P 2018 11 13.8409 1.579529 0.859776 359.5908 77.8610 18.4144 20250607 3.5 12.0 38P/Stephan-Oterma MPEC 2024-YC7 +0039P 2023 09 7.7233 5.761905 0.172443 114.9963 289.2023 1.7222 20250607 7.0 6.0 39P/Oterma MPEC 2024-AF0 +0040P 2025 11 11.9064 1.823661 0.631575 52.0369 128.8986 11.6400 20250607 5.5 12.0 40P/Vaisala MPC184416 +0041P 2028 02 16.1461 1.050959 0.659640 62.2169 140.9720 9.2162 20250607 10.0 16.0 41P/Tuttle-Giacobini-Kresak MPEC 2023-SQ0 +0042P 2026 01 14.9655 2.029513 0.584065 147.1333 150.1599 3.9883 20250607 13.0 6.0 42P/Neujmin MPC184416 +0043P 2025 08 4.7053 2.442863 0.436248 223.8089 243.9939 9.3320 20250607 8.0 6.0 43P/Wolf-Harrington MPC184416 +0044P 2022 04 22.0818 2.114044 0.426744 57.9942 286.4219 5.8959 20250607 8.3 6.0 44P/Reinmuth MPEC 2024-F34 +0045P 2027 08 31.4858 0.557510 0.817617 327.9500 87.6862 4.3240 20250607 13.5 8.0 45P/Honda-Mrkos-Pajdusakova MPEC 2022-O01 +0046P 2024 05 19.0964 1.055235 0.658722 356.3416 82.1618 11.7497 20250607 14.0 6.0 46P/Wirtanen MPEC 2024-F91 +0047P 2025 10 27.9737 2.807476 0.318199 357.9098 356.8826 13.0385 20250607 1.0 11.2 47P/Ashbrook-Jackson MPC184416 +0048P 2025 03 2.6409 2.006586 0.426549 216.7739 110.0640 12.2017 20250607 10.0 6.0 48P/Johnson MPC184416 +0049P 2025 04 10.6074 1.431337 0.599026 332.9278 118.7910 19.0597 20250607 11.3 4.4 49P/Arend-Rigaux MPC184416 +0050P 2024 05 12.6306 1.921926 0.529703 49.3128 355.1447 19.1006 20250607 9.5 6.0 50P/Arend MPC184417 +0051P 2022 09 30.6770 1.694164 0.542783 269.2338 83.6588 5.4264 20250607 10.0 8.0 51P/Harrington MPEC 2023-J29 +0051P a 2022 10 3.2574 1.694015 0.542976 83.6431 269.2296 5.4262 20250607 10.0 8.0 51P-A/Harrington NK 3014 +0051P d 2022 10 1.1005 1.693843 0.542913 269.2519 83.6471 5.4269 20250607 16.0 8.0 51P-D/Harrington MPEC 2023-J29 +0052P 2021 10 6.2452 1.772338 0.541094 139.6148 336.7546 10.2378 20250607 13.5 6.0 52P/Harrington-Abell MPEC 2023-XP6 +0053P 2028 12 26.2057 2.449648 0.549643 134.3400 148.8521 6.6025 20250607 7.7 4.8 53P/VanBiesbroeck MPEC 2023-TM6 +0054P 2024 09 4.1482 2.172005 0.427033 2.0852 358.7511 6.0620 20250607 10.0 6.0 54P/deVico-Swift-NEAT MPEC 2024-YC7 +0055P 2031 05 22.5756 0.974524 0.905729 172.4929 235.4117 162.4843 20250607 9.0 4.0 55P/Tempel-Tuttle MPC 31070 +0056P 2027 12 19.4530 2.489320 0.508355 44.2185 345.8894 8.1549 20250607 8.5 6.0 56P/Slaughter-Burnham MPEC 2023-TM6 +0057P 2028 03 4.7859 1.716050 0.501283 115.0582 188.7423 2.8532 20250607 12.5 6.0 57P/duToit-Neujmin-Delporte MPEC 2024-DC6 +0058P 2028 09 4.2999 1.384169 0.661669 200.5826 159.0405 13.0878 20250607 15.5 6.0 58P/Jackson-Neujmin MPEC 2024-A43 +0059P 2028 03 15.4544 2.342473 0.477029 127.6677 312.7288 9.3558 20250607 7.0 6.0 59P/Kearns-Kwee MPEC 2023-A50 +0060P 2025 07 20.6135 1.645697 0.533836 216.9163 267.3963 3.5799 20250607 11.5 6.0 60P/Tsuchinshan MPC182887 +0061P 2022 10 23.4170 2.129156 0.423078 221.7082 162.9615 5.9969 20250607 6.0 10.0 61P/Shajn-Schaldach MPEC 2024-JU4 +0062P 2023 12 25.1982 1.265130 0.624709 47.3311 68.6656 4.7370 20250607 8.0 10.0 62P/Tsuchinshan MPC182887 +0063P 2026 07 6.2784 1.973367 0.650784 168.7961 357.7693 19.6200 20250607 10.5 6.0 63P/Wild MPC 84320 +0064P 2028 03 31.0128 1.387139 0.688440 97.3344 299.7732 8.9538 20250607 9.5 12.0 64P/Swift-Gehrels MPEC 2024-A43 +0065P 2025 06 16.4811 2.926255 0.248143 213.6757 61.9757 9.1753 20250607 5.0 6.0 65P/Gunn MPC184417 +0066P 2018 05 12.7648 1.305334 0.784969 257.3858 21.8372 18.6450 20250607 15.0 4.0 66P/duToit MPEC 2021-F20 +0067P 2028 04 9.0821 1.211062 0.649841 22.2106 36.3149 3.8685 20250607 11.0 4.0 67P/Churyumov-Gerasimenko MPEC 2024-C04 +0068P 2030 11 27.2994 1.807824 0.635780 153.2232 175.0913 11.0995 20250607 12.6 4.0 68P/Klemola MPEC 2023-HD1 +0069P 2026 11 12.3461 2.271254 0.414690 343.4962 104.8080 22.0613 20250607 9.5 12.0 69P/Taylor MPEC 2024-C04 +0070P 2028 11 20.8534 2.003882 0.454791 1.7925 119.2353 6.6030 20250607 11.0 6.0 70P/Kojima MPEC 2023-VM5 +0071P 2023 01 21.7233 1.627075 0.487386 210.3763 59.2535 9.3047 20250607 9.8 6.0 71P/Clark MPEC 2024-YC7 +0072P 2023 06 15.5820 0.782510 0.818342 346.7424 26.7204 10.9440 20250607 17.5 10.0 72P/Denning-Fujikawa MPEC 2023-VM5 +0073P 2027 12 11.6478 0.848301 0.719672 206.8065 60.6725 7.5519 20250607 11.5 6.0 73P/Schwassmann-Wachmann MPEC 2023-RF3 +0073P b 2028 01 22.2993 0.933166 0.696318 75.1585 193.1964 10.6840 20250607 9.0 4.0 73P-B/Schwassmann-Wachmann B NK 1613 +0073P c 2028 01 16.9506 0.933326 0.696126 75.0145 193.3767 10.6964 20250607 9.0 4.0 73P-C/Schwassmann-Wachmann NK 2710 +0073P e 2028 02 3.7712 0.933327 0.696660 75.4505 192.8710 10.6521 20250607 9.0 4.0 73P-E/Schwassmann-Wachmann NK 934 +0073P g 2006 06 8.096 0.93920 0.69330 198.772 69.909 11.388 9.0 4.0 73P-G/Schwassmann-Wachmann MPC 56796 +0073P h 2006 06 8.281 0.93918 0.69330 198.778 69.903 11.389 9.0 4.0 73P-H/Schwassmann-Wachmann MPC 56796 +0073P j 2006 06 8.141 0.93966 0.69330 198.673 69.983 11.386 9.0 4.0 73P-J/Schwassmann-Wachmann MPC 56796 +0073P k 2006 06 8.224 0.93903 0.69330 198.809 69.881 11.390 9.0 4.0 73P-K/Schwassmann-Wachmann MPC 56797 +0073P l 2006 06 8.340 0.93914 0.69330 198.772 69.911 11.388 9.0 4.0 73P-L/Schwassmann-Wachmann MPC 56797 +0073P m 2006 06 8.262 0.93912 0.69330 198.787 69.895 11.389 9.0 4.0 73P-M/Schwassmann-Wachmann MPC 56797 +0073P n 2006 06 8.261 0.93920 0.69330 198.754 69.909 11.389 9.0 4.0 73P-N/Schwassmann-Wachmann MPC 56797 +0073P p 2006 06 7.872 0.93917 0.69330 198.783 69.900 11.390 9.0 4.0 73P-P/Schwassmann-Wachmann MPC 56797 +0073P q 2006 06 7.725 0.93941 0.69330 198.717 69.944 11.387 9.0 4.0 73P-Q/Schwassmann-Wachmann MPC 56797 +0073P r 2006 06 8.185 0.93918 0.69330 198.776 69.904 11.388 9.0 4.0 73P-R/Schwassmann-Wachmann MPC 56797 +0073P s 2006 06 8.689 0.98977 0.69330 188.229 77.364 11.127 9.0 4.0 73P-S/Schwassmann-Wachmann MPC 56797 +0073P t 2027 12 9.7896 0.848041 0.719650 206.6988 60.7971 7.6034 20250607 9.0 4.0 73P-T/Schwassmann-Wachmann MPEC 2023-J29 +0073P u 2006 06 9.016 0.93962 0.69330 198.659 69.994 11.384 9.0 4.0 73P-U/Schwassmann-Wachmann MPC 56797 +0073P v 2006 06 8.477 0.91217 0.69330 204.943 65.236 11.651 9.0 4.0 73P-V/Schwassmann-Wachmann MPC 56797 +0073P w 2006 06 8.500 0.93906 0.69330 198.803 69.884 11.390 9.0 4.0 73P-W/Schwassmann-Wachmann MPC 56797 +0073P x 2006 06 8.566 0.93913 0.69330 198.778 69.900 11.388 9.0 4.0 73P-X/Schwassmann-Wachmann MPC 56798 +0073P y 2006 06 8.770 0.93911 0.69330 198.785 69.879 11.391 9.0 4.0 73P-Y/Schwassmann-Wachmann MPC 56798 +0073P z 2006 06 8.309 0.94204 0.69330 198.017 70.493 11.349 9.0 4.0 73P-Z/Schwassmann-Wachmann MPC 56798 +0073P aa 2006 06 9.086 0.93905 0.69330 198.804 69.883 11.390 9.0 4.0 73P-AA/Schwassmann-Wachmann MPC 56798 +0073P ab 2006 06 8.697 0.93906 0.69330 198.792 69.888 11.390 9.0 4.0 73P-AB/Schwassmann-Wachmann MPC 56798 +0073P ac 2006 06 8.693 0.93918 0.69330 198.766 69.914 11.387 9.0 4.0 73P-AC/Schwassmann-Wachmann MPC 56798 +0073P ad 2006 06 8.694 0.94167 0.69330 198.119 70.416 11.355 9.0 4.0 73P-AD/Schwassmann-Wachmann MPC 56798 +0073P ae 2006 06 8.352 0.93910 0.69330 198.790 69.891 11.390 9.0 4.0 73P-AE/Schwassmann-Wachmann MPC 56798 +0073P af 2006 06 6.841 0.94144 0.69330 198.217 70.302 11.356 9.0 4.0 73P-AF/Schwassmann-Wachmann MPC 56798 +0073P ag 2006 06 9.016 0.93921 0.69330 198.724 69.932 11.386 9.0 4.0 73P-AG/Schwassmann-Wachmann MPC 56798 +0073P ah 2006 06 8.628 0.94293 0.69330 197.755 70.695 11.331 9.0 4.0 73P-AH/Schwassmann-Wachmann MPC 56798 +0073P ai 2006 06 8.737 0.93912 0.69330 198.806 69.885 11.392 9.0 4.0 73P-AI/Schwassmann-Wachmann MPC 56798 +0073P aj 2006 06 8.740 0.93930 0.69330 198.663 70.041 11.385 9.0 4.0 73P-AJ/Schwassmann-Wachmann MPC 56799 +0073P ak 2006 06 8.395 0.93924 0.69330 198.822 69.784 11.389 9.0 4.0 73P-AK/Schwassmann-Wachmann MPC 56799 +0073P al 2006 06 8.456 0.93892 0.69330 198.857 69.843 11.395 9.0 4.0 73P-AL/Schwassmann-Wachmann MPC 56799 +0073P am 2006 06 8.266 0.93912 0.69330 198.815 69.876 11.394 9.0 4.0 73P-AM/Schwassmann-Wachmann MPC 56799 +0073P an 2006 06 8.328 0.93906 0.69330 198.820 69.870 11.393 9.0 4.0 73P-AN/Schwassmann-Wachmann MPC 56799 +0073P ao 2006 06 7.808 0.94408 0.69330 197.007 71.286 11.210 9.0 4.0 73P-AO/Schwassmann-Wachmann MPC 56799 +0073P ap 2006 06 6.685 0.93918 0.69330 198.794 69.895 11.393 9.0 4.0 73P-AP/Schwassmann-Wachmann MPC 56799 +0073P aq 2006 06 7.919 0.93920 0.69330 198.770 69.911 11.387 9.0 4.0 73P-AQ/Schwassmann-Wachmann MPC 56799 +0073P ar 2006 06 6.833 0.93937 0.69330 198.722 69.946 11.385 9.0 4.0 73P-AR/Schwassmann-Wachmann MPC 56799 +0073P as 2006 06 6.335 0.93922 0.69330 198.773 69.906 11.392 9.0 4.0 73P-AS/Schwassmann-Wachmann MPC 56799 +0073P at 2006 06 6.228 0.93925 0.69330 198.778 69.901 11.391 9.0 4.0 73P-AT/Schwassmann-Wachmann MPC 56799 +0073P au 2006 06 8.093 0.93929 0.69330 198.744 69.928 11.385 9.0 4.0 73P-AU/Schwassmann-Wachmann MPC 56799 +0073P av 2006 06 6.490 0.93930 0.69330 198.751 69.945 11.388 9.0 4.0 73P-AV/Schwassmann-Wachmann MPC 56800 +0073P aw 2006 06 7.766 0.93947 0.69330 198.673 69.982 11.377 9.0 4.0 73P-AW/Schwassmann-Wachmann MPC 56800 +0073P ax 2006 06 9.533 0.93912 0.69330 198.757 69.915 11.388 9.0 4.0 73P-AX/Schwassmann-Wachmann MPC 56800 +0073P ay 2006 06 8.760 0.93918 0.69330 198.750 69.923 11.385 9.0 4.0 73P-AY/Schwassmann-Wachmann MPC 56800 +0073P az 2006 06 6.515 0.93962 0.69330 198.644 70.002 11.371 9.0 4.0 73P-AZ/Schwassmann-Wachmann MPC 56800 +0073P ba 2006 06 6.436 0.93976 0.69330 198.588 70.042 11.364 9.0 4.0 73P-BA/Schwassmann-Wachmann MPC 56800 +0073P bb 2006 06 7.087 0.93912 0.69330 198.807 69.882 11.395 9.0 4.0 73P-BB/Schwassmann-Wachmann MPC 56800 +0073P bc 2006 06 6.670 0.93922 0.69330 198.778 69.901 11.391 9.0 4.0 73P-BC/Schwassmann-Wachmann MPC 56800 +0073P bd 2006 06 6.417 0.93998 0.69330 198.503 70.085 11.352 9.0 4.0 73P-BD/Schwassmann-Wachmann MPC 56800 +0073P be 2006 06 6.863 0.93902 0.69330 198.861 69.841 11.405 9.0 4.0 73P-BE/Schwassmann-Wachmann MPC 56800 +0073P bf 2006 06 6.992 0.93918 0.69330 198.752 69.908 11.390 9.0 4.0 73P-BF/Schwassmann-Wachmann MPC 56800 +0073P bg 2006 06 8.741 0.93915 0.69330 198.750 69.925 11.384 9.0 4.0 73P-BG/Schwassmann-Wachmann MPC 56800 +0073P bh 2006 06 8.568 0.93874 0.69330 198.947 69.752 11.410 9.0 4.0 73P-BH/Schwassmann-Wachmann MPC 56801 +0073P bi 2006 06 8.639 0.93905 0.69330 198.877 69.819 11.404 9.0 4.0 73P-BI/Schwassmann-Wachmann MPC 56801 +0073P bj 2006 06 8.669 0.93914 0.69330 198.776 69.905 11.389 9.0 4.0 73P-BJ/Schwassmann-Wachmann MPC 56801 +0073P bk 2006 06 8.884 0.93931 0.69330 198.698 69.970 11.379 9.0 4.0 73P-BK/Schwassmann-Wachmann MPC 56801 +0073P bl 2006 06 8.885 0.93923 0.69330 198.739 69.930 11.385 9.0 4.0 73P-BL/Schwassmann-Wachmann MPC 56801 +0073P bm 2006 06 8.938 0.93962 0.69330 198.546 70.086 11.364 9.0 4.0 73P-BM/Schwassmann-Wachmann MPC 56801 +0073P bn 2006 06 8.203 0.93905 0.69330 198.815 69.871 11.398 9.0 4.0 73P-BN/Schwassmann-Wachmann MPC 56801 +0073P bo 2006 06 8.259 0.93913 0.69330 198.765 69.903 11.390 9.0 4.0 73P-BO/Schwassmann-Wachmann MPC 56801 +0073P bp 2006 06 8.302 0.93910 0.69330 198.807 69.881 11.395 9.0 4.0 73P-BP/Schwassmann-Wachmann MPC 56801 +0073P bq 2006 06 8.297 0.93900 0.69330 198.862 69.836 11.404 9.0 4.0 73P-BQ/Schwassmann-Wachmann MPC 56801 +0073P br 2006 06 6.154 0.93921 0.69330 198.774 69.910 11.389 9.0 4.0 73P-BR/Schwassmann-Wachmann MPC 56957 +0073P bs 2006 06 5.831 0.93918 0.69330 198.814 69.885 11.399 9.0 4.0 73P-BS/Schwassmann-Wachmann MPC 56957 +0073P bt 2028 01 20.0279 0.933292 0.696310 75.0745 193.2962 10.6901 20250607 11.5 6.0 73P-BT/Schwassmann-Wachmann MPC106348 +0073P bu 2027 07 2.9875 0.927287 0.675740 73.0148 197.2653 10.8866 20250607 19.0 4.0 73P-BU/Schwassmann-Wachmann MPEC 2022-P18 +0073P bv 2028 01 16.7600 0.863298 0.719679 204.5446 62.0250 7.6840 20250607 19.0 4.0 73P-BV/Schwassmann-Wachmann MPEC 2022-X67 +0073P bw 2022 08 23.8290 0.966540 0.786581 71.6040 193.1064 10.2036 20250607 18.2 4.0 73P-BW/Schwassmann-Wachmann MPEC 2022-R15 +0073P bx 2028 01 2.0078 0.857999 0.719525 205.7595 61.0221 7.4975 20250607 17.5 4.0 73P-BX/Schwassmann-Wachmann MPEC 2023-A50 +0073P by 2027 11 23.1121 0.930864 0.691150 74.6070 194.0425 10.7561 20250607 17.4 4.0 73P-BY/Schwassmann-Wachmann MPEC 2022-R15 +0074P 2026 07 19.0322 4.824717 0.042284 68.1731 53.0564 6.1917 20250607 5.0 6.0 74P/Smirnova-Chernykh MPC184417 +0075D 2027 11 2.4526 1.770046 0.499517 175.5871 269.5527 5.9270 20250607 9.5 6.0 75D/Kohoutek CCO 7 +0076P 2026 04 13.5549 1.596863 0.539454 0.0042 84.1111 30.4885 20250607 8.0 12.0 76P/West-Kohoutek-Ikemura MPEC 2022-K19 +0077P 2023 04 2.8232 2.346824 0.351785 196.6203 14.7501 24.3249 20250607 7.0 8.0 77P/Longmore MPEC 2024-UA9 +0078P 2026 06 25.0255 2.004771 0.463069 192.7555 210.5042 6.2571 20250607 5.5 8.0 78P/Gehrels MPC184417 +0079P 2023 09 30.3288 1.120175 0.619323 281.7545 280.5072 3.1488 20250607 16.0 4.0 79P/duToit-Hartley MPEC 2024-PC5 +0080P 2022 12 8.2169 1.617842 0.597722 339.2746 259.7723 29.9270 20250607 9.0 8.0 80P/Peters-Hartley MPEC 2024-Q20 +0081P 2022 12 15.7903 1.595901 0.537630 41.5508 136.0988 3.2381 20250607 7.0 6.0 81P/Wild MPEC 2024-RQ6 +0082P 2026 11 15.9261 3.624382 0.122850 226.4740 239.2149 1.1294 20250607 15.0 4.0 82P/Gehrels MPC133426 +0083D 2028 12 2.6984 2.146707 0.441439 334.3790 226.2964 17.8309 20250607 9.0 4.0 83D/Russell NK 932 +0084P 2027 02 12.5931 1.719242 0.515728 281.6821 108.1420 7.5527 20250607 9.5 8.0 84P/Giclas MPEC 2020-FB5 +0085D 2020 07 30.3549 1.130926 0.775891 333.0902 65.2964 4.1729 20250607 6.5 8.0 85D/Boethin unp +0086P 2022 02 2.0648 2.323570 0.362807 181.0637 72.0960 15.5067 20250607 11.0 6.0 86P/Wild MPEC 2022-YB4 +0087P 2029 04 1.5167 3.413777 0.216922 51.8896 184.9577 2.6685 20250607 7.2 10.0 87P/Bus MPEC 2020-SI8 +0088P 2026 03 18.7905 1.357669 0.563230 235.8817 56.6687 4.3820 20250607 11.0 6.0 88P/Howell MPC184417 +0089P 2024 03 26.6073 2.222459 0.407483 250.4244 41.3448 12.0714 20250607 11.5 6.0 89P/Russell MPC182887 +0090P 2032 05 16.9647 2.962707 0.510632 29.1868 13.1869 9.6395 20250607 8.5 6.0 90P/Gehrels MPEC 2022-K19 +0091P 2028 10 23.3203 3.072257 0.257381 357.3521 242.4335 16.1982 20250607 7.5 6.0 91P/Russell MPEC 2023-VM5 +0092P 2027 07 15.3941 1.816790 0.660053 163.7807 181.3632 19.4794 20250607 12.0 6.0 92P/Sanguin MPEC 2014-J58 +0093P 2026 05 2.9105 1.688614 0.613962 75.0222 339.5513 12.2092 20250607 9.5 6.0 93P/Lovas MPEC 2024-R10 +0094P 2023 05 21.1754 2.225413 0.365987 92.3751 70.8479 6.1876 20250607 9.0 6.0 94P/Russell MPEC 2024-R10 +0095P 2046 08 14.1935 8.515863 0.378319 339.3547 209.1928 6.9282 20250607 6.5 2.0 95P/Chiron MPC 75717 +0096P 2023 01 31.3213 0.116080 0.961703 14.7370 93.9626 57.5860 20250607 13.0 4.8 96P/Machholz MPC182887 +0096P b 2023 01 31.1868 0.115948 0.961733 94.0147 14.5915 57.5036 20250607 13.0 4.8 96P-B/Machholz MPC106348 +0096P c 2012 07 14.6812 0.123794 0.958898 15.5380 94.3495 58.5311 9.0 4.0 96P-C/Machholz MPC103849 +0097P 2022 02 15.9771 2.575916 0.459958 230.1954 184.0743 17.9384 20250607 5.5 6.0 97P/Metcalf-Brewington MPEC 2024-GJ3 +0098P 2028 05 14.0028 1.638914 0.566579 157.7254 114.5115 10.6452 20250607 9.0 8.0 98P/Takamizawa MPEC 2021-W31 +0099P 2022 04 9.0547 4.699980 0.228745 174.5391 28.0659 4.3391 20250607 4.5 6.0 99P/Kowal MPEC 2024-R10 +0100P 2022 08 10.1800 2.019239 0.411360 181.9266 37.6857 25.5674 20250607 9.0 8.0 100P/Hartley MPEC 2023-OA6 +0101P 2020 01 13.0328 2.352434 0.595620 277.9812 116.1243 5.0485 20250607 10.0 4.8 101P/Chernykh MPEC 2024-R10 +0101P b 2020 01 30.8022 2.357488 0.595831 115.6010 278.5078 5.0502 20250607 9.0 4.0 101P-B/Chernykh MPC105241 +0102P 2028 07 10.7376 2.078137 0.456006 20.6754 339.3963 25.8545 20250607 6.5 8.0 102P/Shoemaker MPEC 2022-C56 +0103P 2023 10 12.4279 1.065232 0.693513 181.3270 219.7565 13.6080 20250607 8.5 8.0 103P/Hartley MPC184417 +0104P 2027 10 12.7835 1.072012 0.665902 227.3022 207.1844 5.7010 20250607 16.0 4.0 104P/Kowal MPEC 2023-G31 +0105P 2025 01 22.7537 2.052079 0.409144 46.3320 192.3939 9.1673 20250607 11.5 6.0 105P/SingerBrewster MPC184417 +0106P 2028 12 11.9614 1.531652 0.593542 353.7969 48.8659 19.5338 20250607 14.0 4.8 106P/Schuster MPEC 2024-R10 +0107P 2026 11 25.5853 0.969083 0.630969 95.5174 266.7278 2.7986 20250607 9.0 4.0 107P/Wilson-Harrington MPEC 2015-M77 +0108P 2028 12 8.2975 1.663382 0.555698 354.5319 50.3013 11.4325 20250607 8.0 12.0 108P/Ciffreo MPEC 2022-P82 +0109P 1992 12 20.6385 0.972799 0.962875 153.2777 139.7040 113.1148 20250607 4.0 6.0 109P/Swift-Tuttle 105, 420 +0110P 2028 08 22.2234 2.453304 0.319215 167.5590 287.4820 11.7114 20250607 1.0 12.0 110P/Hartley MPEC 2023-KD6 +0111P 2021 06 19.7841 3.707913 0.107169 1.4289 89.8101 4.2262 20250607 5.0 8.0 111P/Helin-Roman-Crockett MPC 75718 +0112P 2026 09 21.7990 1.441257 0.590839 21.5501 31.8130 24.2025 20250607 14.0 6.0 112P/Urata-Niijima MPEC 2021-S45 +0113P 2022 06 1.8054 2.144901 0.419678 115.7351 306.6219 5.2876 20250607 13.5 4.0 113P/Spitaler MPEC 2024-JU4 +0114P 2026 09 14.9513 1.571257 0.556139 172.8097 271.0265 18.3039 20250607 11.5 6.0 114P/Wiseman-Skiff MPEC 2023-A50 +0115P 2029 05 24.8501 2.059342 0.517846 120.9150 175.9849 11.6808 20250607 10.5 6.0 115P/Maury MPEC 2023-J29 +0116P 2022 07 16.7383 2.193852 0.370677 173.1590 20.9598 3.6045 20250607 2.5 10.0 116P/Wild MPEC 2024-RQ6 +0117P 2022 07 12.3732 3.075768 0.252846 224.6761 58.8222 8.6809 20250607 2.5 8.0 117P/Helin-Roman-Alu MPC182887 +0118P 2022 11 24.7387 1.829186 0.453806 314.9495 142.0552 10.0915 20250607 12.0 4.0 118P/Shoemaker-Levy MPEC 2024-MB8 +0119P 2022 08 12.4226 2.330826 0.388117 322.2686 104.5429 7.3928 20250607 3.5 8.0 119P/Parker-Hartley MPEC 2024-R10 +0120P 2029 04 4.6780 2.484476 0.374169 36.7831 358.7057 8.4815 20250607 12.0 4.0 120P/Mueller MPEC 2022-CN4 +0121P 2023 06 30.6763 3.732374 0.186710 11.9606 94.1051 20.1621 20250607 6.5 8.0 121P/Shoemaker-Holt MPC184417 +0122P 1995 10 1.6300 0.659529 0.962598 13.0037 79.7417 86.0276 20250607 7.5 5.2 122P/de Vico MPC 75718 +0123P 2026 09 22.2047 2.157258 0.444529 103.9556 45.9010 15.2799 20250607 12.2 4.0 123P/West-Hartley MPEC 2021-F20 +0124P 2026 06 23.6261 1.734320 0.486422 185.1176 359.9889 31.4045 20250607 13.5 2.8 124P/Mrkos MPEC 2024-UQ8 +0125P 2024 03 7.2317 1.526415 0.511989 87.1094 153.1496 9.9858 20250607 13.0 6.0 125P/Spacewatch MPEC 2024-UA9 +0126P 2023 07 5.0519 1.710632 0.696037 356.5607 357.8575 45.8713 20250607 6.0 8.0 126P/IRAS MPEC 2024-JU4 +0127P 2022 08 10.0280 2.215051 0.358764 6.3395 13.6163 14.2955 20250607 11.0 6.0 127P/Holt-Olmstead MPEC 2024-R10 +0128P 2026 07 16.7605 3.037356 0.322369 210.4909 214.3212 4.3709 20250607 8.5 4.0 128P/Shoemaker-Holt MPC 89014 +0129P 2022 12 3.4150 3.925044 0.085923 307.8668 184.8497 3.4414 20250607 11.0 4.0 129P/Shoemaker-Levy MPC184417 +0130P 2024 04 15.2661 1.825040 0.461237 246.3029 70.1805 6.0602 20250607 10.0 6.0 130P/McNaught-Hughes MPC184417 +0131P 2026 02 15.6207 2.407941 0.344760 179.2411 214.1364 7.3618 20250607 11.0 4.0 131P/Mueller MPEC 2025-A40 +0132P 2021 11 12.9507 1.696922 0.564039 216.5083 173.9792 5.3778 20250607 11.0 6.0 132P/Helin-Roman-Alu MPEC 2024-BE0 +0133P 2024 05 10.1023 2.670696 0.155666 131.8701 160.1011 1.3899 20250607 15.4 2.0 133P/Elst-Pizarro MPC 94676 +0134P 2030 01 8.5981 2.600476 0.585473 18.6592 201.9924 4.3331 20250607 11.5 4.0 134P/Kowal-Vavrova MPC 89012 +0135P 2022 04 6.1629 2.685828 0.293491 22.3772 213.0197 6.0630 20250607 7.0 8.0 135P/Shoemaker-Levy MPEC 2024-C04 +0136P 2025 01 3.4368 2.958464 0.293161 225.3159 137.4204 9.4273 20250607 11.0 4.0 136P/Mueller MPC182888 +0137P 2028 07 29.3193 1.931703 0.572981 141.2180 232.9270 4.8598 20250607 11.0 4.0 137P/Shoemaker-Levy MPEC 2023-J29 +0138P 2026 03 24.2998 1.694436 0.531550 95.6874 309.2718 10.0998 20250607 15.0 6.0 138P/Shoemaker-Levy MPEC 2016-U66 +0139P 2027 07 22.7826 3.392889 0.248310 165.9764 242.1800 2.3374 20250607 9.5 4.0 139P/Vaisala-Oterma MPEC 2020-HN5 +0140P 2031 10 5.4681 1.954760 0.695192 172.1562 343.3736 3.6971 20250607 11.5 6.0 140P/Bowell-Skiff MPEC 2015-E14 +0141P 2026 04 22.9724 0.807385 0.735894 153.6439 241.7761 13.9618 20250607 12.0 12.0 141P/Machholz MPEC 2024-R10 +0141P a 2026 04 23.3368 0.807389 0.735912 241.9272 153.5044 13.9416 20250607 12.0 12.0 141P-A/Machholz MPEC 2015-KD9 +0141P b 2026 04 15.3546 0.807689 0.735673 241.8162 153.5804 13.9856 20250607 9.0 4.0 141P-B/Machholz MPC 24216 +0141P d 2026 05 18.5845 0.806740 0.736858 242.1757 153.2303 13.8334 20250607 9.0 4.0 141P-D/Machholz MPC 37026 +0141P e 1994 09 19.2500 0.752528 0.750233 149.2667 246.1856 12.8152 9.0 4.0 141P-E/Machholz MPEC 2015-R12 +0141P f 1994 09 19.1963 0.752528 0.750009 149.2374 246.1881 12.7898 9.0 4.0 141P-F/Machholz MPEC 2015-R12 +0141P g 1994 09 19.1048 0.752528 0.749643 149.0784 246.3146 12.8259 9.0 4.0 141P-G/Machholz MPEC 2015-R12 +0141P h 2015 08 24.3866 0.761562 0.746822 149.4500 246.0900 12.8431 18.5 4.0 141P-H/Machholz MPC 95735 +0141P i 2026 04 13.6078 0.807222 0.735141 241.9370 153.4592 13.9417 20250607 17.5 4.0 141P-I/Machholz MPEC 2022-SU8 +0142P 2021 05 11.3105 2.521898 0.495968 174.0641 175.9595 12.2448 20250607 8.5 6.0 142P/Ge-Wang MPEC 2024-C04 +0143P 2026 12 25.8368 2.947370 0.383193 304.3260 242.5111 5.4508 20250607 13.5 2.0 143P/Kowal-Mrkos MPC182888 +0144P 2024 01 25.8202 1.399434 0.634966 216.3592 242.9246 3.9317 20250607 8.5 8.0 144P/Kushida MPEC 2024-YC7 +0145P 2026 01 31.9034 1.889824 0.542473 10.3792 26.7938 11.2765 20250607 13.5 4.0 145P/Shoemaker-Levy MPC108598 +0146P 2024 08 5.4182 1.418684 0.647579 317.0449 53.3588 23.1180 20250607 15.0 4.0 146P/Shoemaker-LINEAR MPC184418 +0147P 2023 12 7.4820 3.160491 0.211801 348.6036 91.6674 2.3115 20250607 14.0 4.0 147P/Kushida-Muramatsu MPEC 2024-UQ8 +0148P 2022 06 14.2794 1.627680 0.550388 8.0803 89.1952 3.6589 20250607 16.0 2.0 148P/Anderson-LINEAR MPEC 2024-JU4 +0149P 2026 12 16.5025 2.790002 0.324446 30.2359 143.7594 34.2352 20250607 8.0 8.0 149P/Mueller MPEC 2023-J29 +0150P 2024 03 12.5262 1.745410 0.549214 246.1239 272.0557 18.5484 20250607 13.5 4.0 150P/LONEOS MPEC 2024-NE4 +0151P 2029 08 17.9186 2.464821 0.572554 216.1557 143.1233 4.7254 20250607 10.0 6.0 151P/Helin MPEC 2022-K19 +0152P 2022 01 13.3702 3.109256 0.306872 164.4435 91.7755 9.8798 20250607 11.5 4.0 152P/Helin-Lawrence MPC182888 +0153P 2002 03 12.2852 0.496820 0.990158 34.2224 93.8008 28.4977 20250607 9.0 4.0 153P/Ikeya-Zhang MPC 46101 +0154P 2024 06 13.2145 1.552474 0.676277 47.9314 342.9957 17.6381 20250607 2.5 12.0 154P/Brewington MPC184418 +0155P 2019 11 17.3735 1.789732 0.727668 14.5310 97.1568 6.4107 20250607 10.0 4.8 155P/Shoemaker MPEC 2022-YN2 +0156P 2027 04 30.4841 1.333572 0.614870 0.5258 35.3344 17.2610 20250607 15.5 2.0 156P/Russell-LINEAR MPEC 2023-J29 +0157P 2022 09 10.1596 1.572474 0.556799 155.1773 287.4983 12.4243 20250607 10.0 4.0 157P/Tritton MPEC 2024-D33 +0157P b 2028 02 25.6658 1.551697 0.499895 287.2084 153.8813 12.4252 20250607 15.7 4.0 157P-B/Tritton MPEC 2022-VC5 +0158P 2022 09 4.9627 5.016906 0.117410 229.2637 124.4475 7.4482 20250607 9.0 4.0 158P/Kowal-LINEAR MPC182888 +0159P 2018 05 26.1980 3.615253 0.382550 4.7263 54.9389 23.4836 20250607 10.0 4.0 159P/LONEOS MPEC 2024-DC6 +0160P 2027 04 7.2141 1.795322 0.525010 12.7801 333.3492 15.5950 20250607 15.5 2.0 160P/LINEAR MPEC 2022-K19 +0161P 2026 11 27.9684 1.266729 0.835823 47.0675 1.5145 95.8181 20250607 8.5 6.0 161P/Hartley-IRAS MPC 75721 +0162P 2026 05 17.8212 1.289487 0.582940 357.2370 30.8767 27.5535 20250607 12.0 4.0 162P/SidingSpring MPEC 2025-A40 +0163P 2026 11 23.9149 2.055501 0.453480 349.6342 102.0725 12.7212 20250607 14.5 4.0 163P/NEAT MPEC 2021-S45 +0164P 2025 05 27.4029 1.675101 0.541313 325.9523 88.2690 16.2774 20250607 11.0 4.0 164P/Christensen MPEC 2024-TD8 +0165P 2000 06 13.8547 6.783297 0.619226 125.8783 0.6769 15.9084 20250607 11.5 2.0 165P/LINEAR MPC 75721 +0166P 2002 06 6.5566 8.541915 0.382884 321.8517 64.4387 15.3778 20250607 5.5 4.0 166P/NEAT MPC 75722 +0167P 2001 03 27.1522 11.898661 0.267848 344.4500 295.8361 19.0752 20250607 9.5 2.0 167P/CINEOS MPEC 2023-J29 +0168P 2026 05 26.2446 1.358408 0.621272 15.1000 355.3888 21.5949 20250607 15.5 4.0 168P/Hergenrother MPEC 2023-J29 +0169P 2026 09 21.3273 0.603920 0.768047 218.1215 176.0585 11.2869 20250607 16.0 2.0 169P/NEAT MPC184418 +0170P 2023 04 15.7014 2.913968 0.305265 224.7384 142.6378 10.1295 20250607 12.0 4.0 170P/Christensen MPC184418 +0171P 2025 09 25.0455 1.766303 0.502770 347.0896 101.7000 21.9508 20250607 13.5 4.0 171P/Spahr MPC102102 +0172P 2025 11 2.5261 3.358145 0.204898 208.8955 30.8826 11.2231 20250607 13.0 4.0 172P/Yeung MPC184418 +0173P 2021 12 17.8454 4.215990 0.262369 29.2903 100.3460 16.4934 20250607 7.5 4.0 173P/Mueller MPEC 2023-N01 +0174P 2015 04 20.0111 5.865233 0.454848 163.4309 173.3387 4.3409 20250607 9.4 2.0 174P/Echeclus MPC 92985 +0175P 2026 09 2.9999 2.303115 0.376034 74.6824 109.8170 4.9273 20250607 14.0 4.0 175P/Hergenrother MPC114608 +0176P 2022 11 19.8242 2.582357 0.191833 34.4714 345.6320 0.2312 20250607 15.1 2.0 176P/LINEAR MPC 89015 +0177P 2006 08 30.1704 1.121708 0.954235 60.7589 271.8625 31.0065 20250607 15.0 4.0 177P/Barnard MPEC 2020-L06 +0178P 2027 06 21.3903 1.880757 0.482287 297.9618 102.7847 11.0925 20250607 13.5 4.0 178P/Hug-Bell MPEC 2024-R10 +0179P 2022 05 31.8463 4.123731 0.305425 297.2135 115.5083 19.8900 20250607 2.5 8.0 179P/Jedicke MPEC 2024-EF7 +0180P 2023 07 12.1366 2.499272 0.353827 94.6044 84.5589 16.8619 20250607 11.0 4.0 180P/NEAT MPEC 2024-F34 +0181P 2022 01 8.2830 1.164514 0.699801 336.2927 35.4405 17.4744 20250607 11.5 4.0 181P/Shoemaker-Levy MPC 89012 +0182P 2027 06 5.3774 0.990976 0.663934 54.2080 72.4549 16.2309 20250607 18.0 4.0 182P/LONEOS MPEC 2024-UQ8 +0183P 2027 09 16.5050 4.224695 0.102658 162.7099 3.5479 18.7278 20250607 12.5 2.0 183P/Korlevic-Juric MPEC 2024-VJ2 +0184P 2028 03 23.8107 1.711079 0.549810 186.5614 173.2678 4.5700 20250607 13.5 4.0 184P/Lovas MPEC 2020-W26 +0185P 2023 07 12.7923 0.931716 0.699416 181.9200 214.1225 14.0099 20250607 15.0 4.0 185P/Petriew MPEC 2024-F91 +0186P 2029 08 25.1242 4.254476 0.123834 268.4981 325.8854 28.6548 20250607 7.5 4.0 186P/Garradd MPEC 2022-X67 +0187P 2028 02 3.9606 3.840235 0.156087 131.6378 109.8449 13.6673 20250607 9.0 4.0 187P/LINEAR MPEC 2020-SI8 +0188P 2026 04 13.2649 2.546204 0.416705 26.8280 358.9140 10.5247 20250607 11.5 4.0 188P/LINEAR-Mueller MPEC 2023-J29 +0189P 2027 09 13.5794 1.203548 0.590621 16.1831 281.6845 20.1200 20250607 19.0 4.0 189P/NEAT MPEC 2022-QD9 +0190P 2024 12 24.1533 2.019409 0.522666 50.5502 335.4758 2.1747 20250607 13.0 4.0 190P/Mueller MPC182889 +0191P 2028 02 29.6475 2.238640 0.385137 284.2680 98.1790 8.8395 20250607 13.0 4.0 191P/McNaught MPEC 2024-TD8 +0192P 2024 05 24.5066 1.462848 0.773402 313.0401 51.5815 24.5800 20250607 15.0 4.0 192P/Shoemaker-Levy MPC182889 +0193P 2028 06 1.4387 2.174171 0.392609 8.1166 335.1861 10.6791 20250607 14.0 4.0 193P/LINEAR-NEAT MPEC 2024-R10 +0194P 2024 02 4.3188 1.800038 0.563391 128.6173 349.5116 11.8035 20250607 16.0 4.0 194P/LINEAR MPEC 2024-GJ3 +0195P 2025 08 5.6118 4.440568 0.310949 250.5995 243.0986 36.4168 20250607 8.5 4.0 195P/Hill MPC184418 +0196P 2022 10 29.1836 2.178953 0.427533 12.1370 24.1242 19.2950 20250607 13.5 4.0 196P/Tichy MPEC 2024-GJ3 +0197P 2027 11 20.6129 1.107031 0.619279 189.9473 66.2028 25.3240 20250607 16.5 2.0 197P/LINEAR MPEC 2023-UR6 +0198P 2025 10 7.1122 1.994799 0.444656 69.0495 358.4690 1.3400 20250607 12.5 4.0 198P/ODAS MPEC 2024-VJ2 +0199P 2023 08 7.3568 2.910924 0.504415 191.7635 92.3438 24.9392 20250607 10.0 4.0 199P/Shoemaker MPEC 2024-Q20 +0200P 2030 08 6.2574 3.312886 0.331172 134.3852 234.8103 12.0951 20250607 9.0 4.0 200P/Larsen MPEC 2022-C56 +0201P 2027 07 20.1277 1.216021 0.637512 19.8020 41.5254 5.7371 20250607 14.0 4.0 201P/LONEOS MPC 93588 +0202P 2024 05 17.2938 3.069940 0.251079 274.4959 177.3005 2.1418 20250607 13.5 4.0 202P/Scotti MPC182889 +0203P 2030 04 8.8221 3.191439 0.316385 154.9356 290.2218 2.9760 20250607 14.5 2.0 203P/Korlevic MPEC 2025-A40 +0204P 2022 11 17.2747 1.834082 0.488286 356.7280 108.4733 6.5979 20250607 14.0 4.0 204P/LINEAR-NEAT MPEC 2024-JU4 +0205P 2028 09 13.5869 1.533512 0.567187 154.1547 179.6235 15.3004 20250607 13.0 4.0 205P/Giacobini MPEC 2023_O39 +0206P 2027 09 12.9880 1.567174 0.551138 189.5764 202.3418 33.6176 20250607 19.0 4.0 206P/Barnard-Boattini MPC 75725 +0207P 2024 01 31.8681 0.938406 0.758524 273.0274 198.1389 10.1986 20250607 16.0 4.0 207P/NEAT MPEC 2024-NE4 +0208P 2024 08 24.2113 2.529177 0.374103 310.7650 36.3327 4.4113 20250607 12.5 4.0 208P/McMillan MPC182889 +0209P 2024 07 14.4925 0.964175 0.674029 152.4816 62.7647 21.2828 20250607 17.0 2.0 209P/LINEAR MPEC 2024-TD8 +0210P 2025 11 22.7191 0.524456 0.834072 345.9167 93.8249 10.2819 20250607 13.5 4.0 210P/Christensen MPC105242 +0211P 2022 10 5.1555 2.326375 0.344481 4.3500 117.1009 18.9246 20250607 12.5 4.0 211P/Hill MPEC 2024-JU4 +0212P 2024 04 25.1487 1.612888 0.586754 14.0596 97.9719 22.1490 20250607 17.0 2.0 212P/NEAT MPEC 2024-GJ3 +0213P 2023 11 13.3326 1.981627 0.409641 6.4763 310.9338 10.4233 20250607 10.5 4.0 213P/VanNess MPC184418 +0213P b 2023 11 13.2013 1.981984 0.409514 6.4955 310.9302 10.4227 20250607 17.0 4.0 213P-B/Van Ness MPEC 2025-GB9 +0213P c 2023 11 12.3629 1.981014 0.409529 312.0709 5.2771 10.3509 20250607 17.5 4.0 213P-C/Van Ness MPC 76570 +0214P 2022 09 26.3643 1.857939 0.486262 190.1204 348.2119 15.1927 20250607 13.0 4.0 214P/LINEAR MPC 92986 +0215P 2028 11 24.3165 3.620663 0.164936 262.2519 56.6780 10.5763 20250607 11.0 4.0 215P/NEAT MPC184418 +0216P 2024 01 6.9898 2.126974 0.449009 151.7693 359.7818 9.0616 20250607 13.0 4.0 216P/LINEAR MPEC 2024-N80 +0217P 2025 05 24.9443 1.226374 0.689075 247.0363 125.3714 12.8655 20250607 12.0 4.0 217P/LINEAR MPC184418 +0218P 2026 03 3.8636 1.129972 0.630929 61.4031 174.6836 2.7263 20250607 16.0 4.0 218P/LINEAR MPEC 2022-K19 +0219P 2024 02 15.0848 2.355846 0.355752 107.9586 230.9019 11.5176 20250607 11.0 4.0 219P/LINEAR MPC182889 +0220P 2026 06 14.1438 1.558894 0.500395 180.5839 150.0915 8.1209 20250607 15.0 4.0 220P/McNaught MPEC 2024-A43 +0221P 2028 04 2.8350 1.621531 0.521280 41.4818 226.9766 10.9095 20250607 14.5 4.0 221P/LINEAR MPEC 2022-UY9 +0222P 2024 05 12.8887 0.826010 0.714804 346.2749 6.7547 5.0973 20250607 20.0 4.0 222P/LINEAR MPC 92277 +0223P 2027 07 24.7596 2.427373 0.416254 37.9819 346.7057 27.0059 20250607 12.0 4.0 223P/Skiff MPEC 2023-A50 +0224P 2022 09 30.1513 2.049091 0.405571 16.8136 40.0413 13.3015 20250607 15.5 4.0 224P/LINEAR-NEAT MPEC 2024-L77 +0225P 2023 08 7.8609 1.319774 0.638165 3.9063 14.2106 21.3614 20250607 18.0 4.0 225P/LINEAR MPEC 2024-F91 +0226P 2023 12 27.0656 1.773971 0.528864 341.0320 54.0132 44.0449 20250607 12.5 4.0 226P/Pigott-LINEAR-Kowalski MPEC 2024-MB8 +0227P 2024 03 8.3221 1.623605 0.527698 105.5931 36.8025 7.5073 20250607 16.5 2.0 227P/Catalina-LINEAR MPEC 2024-R10 +0228P 2028 09 5.1280 3.423857 0.177397 114.7985 30.9551 7.9156 20250607 14.1 4.0 228P/LINEAR MPEC 2022-HC2 +0229P 2025 03 5.7996 2.440390 0.378008 224.2231 157.8807 26.0965 20250607 13.0 4.0 229P/Gibbs MPC182889 +0230P 2028 08 20.4601 1.570485 0.545455 313.5802 106.9269 15.4721 20250607 13.0 4.0 230P/LINEAR MPC184419 +0231P 2027 08 4.7040 3.086582 0.240024 43.7267 132.7826 12.2723 20250607 14.5 2.0 231P/LINEAR-NEAT MPEC 2023-SQ0 +0232P 2028 09 20.5806 2.967638 0.336109 53.2986 56.0109 14.6429 20250607 11.5 4.0 232P/Hill MPC112394 +0233P 2026 01 8.1407 1.776702 0.412971 27.0258 74.8974 11.2889 20250607 15.0 4.0 233P/La Sagra MPEC 2021-N06 +0234P 2024 10 23.6852 2.820910 0.257280 357.4457 179.5649 11.5337 20250607 12.0 4.0 234P/LINEAR MPC184419 +0235P 2025 12 22.6035 1.978073 0.426123 352.1610 200.1786 9.8125 20250607 12.0 4.0 235P/LINEAR MPC184419 +0236P 2025 02 3.8327 1.828122 0.509273 119.4267 245.5692 16.3554 20250607 14.0 4.0 236P/LINEAR MPEC 2024-P23 +0237P 2023 05 14.4249 1.995252 0.432681 25.5322 245.3579 14.0114 20250607 14.5 2.0 237P/LINEAR MPC182890 +0238P 2028 01 24.0320 2.373692 0.250615 324.2657 51.6485 1.2637 20250607 14.5 4.0 238P/Read MPEC 2024-L77 +0239P 2028 06 17.6631 1.644945 0.631495 220.3823 255.9373 11.3067 20250607 17.5 2.0 239P/LINEAR MPEC 2021-F20 +0240P 2025 12 19.9922 2.121690 0.450335 352.0749 74.9134 23.5371 20250607 11.0 4.0 240P/NEAT MPEC 2024-YC7 +0241P 2021 07 26.1985 1.921092 0.610144 111.6127 305.4186 21.0948 20250607 13.5 4.0 241P/LINEAR MPEC 2022-J42 +0242P 2024 12 23.3627 3.971675 0.282836 244.9766 180.2471 32.4231 20250607 8.0 4.0 242P/Spahr MPC184419 +0243P 2026 02 25.5309 2.448047 0.360311 283.7011 87.6477 7.6441 20250607 12.5 4.0 243P/NEAT MPEC 2022-K19 +0244P 2022 11 20.0911 3.924390 0.199835 93.5046 354.0076 2.2576 20250607 9.0 4.0 244P/Scotti MPEC 2024-L77 +0245P 2026 03 31.1959 2.205471 0.455804 316.5013 316.8853 21.1714 20250607 14.0 4.0 245P/WISE MPEC 2022-CN4 +0246P 2029 10 20.8243 3.349306 0.220436 185.4957 74.2175 17.4879 20250607 10.5 4.0 246P/NEAT MPEC 2024-YC7 +0247P 2026 10 25.9558 1.484153 0.625583 47.5037 53.9871 13.6581 20250607 16.5 2.0 247P/LINEAR MPEC 2021-F20 +0248P 2025 09 14.9263 2.157756 0.639286 209.9803 207.8066 6.3520 20250607 14.0 4.0 248P/Gibbs MPC 75730 +0249P 2025 02 1.6973 0.499542 0.819377 65.7503 239.0417 8.3848 20250607 15.5 4.0 249P/LINEAR MPEC 2022-YN2 +0250P 2025 05 16.7319 2.272327 0.398374 45.7061 73.3031 13.1521 20250607 14.5 4.0 250P/Larson MPC182890 +0251P 2024 02 13.1500 1.741149 0.504214 31.1929 219.3373 23.3884 20250607 16.5 2.0 251P/LINEAR MPEC 2024-TD8 +0252P 2026 11 7.7416 1.003712 0.671047 343.3749 190.9062 10.4199 20250607 17.5 4.0 252P/LINEAR MPEC 2021-S45 +0253P 2024 10 21.0322 2.026499 0.415181 230.8501 146.8343 4.9449 20250607 14.5 4.0 253P/PANSTARRS MPC182890 +0254P 2020 09 28.4499 3.148687 0.318474 219.7264 129.1793 32.5387 20250607 11.0 4.0 254P/McNaught MPC184419 +0255P 2027 09 25.4980 0.847219 0.712054 186.0449 275.6366 13.4053 20250607 9.0 4.0 255P/Levy NK 2214 +0256P 2023 03 11.9393 2.697564 0.418010 124.0662 81.3247 27.6234 20250607 14.0 2.0 256P/LINEAR MPEC 2024-L77 +0257P 2028 01 1.6961 2.152357 0.428773 117.7268 207.7287 20.2156 20250607 11.5 4.0 257P/Catalina MPEC 2023-A50 +0258P 2029 08 28.8224 3.469190 0.209546 25.6082 126.2360 6.7511 20250607 13.0 4.0 258P/PANSTARRS MPEC 2021-U31 +0259P 2026 08 12.1614 1.804866 0.338733 257.4883 51.3732 15.8982 20250607 15.5 4.0 259P/Garradd MPC106349 +0260P 2026 08 4.9899 1.417605 0.608790 18.4922 349.3050 15.0430 20250607 13.5 4.0 260P/McNaught MPEC 2022-O01 +0261P 2025 12 27.3783 2.014210 0.422809 67.3645 291.0505 6.0733 20250607 14.0 4.0 261P/Larson MPEC 2021-J28 +0262P 2030 12 15.0434 1.264102 0.815979 171.0696 217.8865 29.2496 20250607 13.5 4.0 262P/McNaught-Russell MPC 82322 +0263P 2023 01 30.9050 1.234436 0.594051 35.0217 105.5039 11.5267 20250607 18.0 4.0 263P/Gibbs MPEC 2024-L77 +0264P 2027 03 15.6281 2.657770 0.340392 341.1331 219.1493 25.1457 20250607 13.0 4.0 264P/Larsen MPC114608 +0265P 2021 02 8.6987 1.505233 0.646726 33.5635 342.9219 14.3408 20250607 14.5 4.0 265P/LINEAR MPC 79870 +0266P 2026 12 7.3131 2.325141 0.340932 97.7901 4.9467 3.4283 20250607 14.7 4.0 266P/Christensen MPEC 2021-F20 +0267P 2024 04 24.9239 1.235637 0.614866 114.1983 228.5543 6.1399 20250607 19.5 4.0 267P/LONEOS MPC114608 +0268P 2024 12 18.4801 2.412697 0.474492 0.0167 125.6325 15.6615 20250607 14.0 4.0 268P/Bernardi MPC184419 +0269P 2033 07 11.3513 3.998541 0.433512 225.7307 241.7646 7.0839 20250607 10.0 4.0 269P/Jedicke MPEC 2023-J29 +0270P 2030 08 16.6594 3.522829 0.470186 209.9285 223.0252 2.9248 20250607 8.0 4.0 270P/Gehrels MPC 88332 +0271P 2032 03 21.7304 4.248477 0.395879 36.6173 9.2795 6.8667 20250607 11.0 4.0 271P/van Houten-Lemmon MPC 92277 +0272P 2022 07 17.4948 2.429559 0.455501 27.8897 109.4391 18.0822 20250607 16.0 2.0 272P/NEAT MPEC 2023-D41 +0273P 2012 12 21.9541 0.813485 0.974520 20.1264 320.3843 136.3695 20250607 11.5 4.0 273P/Pons-Gambart MPC 82723 +0274P 2022 04 9.1604 2.450906 0.440240 38.4945 81.3175 15.8206 20250607 13.0 4.0 274P/Tombaugh-Tenagra MPEC 2024-GJ3 +0275P 2026 10 27.9935 1.659053 0.713749 173.8955 348.6850 21.2543 20250607 17.0 4.0 275P/Hermann MPC 81862 +0276P 2024 12 11.0147 3.898631 0.273536 199.3543 211.2699 14.7753 20250607 11.5 4.0 276P/Vorobjov MPC184419 +0277P 2028 07 25.8343 1.902137 0.506401 152.4366 276.2601 16.7929 20250607 15.1 4.0 277P/LINEAR MPEC 2021-F20 +0278P 2027 09 15.1224 1.998232 0.451225 240.3306 12.7683 6.6126 20250607 14.0 4.0 278P/McNaught MPEC 2021-S45 +0279P 2023 04 18.7535 2.142821 0.399448 5.6319 346.0999 5.0529 20250607 14.0 4.0 279P/LaSagra MPEC 2024-A43 +0280P 2023 08 4.3950 2.638607 0.416823 104.6390 131.3778 11.7754 20250607 12.5 4.0 280P/Larsen MPEC 2024-RQ6 +0281P 2023 02 4.2051 4.036817 0.173922 27.0087 87.1662 4.7176 20250607 11.0 4.0 281P/MOSS MPEC 2023-D41 +0282P 2021 10 22.6766 3.440664 0.187654 9.0939 217.6073 5.8137 20250607 13.5 2.0 282P MPC133426 +0283P 2021 09 8.3060 2.127946 0.484975 22.1445 161.1234 14.4684 20250607 16.0 2.0 283P/Spacewatch MPEC 2022-K19 +0284P 2028 10 1.6411 2.301840 0.374316 202.4637 144.2643 11.8530 20250607 13.0 4.0 284P/McNaught MPEC 2024-D33 +0285P 2023 01 11.8208 1.720703 0.618075 178.3851 185.5139 25.0327 20250607 15.0 4.0 285P/LINEAR MPEC 2024-L77 +0286P 2022 05 12.5129 2.321274 0.430899 24.0456 283.5748 17.2245 20250607 14.0 4.0 286P/Christensen MPEC 2024-LE0 +0287P 2023 07 10.5451 3.044328 0.272883 190.4031 138.6932 16.3397 20250607 13.5 4.0 287P/Christensen MPEC 2025-A40 +0288P 2027 06 28.9933 2.441595 0.199617 280.2869 83.1061 3.2383 20250607 16.0 2.0 288P MPC133426 +0289P 2025 04 14.3174 0.954331 0.686460 9.8759 68.8910 5.9002 20250607 19.0 4.0 289P/Blanpain MPEC 2024-O39 +0290P 2029 07 22.2171 2.310011 0.628239 181.8587 302.6723 20.0452 20250607 10.5 4.0 290P/Jager MPC 95214 +0291P 2023 05 3.9973 2.567361 0.433871 173.5637 237.6618 6.3096 20250607 13.0 4.0 291P/NEAT MPEC 2024-YC7 +0292P 2029 03 3.6850 2.500034 0.589886 319.6607 90.8953 24.3225 20250607 12.5 4.0 292P/Li MPEC 2022-K19 +0293P 2027 11 29.0390 2.111547 0.419531 40.9855 78.3612 9.0610 20250607 14.5 4.0 293P/Spacewatch MPEC 2022-L66 +0294P 2025 08 11.1904 1.273051 0.600960 237.5841 309.6004 17.7429 20250607 15.5 4.0 294P/LINEAR MPC184419 +0295P 2026 07 22.7289 2.026083 0.617634 73.0414 7.3806 21.0849 20250607 12.0 4.0 295P/LINEAR MPEC 2022-K19 +0296P 2027 03 20.4442 1.784476 0.485992 350.2391 263.5270 25.3750 20250607 14.0 4.0 296P/Garradd MPEC 2021-N06 +0297P 2027 10 18.3866 2.552024 0.285073 142.3655 92.1754 11.2481 20250607 15.0 4.0 297P/Beshore MPC102956 +0298P 2027 06 24.7748 2.199813 0.386919 100.6203 52.7858 7.8723 20250607 15.0 4.0 298P/Christensen MPC114609 +0299P 2024 04 30.0134 3.155804 0.280934 323.6180 271.5804 10.4690 20250607 11.5 4.0 299P/Catalina-PANSTARRS MPEC 2024-TD8 +0300P 2023 04 11.0102 0.830213 0.692095 222.8782 95.6225 5.6766 20250607 16.0 4.0 300P/Catalina MPEC 2023-VM5 +0301P 2028 05 17.1193 2.379948 0.586227 193.4329 351.0625 10.3288 20250607 13.0 4.0 301P/LINEAR-NEAT MPC 89014 +0302P 2025 03 9.3965 3.288628 0.229338 208.6251 121.7156 6.0357 20250607 12.5 4.0 302P/Lemmon-PANSTARRS MPEC 2024-YC7 +0303P 2026 02 19.9151 2.468158 0.510275 357.0297 347.9490 7.0162 20250607 13.5 4.0 303P/NEAT MPC 92278 +0304P 2026 03 18.1981 1.257203 0.600846 335.2794 58.9379 2.6056 20250607 16.5 4.0 304P/Ory MPEC 2022-K19 +0305P 2024 11 17.1375 1.418282 0.694088 147.4036 240.0993 11.6706 20250607 18.0 4.0 305P/Skiff MPC182890 +0306P 2025 08 1.6474 1.272974 0.592573 0.8972 341.3519 8.3029 20250607 19.0 4.0 306P/LINEAR MPC 92278 +0307P 2028 12 2.2678 1.881082 0.675007 222.2539 158.1133 4.4346 20250607 15.0 4.0 307P/LINEAR MPC 92278 +0308P 2032 04 30.5504 4.197447 0.364151 333.7577 63.0994 4.8521 20250607 13.0 2.0 308P/Lagerkvist-Carsenty MPEC 2022-C56 +0309P 2024 03 28.9491 1.670158 0.618217 49.9181 10.1387 17.0199 20250607 15.0 4.0 309P/LINEAR MPC184419 +0310P 2023 10 23.1355 2.416294 0.422074 31.5182 8.8835 13.1202 20250607 13.5 4.0 310P/Hill MPC182891 +0311P 2024 01 1.8907 1.935914 0.115493 144.2911 279.1689 4.9713 20250607 17.0 4.0 311P/PANSTARRS MPC184419 +0312P 2027 03 15.4912 1.990855 0.426671 207.6982 144.6358 19.7461 20250607 16.0 4.0 312P/NEAT MPEC 2024-NE4 +0313P 2025 12 2.7313 2.421615 0.234469 254.9845 105.9254 10.9810 20250607 15.0 4.0 313P/Gibbs MPEC 2024-N80 +0314P 2016 10 13.6273 4.214850 0.418570 213.8651 267.6230 3.9920 20250607 9.5 4.0 314P/Montani MPC105243 +0315P 2027 11 16.5178 2.359080 0.522084 65.9152 68.6388 17.7349 20250607 11.0 4.0 315P/LONEOS MPEC 2023-J29 +0316P 2024 10 4.6046 3.717662 0.156619 187.0292 245.8867 9.8739 20250607 13.5 4.0 316P/LONEOS-Christensen MPC182891 +0317P 2025 10 30.8645 1.266631 0.572017 334.8876 275.4729 11.9748 20250607 17.5 4.0 317P/WISE MPEC 2020-C98 +0318P 2015 10 22.5560 2.455268 0.673274 313.3025 35.6057 17.8645 20250607 8.5 6.0 318P/McNaught-Hartley MPC102103 +0319P 2022 03 30.5813 1.188413 0.666415 203.5954 111.3650 15.0967 20250607 15.0 4.0 319P/Catalina-McNaught MPC184420 +0320P 2026 06 27.8606 0.975539 0.684898 0.7569 295.9405 4.9028 20250607 20.5 4.0 320P/McNaught MPC 96281 +0321P 2023 10 26.5036 0.046007 0.981005 172.7403 165.0264 20.0548 20250607 20.0 4.0 321P/SOHO MPC105243 +0322P 2023 08 21.1627 0.050350 0.979930 57.0765 351.3451 11.4483 20250607 19.0 4.0 322P/SOHO MPC102103 +0323P 2025 03 14.2315 0.040388 0.983449 353.3260 323.9472 5.2114 20250607 20.0 4.0 323P/SOHO MPC182891 +0323P b 2025 12 16.2395 0.040099 0.986125 353.9663 323.4632 5.4606 20250607 26.0 4.0 323P-B/SOHO MPEC 2024-F21 +0323P c 2025 04 7.1008 0.039790 0.984767 353.2123 324.1881 5.3377 20250607 27.0 4.0 323P-C/SOHO MPEC 2024-F21 +0324P 2026 10 14.7649 2.623998 0.152801 57.4188 270.5691 21.3992 20250607 13.0 4.0 324P/LaSagra MPEC 2021-W31 +0325P 2022 03 24.0978 1.465242 0.587192 344.9151 256.8575 16.8469 20250607 14.0 4.0 325P/Yang-Gao MPEC 2024-LE0 +0326P 2023 12 28.3698 2.761392 0.320498 278.0740 99.7608 2.4737 20250607 13.5 4.0 326P/Hill MPEC 2024-LE0 +0327P 2022 09 1.8680 1.558756 0.562520 185.0403 173.9985 36.2309 20250607 16.0 4.0 327P/VanNess MPEC 2024-M41 +0328P 2024 07 27.9351 1.872486 0.553147 30.6760 341.5489 17.6792 20250607 14.5 4.0 328P/LONEOS-Tucker MPEC 2024-YC7 +0329P 2027 09 25.6045 1.664065 0.678881 343.6018 87.6876 21.7189 20250607 13.5 4.0 329P/LINEAR-Catalina MPC101101 +0330P 2033 09 5.4910 2.973039 0.550571 188.8366 293.0837 15.7400 20250607 12.0 4.0 330P/Catalina MPEC 2023-J29 +0331P 2025 12 24.5831 2.878519 0.041442 185.5961 216.7425 9.7407 20250607 12.0 4.0 331P/Gibbs MPEC 2024-Q20 +0332P 2027 01 19.7205 1.574393 0.489842 152.2975 3.7544 9.3858 20250607 18.0 4.0 332P/Ikeya-Murakami MPEC 2016-K18 +0332P a 2027 01 19.7220 1.574361 0.489850 3.7383 152.3146 9.3856 20250607 9.0 4.0 332P-A/Ikeya-Murakami MPEC 2016-K18 +0332P b 2016 03 17.1650 1.572891 0.489707 152.3711 3.8028 9.3805 19.0 4.0 332P-B/Ikeya-Murakami MPEC 2016-EI8 +0332P c 2027 01 19.6116 1.574327 0.489855 3.7387 152.3058 9.3847 20250607 16.5 4.0 332P-C/Ikeya-Murakami MPEC 2016-K18 +0332P d 2016 03 17.2819 1.572064 0.489778 152.4393 3.7923 9.3761 19.0 4.0 332P-D/Ikeya-Murakami MPEC 2016-ED0 +0332P e 2016 03 17.0610 1.573139 0.489220 152.2825 3.8228 9.3774 21.0 4.0 332P-E/Ikeya-Murakami MPEC 2016-ED0 +0332P f 2016 03 17.8554 1.584174 0.499189 152.8203 3.4757 9.5293 21.0 4.0 332P-F/Ikeya-Murakami MPEC 2016-ED0 +0332P g 2016 03 19.5375 1.549652 0.492004 154.4000 3.6955 9.2523 19.0 4.0 332P-G/Ikeya-Murakami MPEC 2016-ED0 +0332P h 2027 01 20.1452 1.574308 0.489891 3.7384 152.3065 9.3852 20250607 19.0 4.0 332P-H/Ikeya-Murakami MPC100285 +0332P i 2016 03 17.3515 1.573073 0.489555 152.3297 3.8048 9.3791 20.5 2.0 332P-I/Ikeya-Murakami MPEC 2016-ED0 +0332P j 2016 03 17.7739 1.575357 0.494294 152.7712 3.6729 9.4296 20.5 2.0 332P-J/Ikeya-Murakami MPEC 2016-EI8 +0333P 2024 11 29.2982 1.112998 0.736284 26.0208 115.7067 132.0224 20250607 15.0 4.0 333P/LINEAR MPC182891 +0334P 2017 06 4.3958 4.422518 0.351964 90.0699 90.3619 20.3646 20250607 10.5 4.0 334P/NEAT MPEC 2023-J29 +0335P 2022 08 12.5222 1.620968 0.546866 162.3214 330.7916 7.2978 20250607 16.8 4.0 335P/Gibbs MPEC 2023-M14 +0336P 2028 05 14.4625 2.788726 0.446150 308.6902 298.1716 17.8712 20250607 13.5 4.0 336P/McNaught MPC105244 +0337P 2022 06 25.9826 1.726803 0.483226 166.1615 102.1071 16.9967 20250607 17.0 4.0 337P/WISE MPEC 2024-A43 +0338P 2024 08 3.3180 2.287593 0.412786 4.6326 9.7459 25.3761 20250607 12.0 4.0 338P/McNaught MPC182891 +0339P 2023 08 30.9794 1.347015 0.635797 172.6745 27.4580 5.7346 20250607 17.0 4.0 339P/Gibbs MPC101101 +0340P 2025 08 29.2589 3.057947 0.279977 36.0649 291.6595 2.0790 20250607 14.3 4.0 340P/Boattini MPC133426 +0341P 2025 04 22.7088 2.506426 0.415050 312.3622 29.9526 3.7965 20250607 12.5 4.0 341P/Gibbs MPEC 2023-J29 +0342P 2027 02 7.6938 0.051751 0.982981 27.6513 73.3085 11.6901 20250607 9.0 4.0 342P/SOHO MPC101101 +0343P 2029 11 4.6256 2.266022 0.584823 137.6081 257.0545 5.5976 20250607 14.0 4.0 343P/NEAT-LONEOS MPEC 2024-PC5 +0344P 2027 07 24.8358 2.797731 0.423741 140.6245 273.1014 3.4996 20250607 13.0 4.0 344P/Read MPEC 2023-J29 +0345P 2024 08 31.0096 3.139774 0.221345 196.7603 154.5068 2.7280 20250607 12.0 4.0 345P/LINEAR MPEC 2024-TP3 +0346P 2026 08 1.2529 2.216448 0.503910 336.0765 102.4579 22.2194 20250607 14.0 4.0 346P/Catalina MPEC 2022-K19 +0347P 2023 07 19.2503 2.206971 0.386957 98.0936 260.9915 11.7660 20250607 15.0 4.0 347P/PANSTARRS MPEC 2024-RQ6 +0348P 2027 09 19.1383 2.182497 0.307498 135.7760 312.9127 17.7427 20250607 14.0 4.0 348P/PANSTARRS MPEC 2022-ED3 +0349P 2024 05 26.9507 2.509649 0.298594 255.7502 331.7388 5.4892 20250607 14.0 4.0 349P/Lemmon MPEC 2024-LE0 +0350P 2026 03 17.4107 3.694352 0.094709 140.0563 65.2953 7.3655 20250607 14.0 4.0 350P/McNaught MPC184420 +0351P 2025 03 26.1607 3.131866 0.294732 352.5578 283.3862 12.7789 20250607 12.5 4.0 351P/Wiegert-PANSTARRS MPC184420 +0352P 2017 06 18.5716 2.555944 0.615969 309.3709 28.0508 21.0036 20250607 13.2 4.0 352P/Skiff MPEC 2023-J29 +0353P 2026 07 1.4691 2.211773 0.469711 230.4855 121.5095 28.4192 20250607 14.5 4.0 353P/McNaught MPEC 2020-AA5 +0354P 2023 10 14.2523 2.005325 0.124449 132.9363 320.0587 5.2507 20250607 15.5 4.0 354P/LINEAR MPEC 2024-EF7 +0355P 2024 04 1.2457 1.705961 0.507961 336.2591 51.4242 11.0460 20250607 15.5 2.0 355P/LINEAR-NEAT MPEC 2023-CD7 +0356P 2026 06 12.3230 2.674656 0.355868 226.2159 160.7914 9.6419 20250607 14.0 4.0 356P/WISE MPEC 2022-F14 +0357P 2027 10 29.6424 2.512565 0.436012 1.5056 44.5679 6.3126 20250607 15.5 4.0 357P/Hill MPC114609 +0358P 2023 11 9.5161 2.392365 0.239479 299.3321 85.6673 11.0668 20250607 18.0 4.0 358P/PANSTARRS MPEC 2024-EF7 +0359P 2027 08 24.4275 3.142462 0.323116 200.2814 149.7455 10.2618 20250607 13.5 4.0 359P/LONEOS MPC110086 +0360P 2024 10 3.8284 1.851750 0.499394 354.3254 2.1565 24.1054 20250607 19.5 6.0 360P/WISE MPEC 2025-A40 +0361P 2029 06 21.6251 2.764802 0.439527 219.1327 203.2288 13.8976 20250607 12.0 4.0 361P/Spacewatch MPEC 2023-CD7 +0363P 2024 11 13.2231 1.720986 0.518561 340.7629 146.7583 5.3938 20250607 17.5 4.0 363P/Lemmon MPC184420 +0364P 2023 05 12.7369 0.819619 0.717485 212.8214 45.8295 11.8874 20250607 17.0 2.0 364P/PANSTARRS MPEC 2024-M41 +0365P 2023 10 9.5116 1.320420 0.581653 67.4151 86.6558 9.8499 20250607 17.0 4.0 365P/PANSTARRS MPC111775 +0366P 2025 01 30.8881 2.279975 0.348650 152.9939 70.7230 8.8567 20250607 15.0 4.0 366P/Spacewatch MPC114610 +0367P 2025 01 11.5227 2.527941 0.280141 172.6817 58.6609 8.4591 20250607 17.5 2.0 367P/Catalina MPC112395 +0368P 2031 09 23.7580 2.072167 0.625636 118.9858 257.8564 15.4825 20250607 14.0 4.0 368P/NEAT MPC114610 +0369P 2027 12 18.9450 1.944545 0.555899 13.2411 47.2842 10.3194 20250607 15.0 4.0 369P/Hill MPC114610 +0370P 2018 06 12.7357 2.478543 0.615147 356.7862 55.0864 19.4170 20250607 13.0 4.0 370P/NEAT MPEC 2021-F20 +0371P 2027 04 25.9766 2.188217 0.476573 308.5665 67.2837 17.3837 20250607 16.0 4.0 371P/LINEAR-Skiff MPC114610 +0372P 2028 05 24.1762 3.830510 0.151214 325.9547 27.5495 9.5038 20250607 13.5 4.0 372P/McNaught MPEC 2020-K19 +0373P 2026 09 4.9523 2.301629 0.393816 221.1400 231.9304 13.7707 20250607 14.5 4.0 373P/Rinner MPEC 2021-F20 +0374P 2030 02 14.2866 2.666529 0.463617 51.5881 7.8651 10.7604 20250607 14.0 4.0 374P/Larson MPC114610 +0375P 2018 12 23.7806 1.884058 0.660253 119.4548 359.8306 17.3748 20250607 16.0 4.0 375P/Hill MPEC 2021-F20 +0376P 2019 09 13.0402 2.798454 0.513751 285.3446 312.8501 1.1662 20250607 12.5 4.0 376P/LONEOS MPEC 2024-RQ6 +0377P 2020 07 9.5016 5.011329 0.251454 354.8934 225.9300 9.0321 20250607 9.5 4.0 377P/Scotti MPEC 2022-N37 +0378P 2020 10 6.3545 3.373616 0.463391 193.3032 93.7910 19.1600 20250607 12.0 4.0 378P/McNaught MPEC 2025-A40 +0379P 2026 02 22.8127 2.263425 0.350190 184.6969 30.4474 12.4366 20250607 15.0 4.0 379P/Spacewatch MPC115889 +0380P 2028 08 8.3300 2.960208 0.333859 87.6880 127.7067 8.0341 20250607 12.5 4.0 380P/PANSTARRS MPEC 2023-C45 +0381P 2019 09 25.0716 2.282641 0.680530 173.8476 173.3215 28.3365 20250607 17.5 2.0 381P/LINEAR-Spacewatch MPEC 2021-J28 +0382P 2021 10 29.5070 4.327115 0.265256 162.4166 170.1174 8.2729 20250607 8.0 4.0 382P/Larson MPC182891 +0383P 2026 07 2.5861 1.425045 0.598474 133.7223 207.8549 12.3167 20250607 18.0 4.0 383P/Christensen MPEC 2022-OB6 +0384P 2024 09 19.1196 1.111873 0.616253 37.7015 354.1877 7.2841 20250607 19.5 4.0 384P/Kowalski MPC182891 +0385P 2028 08 4.8709 2.565567 0.401845 44.4646 357.0334 16.8222 20250607 13.0 4.0 385P/Hill MPEC 2021-F20 +0386P 2028 10 13.7436 2.358494 0.417515 353.1051 134.9159 15.2470 20250607 14.5 4.0 386P/PANSTARRS MPEC 2021-L04 +0387P 2030 03 13.1125 1.261845 0.736977 162.8531 259.2388 8.9379 20250607 15.0 4.0 387P/Boattini MPEC 2021-J28 +0388P 2019 07 26.8058 1.994877 0.619357 42.3719 37.0081 23.8776 20250607 13.0 4.0 388P/Gibbs MPEC 2021-S45 +0389P 2019 12 31.3658 1.656768 0.705725 249.3209 218.8495 160.0792 20250607 16.0 4.0 389P/Siding Spring MPEC 2022-OB6 +0390P 2020 03 22.3468 1.706662 0.706652 232.5597 152.1999 18.5218 20250607 12.0 4.0 390P/Gibbs MPEC 2024-EF7 +0391P 2028 05 11.1802 4.136292 0.118368 186.9236 124.7736 21.2568 20250607 8.0 4.0 391P/Kowalski MPEC 2021-F20 +0392P 2020 04 2.9856 1.941400 0.683938 71.9684 24.8005 4.9284 20250607 14.5 4.0 392P/LINEAR MPEC 2021-J28 +0393P 2030 05 7.1159 4.228917 0.119079 329.2023 36.4019 16.7833 20250607 11.0 4.0 393P/Spacewatch-Hill MPC182892 +0394P 2028 11 30.1102 2.732685 0.368375 54.4531 98.1022 8.5280 20250607 16.0 2.4 394P/PANSTARRS MPEC 2020-KB7 +0395P 2022 02 20.4995 4.240018 0.411371 100.7037 220.9653 3.5695 20250607 10.0 4.0 395P/Catalina-NEAT MPC182892 +0396P 2019 08 29.2252 3.963556 0.417014 8.3089 136.6070 5.4426 20250607 12.0 4.0 396P MPEC 2020-KB7 +0397P 2027 12 21.1783 2.281817 0.404576 14.5880 8.2082 10.9198 20250607 12.0 4.0 397P/Lemmon MPEC 2022-OB6 +0398P 2026 07 7.9247 1.300485 0.583766 127.5514 320.1346 11.0276 20250607 15.5 4.0 398P/Boattini MPEC 2021-L04 +0399P 2028 10 12.5248 2.096827 0.447279 214.4505 207.1161 13.3161 20250607 14.0 4.0 399P/PANSTARRS MPEC 2023-XP6 +0400P 2027 11 3.0223 2.103038 0.409589 238.9537 176.3469 10.9251 20250607 15.5 2.8 400P/PANSTARRS MPEC 2024-TD8 +0401P 2019 12 3.1834 2.435737 0.578346 309.3502 359.9230 12.8003 20250607 12.5 4.0 401P/McNaught MPEC 2022-K19 +0402P 2021 12 16.0424 3.942863 0.440016 326.9953 123.0442 30.8290 20250607 9.0 4.0 402P/LINEAR MPEC 2024-LE0 +0403P 2020 09 17.8889 2.693412 0.504225 163.9713 277.5609 12.3321 20250607 12.0 4.0 403P/Catalina MPEC 2021-J28 +0404P 2023 10 31.6874 4.132457 0.124185 168.9818 260.0414 9.8042 20250607 10.0 4.0 404P/Bressi MPC184420 +0405P 2027 10 29.5759 1.116462 0.690199 3.3095 112.1934 9.3791 20250607 17.5 4.0 405P/Lemmon MPEC 2021-L04 +0406P 2027 06 24.8821 1.642885 0.541027 11.5603 352.3872 1.2098 20250607 17.0 4.0 406P/Gibbs MPEC 2021-F20 +0407P 2026 07 25.6178 2.180538 0.375802 93.1181 80.2440 4.8756 20250607 14.0 4.0 407P/PANSTARRS-Fuls MPEC 2022-YN2 +0408P 2022 10 6.0525 3.471990 0.268408 226.6931 189.4513 19.3516 20250607 11.0 4.0 408P/Novichonok-Gerke MPC184420 +0409P 2021 01 28.6707 1.748064 0.710239 15.0413 143.6402 17.1487 20250607 14.0 4.0 409P/LONEOS-Hill MPEC 2022-ED3 +0410P 2021 06 24.7597 3.248927 0.511720 313.2759 139.9321 9.3881 20250607 12.5 4.0 410P/NEAT-LINEAR MPEC 2022-M21 +0411P 2021 01 25.7171 2.430419 0.581806 46.5713 77.6513 12.3887 20250607 13.5 4.0 411P/Christensen MPC184420 +0412P 2026 05 30.6388 1.620937 0.479056 155.8592 0.8422 8.9295 20250607 17.0 4.0 412P/WISE MPEC 2021-F20 +0413P 2028 10 3.3046 2.174952 0.417792 186.7365 38.9485 15.9599 20250607 14.0 4.0 413P/Larson MPC184420 +0414P 2025 09 26.3288 0.524164 0.812267 210.7105 257.8154 23.4073 20250607 19.0 4.0 414P/STEREO MPEC 2024-JU4 +0415P 2029 06 13.6921 3.304886 0.195532 345.8839 160.2578 31.8097 20250607 12.0 4.0 415P/Tenagra MPEC 2022-J42 +0416P 2029 02 23.8581 2.181589 0.455479 134.4535 355.7315 3.3635 20250607 15.5 4.0 416P/Scotti MPC184420 +0417P 2027 05 12.7447 1.490433 0.554714 126.4646 112.0339 9.9002 20250607 16.5 4.0 417P/NEOWISE MPEC 2021-W31 +0418P 2021 10 16.3639 1.710917 0.663870 307.3346 277.6185 5.7809 20250607 13.0 4.0 418P/LINEAR MPEC 2022-TA0 +0419P 2028 06 15.3740 2.567002 0.273637 187.8498 40.4101 2.7951 20250607 12.5 4.0 419P/PANSTARRS MPEC 2023-UR6 +0420P 2022 05 18.1699 2.767435 0.495113 156.4067 173.5362 14.5003 20250607 11.5 4.0 420P/Hill MPEC 2024-L77 +0421P 2021 01 23.6117 1.652444 0.674384 259.8586 55.3316 10.0758 20250607 14.0 4.0 421P/McNaught MPEC 2021-W31 +0422P 2022 01 10.7554 3.101343 0.505701 304.7600 36.0130 39.5804 20250607 11.0 4.0 422P/Christensen MPEC 2024-N80 +0423P 2021 09 26.5503 5.423079 0.122787 80.9199 33.3020 8.3426 20250607 8.0 4.0 423P/Lemmon MPEC 2023-FK0 +0424P 2021 10 30.8860 1.368866 0.690373 312.5567 51.2117 8.6815 20250607 17.0 4.0 424P/LaSagra MPEC 2022-CN4 +0425P 2021 09 20.9687 2.898155 0.543718 200.9908 210.0867 16.4138 20250607 12.0 4.0 425P/Kowalski MPEC 2024-C04 +0426P 2023 09 10.3346 2.672800 0.161039 118.3922 280.3970 17.7841 20250607 13.5 4.0 426P/PANSTARRS MPEC 2024-N80 +0428P 2027 11 17.9743 1.680748 0.518205 36.8957 299.3112 8.5029 20250607 15.0 4.0 428P/Gibbs MPEC 2023-J29 +0429P 2028 09 16.2989 1.810451 0.490852 75.7352 322.0144 7.5142 20250607 15.5 4.0 429P/LINEAR-Hill MPEC 2024-EF7 +0430P 2027 05 22.4892 1.550764 0.500274 94.4519 54.6469 4.4756 20250607 16.5 4.0 430P/Scotti MPEC 2022-L66 +0431P 2028 08 8.6553 1.817259 0.477351 200.0018 202.8384 22.3803 20250607 14.0 4.0 431P/Scotti MPEC 2025-A40 +0432P 2026 12 15.4250 2.306582 0.240841 105.2718 239.1306 10.0678 20250607 17.0 4.0 432P/PANSTARRS MPEC 2021-U31 +0434P 2021 10 27.1034 3.001368 0.274320 128.4444 288.9135 6.3363 20250607 13.0 4.0 434P/Tenagra MPEC 2024-D33 +0435P 2026 10 26.6486 2.062085 0.317562 244.2095 98.5244 18.8745 20250607 17.0 4.0 435P/PANSTARRS MPEC 2021-W31 +0436P 2021 12 7.8069 1.964666 0.669069 282.7618 87.1567 20.1993 20250607 14.5 4.0 436P/Garradd MPEC 2022-X67 +0437P 2022 08 20.2500 3.403586 0.255057 207.0596 245.8406 3.6890 20250607 13.0 4.0 437P/Lemmon-PANSTARRS MPEC 2023-B57 +0438P 2027 10 25.1481 2.257082 0.414142 58.9868 260.1089 8.2807 20250607 14.5 4.0 438P/Christensen MPEC 2025-A40 +0439P 2028 03 5.6720 1.853811 0.469102 342.1057 56.4377 7.1120 20250607 13.5 4.0 439P/LINEAR MPEC 2022-C56 +0440P 2022 03 30.3738 2.051684 0.760853 183.3005 328.8055 12.3506 20250607 15.5 4.0 440P/Kobayashi MPEC 2024-N80 +0441P 2025 09 9.3538 3.327874 0.194656 178.8630 143.5912 2.5748 20250607 13.5 4.0 441P/PANSTARRS MPEC 2022-X67 +0442P 2022 08 17.6837 2.316124 0.532565 310.6429 31.9518 6.0574 20250607 13.5 4.0 442P/McNaught MPEC 2024-N80 +0443P 2022 10 9.4567 2.957540 0.282955 145.0756 108.9339 19.8879 20250607 13.5 4.0 443P/PANSTARRS-Christensen MPEC 2024-TD8 +0444P 2022 06 30.7432 1.535214 0.557888 172.8648 88.1825 22.7308 20250607 17.0 4.0 444P/WISE-PANSTARRS MPEC 2023-VM5 +0445P 2022 08 16.2241 2.370492 0.414144 213.2128 126.5903 1.0888 20250607 15.0 4.0 445P/Lemmon-PANSTARRS MPEC 2024-BE0 +0446P 2022 05 28.7239 1.610829 0.646757 344.6258 336.3393 16.6278 20250607 16.5 4.0 446P/McNaught MPEC 2024-NE4 +0447P 2022 08 16.4281 4.628525 0.177299 97.5241 302.6370 7.4411 20250607 12.0 4.0 447P/Sheppard-Tholen MPEC 2022-YB4 +0448P 2022 09 6.1621 2.115735 0.418171 218.8004 161.7545 12.1451 20250607 16.0 4.0 448P/PANSTARRS MPEC 2024-PC5 +0449P 2027 09 25.1082 1.872734 0.479774 176.7649 242.5221 15.4702 20250607 16.0 4.0 449P/Leonard MPEC 2024-DC6 +0450P 2027 01 31.7283 5.444217 0.314290 23.4293 124.2896 10.6732 20250607 6.5 4.0 450P/LONEOS MPC184420 +0451P 2022 11 27.9550 2.798890 0.559224 186.7904 300.8688 26.4846 20250607 15.5 4.0 451P/Christensen MPEC 2023-HD1 +0452P 2023 04 25.9668 4.177820 0.428542 37.0947 123.6660 6.4219 20250607 9.0 4.0 452P/Sheppard-Jewitt MPEC 2024-NE4 +0453P 2023 03 3.3550 2.279095 0.583139 70.8972 42.8926 27.0601 20250607 14.0 4.0 453P/WISE-Lemmon MPEC 2023-RF3 +0454P 2022 07 26.6557 2.689231 0.361437 20.1924 54.5858 19.8096 20250607 14.0 4.0 454P/PANSTARRS MPEC 2023-CD7 +0455P 2023 02 24.9412 2.193295 0.304454 237.5346 146.1806 14.1349 20250607 17.0 4.0 455P/PANSTARRS MPEC 2022-Y14 +0456P 2025 04 14.9564 2.802242 0.115960 233.0098 243.1455 16.9653 20250607 13.5 4.0 456P/PANSTARRS MPC182892 +0457P 2024 08 20.0796 2.331997 0.118396 104.3201 175.9634 5.2257 20250607 15.5 4.0 457P/Lemmon-PANSTARRS MPEC 2025-A40 +0458P 2022 10 30.7660 2.634879 0.317253 104.9312 1.5622 13.6223 20250607 17.3 4.0 458P/Jahn MPEC 2023-HD1 +0459P 2023 02 21.6654 1.367930 0.577854 205.2246 256.9876 7.1737 20250607 15.5 4.0 459P/Catalina MPEC 2024-N80 +0460P 2026 09 21.6515 1.016499 0.664214 351.9354 180.5167 18.8999 20250607 21.0 4.0 460P/PANSTARRS MPEC 2023-G14 +0461P 2027 05 3.0315 1.353373 0.569586 174.8314 194.3774 18.3993 20250607 18.5 4.0 461P/WISE MPEC 2024-GJ3 +0462P 2022 08 1.2015 2.050171 0.578436 4.2305 322.6698 7.0450 20250607 17.0 4.0 462P/LONEOS-PANSTARRS MPEC 2024-BE0 +0463P 2023 03 29.8400 0.517854 0.825881 216.3408 283.2178 29.2958 20250607 18.0 4.0 463P/NEOWISE MPEC 2024-GJ3 +0464P 2023 02 27.3301 3.369861 0.280566 267.5305 309.5781 21.6732 20250607 10.5 4.0 464P/PANSTARRS MPEC 2024-Q20 +0465P 2023 05 8.9757 2.324382 0.613176 140.9873 217.9596 25.8619 20250607 12.5 4.0 465P/Hill MPEC 2024-NE4 +0466P 2023 05 9.6263 2.114663 0.477057 197.9146 118.1754 12.7718 20250607 14.0 4.0 466P/PANSTARRS MPEC 2024-JU4 +0467P 2022 11 26.8408 5.508694 0.054523 267.4972 43.2631 2.4793 20250607 9.0 4.0 467P/LINEAR-Grauer MPEC 2025-A40 +0468P 2023 11 21.1147 3.950373 0.445001 322.5779 356.1257 50.4516 20250607 11.5 4.0 468P/SidingSpring MPEC 2024-O39 +0469P 2025 12 8.4128 3.005002 0.307990 43.4952 178.9674 20.1724 20250607 13.5 4.0 469P/PANSTARRS MPEC 2025-A40 +0470P 2023 12 16.7708 2.725781 0.389395 151.6954 246.1700 8.8441 20250607 15.5 4.0 470P/PANSTARRS MPC182892 +0471P 2023 12 19.8514 2.119913 0.627724 94.7957 283.3120 4.7969 20250607 12.0 4.0 471P/LINEAR-Lemmon MPC182892 +0472P 2024 07 14.1988 3.387549 0.564693 218.8441 205.8531 10.8240 20250607 10.5 4.0 472P/NEAT-LINEAR MPC184421 +0473P 2024 02 26.2380 1.406342 0.823599 42.9362 22.1898 56.8975 20250607 13.5 4.0 473P/NEAT MPEC 2024-MB8 +0474P 2023 07 15.6722 2.541733 0.188069 11.2619 26.7494 1.0970 20250607 15.5 4.0 474P/Hogan MPEC 2024-B74 +0475P 2024 06 1.6505 4.077413 0.442781 40.4077 147.3609 14.5237 20250607 11.0 4.0 475P/Spacewatch-LINEAR MPEC 2024-O39 +0476P 2024 10 16.4833 3.123411 0.345905 46.7335 57.0503 19.0052 20250607 12.5 4.0 476P/PANSTARRS MPC184421 +0477P 2023 12 26.5325 1.748659 0.417524 305.8802 59.1468 8.9138 20250607 14.5 4.0 477P/PANSTARRS MPEC 2024-GJ3 +0478P 2024 05 2.1573 2.393939 0.343740 13.2403 127.2635 12.5246 20250607 13.5 4.0 478P/ATLAS MPEC 2024-L77 +0479P 2024 05 5.2575 1.243250 0.778900 263.5073 295.8323 15.3996 20250607 15.0 4.0 479P/Elenin MPEC 2024-PC5 +0480P 2023 04 23.7229 3.474913 0.246330 214.4089 229.9814 13.7167 20250607 12.0 4.0 480P/PANSTARRS MPC182893 +0481P 2023 07 9.2780 3.073532 0.343472 356.7966 93.5504 6.0826 20250607 13.5 4.0 481P/Lemmon-PANSTARRS MPEC 2025-A40 +0482P 2023 06 2.1591 1.907084 0.492366 339.7223 126.0783 24.4868 20250607 13.5 4.0 482P/PANSTARRS MPEC 2024-JU4 +0483P a 2027 11 10.4245 2.484149 0.222448 49.1038 199.3062 14.1911 20250607 13.5 4.0 483P-A/PANSTARRS MPEC 2024-R10 +0483P b 2027 11 10.1869 2.484279 0.222389 49.0939 199.3055 14.1919 20250607 17.0 4.0 483P-B/PANSTARRS MPEC 2024-R10 +0484P 2028 03 10.6394 2.130530 0.432916 240.7957 265.3823 14.4743 20250607 16.0 4.0 484P/Spacewatch MPEC 2024-DD5 +0485P 2023 08 25.1954 3.992729 0.417180 196.0955 261.6447 10.0161 20250607 13.0 4.0 485P/Sheppard-Tholen MPEC 2024-JU4 +0486P 2025 04 3.8370 2.308935 0.363558 93.9449 219.0237 2.2095 20250607 14.5 4.0 486P/Leonard MPEC 2024-R10 +0487P 2024 10 20.5965 1.814750 0.648474 0.8441 49.2040 39.3660 20250607 13.5 4.0 487P/SidingSpring MPC184421 +0488P 2024 05 19.4535 1.678954 0.551052 1.6776 323.9647 11.3711 20250607 16.5 4.0 488P/NEAT-PANSTARRS MPEC 2024-UA9 +0489P 2025 12 4.3390 1.561146 0.647117 109.4300 20.6100 4.0264 20250607 15.5 4.0 489P/Denning MPEC 2024-Q14 +0490P 2024 09 28.1811 1.068979 0.647189 332.5397 307.6016 12.2663 20250607 21.0 4.0 490P/ATLAS MPEC 2024-YC7 +0491P 2024 09 6.0283 3.716464 0.258697 298.8843 311.6845 9.3662 20250607 9.5 4.0 491P/Spacewatch-PANSTARRS MPC184421 +0492P 2024 07 20.4507 1.781968 0.690633 40.9840 11.3056 11.4010 20250607 15.0 4.0 492P/LINEAR MPC182893 +0493P 2026 01 14.1041 3.823261 0.466466 83.1979 1.1071 24.1121 20250607 12.0 2.0 493P/LONEOS MPC182893 +0494P 2024 05 30.9949 2.440446 0.356845 48.8777 245.0430 7.7900 20250607 16.0 4.0 494P/PANSTARRS MPEC 2024-RQ6 +0495P 2025 10 22.3931 3.459917 0.272457 141.3381 291.6181 26.3547 20250607 11.5 4.0 495P/Christensen MPEC 2025-A40 +0496P 2025 03 10.2759 1.621033 0.734226 42.2450 63.5864 14.8144 20250607 14.0 4.0 496P/Hill MPC184421 +0497P 2025 02 15.3227 2.075092 0.630482 32.4047 40.3741 10.4368 20250607 17.5 4.0 497P/Spacewatch-PANSTARRS MPC184421 +0498P 2024 12 18.9126 1.964327 0.572313 179.0802 279.2309 14.4828 20250607 14.7 4.0 498P/LINEAR MPC184421 +0499P 2025 03 4.3922 0.931053 0.691456 2.5567 139.3090 24.5822 20250607 18.5 4.0 499P/Catalina MPC184421 +0500P 2025 03 31.9462 2.131767 0.375872 46.6889 111.5293 2.3015 20250607 16.0 4.0 500P/PANSTARRS MPC184421 +0501P 2024 04 14.3029 0.671892 0.698442 53.6944 139.7797 10.0468 20250607 21.5 4.0 501P/Rankin MPC182882 +0502P 2025 08 5.0979 4.229494 0.471199 37.7433 264.4846 11.3996 20250607 8.5 4.0 502P/NEAT MPC184421 +0503P 2025 11 5.5701 1.897318 0.481306 17.9528 268.5823 10.5748 20250607 15.0 4.0 503P/PANSTARRS MPC184422 +0001I 2017 09 9.4886 0.255240 1.199252 241.6845 24.5997 122.6778 20170904 23.0 2.0 1I/`Oumuamua MPC107687 +0002I 2019 12 8.5548 2.006548 3.356633 209.1251 308.1480 44.0527 20191223 11.0 4.0 2I/Borisov MPEC 2023-L37 diff --git a/python/PiFinder/imu_simple_test.py b/python/PiFinder/imu_print_measurements.py similarity index 98% rename from python/PiFinder/imu_simple_test.py rename to python/PiFinder/imu_print_measurements.py index 15c32982b..5e955e232 100644 --- a/python/PiFinder/imu_simple_test.py +++ b/python/PiFinder/imu_print_measurements.py @@ -1,8 +1,8 @@ #!/usr/bin/python # -*- coding:utf-8 -*- """ -For testing: Not for use by PiFinder main loop. -Simple test with IMU based on imu_pi.py +For testing the IMU: Not for use by PiFinder main loop. +Prints the IMU measurements (based on imu_pi.py) """ import time diff --git a/python/README_IMU.md b/python/README_IMU.md index f68985184..4348f12f9 100644 --- a/python/README_IMU.md +++ b/python/README_IMU.md @@ -62,6 +62,12 @@ run from the command line as usual: python3 -m PiFinder.main ``` +For testing, running the following command will dump the raw IMU measurements to the terminal: + +```bash +python PiFinder/imu_print_measurements.py +``` + # Approach: Improved IMU support for quaternions for Altaz During normal operation, we want to find the pointing of the scope, expressed using $q_{hor2scope}$, which is the quaternion that rotates the scope axis in the horizontal frame from the *home* pointing to the current pointing. diff --git a/python/tetra3 b/python/tetra3 new file mode 120000 index 000000000..0cb73b816 --- /dev/null +++ b/python/tetra3 @@ -0,0 +1 @@ +/home/pifinder/PiFinder/python/PiFinder/tetra3/tetra3 \ No newline at end of file From 5cd93c407be30bd18f3c4ca045b7442d2963c63e Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 21 Jun 2025 14:46:09 +0100 Subject: [PATCH 020/253] Initial commit of pointing_model.py --- .../PiFinder/pointing_model/pointing_model.py | 183 ++++++++++++++++++ 1 file changed, 183 insertions(+) create mode 100644 python/PiFinder/pointing_model/pointing_model.py diff --git a/python/PiFinder/pointing_model/pointing_model.py b/python/PiFinder/pointing_model/pointing_model.py new file mode 100644 index 000000000..a7d392ed0 --- /dev/null +++ b/python/PiFinder/pointing_model/pointing_model.py @@ -0,0 +1,183 @@ +""" +Pointing model functions. + +NOTE: + +* All angles are in radians. +* The quaternions use numpy quaternions and are scalar-first. +* Some of the constant quaternion terms can be speeded up by not using +trigonometric functions. +* The methods do not normalize the quaternions because this incurs a small +computational overhead. Normalization should be done manually as and when +necessary. +""" + +import numpy as np +import quaternion + +# Mount type enumerations +mount_type_altaz = 1 +mount_type_gem = 2 + + +def get_q_horiz2mnt_altaz_mount(): + """ + Quaternion rotation from horizontal to the mount frame for a perfect + altaz mount. + + For a perfect altaz mount, y_mnt points to zenith (+z_hor), z_mnt points North (-x_hor) and + x_mnt points West (-y_hor). + """ + q_horiz2mnt = np.quaternion(np.cos(np.pi / 4), 0, 0, np.sin(np.pi / 4)) \ + * np.quaternion(np.cos(np.pi / 4), np.sin(np.pi / 4), 0, 0) * np.quaternion(0, 0, 1, 0) + return q_horiz2mnt + + +def get_q_horiz2mnt_equatorial_mount(lat): + """ + Returns the quaternion to rotate from the Horizontal frame to the equatorial + frame for a perfect equatorial mount. + """ + colat = np.pi / 2 - lat + # Rotate 90° around x_hor so that y' points to zenith + q1 = np.quaternion(np.cos(np.pi / 4), np.sin(np.pi / 4), 0, 0) + # Tilt so that y_mnt points to north polse + q2 = np.quaternion(np.cos(colat / 2), 0, 0, np.sin(colat / 2)) + + q_horiz2mnt = q1 * q2 # Intrinsic rotation: q1 followed by q2 + + return q_horiz2mnt + + +def get_q_mnt_error_for_altaz_mount(az_err=0, alt_err=0): + """ + Returns the mount error for an altaz mount. + + PARAMETERS: + az_err: +ve rotates the mount around z_hor from North to East. + alt_err: +ve rotates the mount around y_hor (West-East axis) towards North. + """ + NotImplementedError() + + +def get_q_mnt_error_for_equatorial_mount(ra_err=0, dec_err=0): + """ + Returns the mount error for an equatorial mount. + + PARAMETERS: + """ + NotImplementedError() + + +def get_q_mnt2gimb(gimb_az, gimb_alt): + """" + Returns the quaternion to rotate from the Mount frame to the Gimbal frame + by the specified gimbal rotations. This assumes that the gimbals are + perpendicular. Later, non-perpendicularity will be incorporated here. + + INPUTS: + gimb_az: Gimbal rotation angle around y_mnt. +ve angle is a clockwise + rotation when looking down along the y_mnt axis (i.e. towards -y_mnt). + gimb_alt: Gimbal altitude angle. +ve angle is clockwise rotation around + when looking towards -x_mnt. + """ + # Step 1: Az: Rotate around the original az axis (y_mnt) + q_gimb_az = np.quaternion(np.cos(-gimb_az / 2), 0, np.sin(-gimb_az / 2), 0) + # Step 2: Alt: Rotate around the new alt axis (x_mnt') + q_gimb_alt = np.quaternion(np.cos(-gimb_alt / 2), np.sin(-gimb_alt / 2), 0, 0) + + # Combine az rotation followed by alt rotation using intrinsic rotation + # so that q_gimb_alt rotates the quaternion around the alt gimbal + # axis after rotation around the az axis. + q_mnt2gimb = q_gimb_az * q_gimb_alt # Intrinsic (az followed by alt) + + return q_mnt2gimb + + +def get_q_gimb2scope(mount_type): + """" + Returns the quaternion to rotate from the Gimbal frame to the Scope frame. + For the ideal case, the Scope frame is assumed to be the same as the Gimbal + frame. + + Misalignments and gravitational sag of the scope could be incroporated here. + """ + if mount_type == mount_type_altaz: + # Altaz + q_gimb2scope = np.quaternion(1, 0, 0, 0) # Invariant + elif mount_type == mount_type_gem: + # GEM + q_gimb2scope = np.quaternion(np.cos(-np.pi / 4), 0, np.sin(-np.pi / 4), 0) \ + * np.quaternion(np.cos(-np.pi / 4), np.sin(-np.pi / 4), 0, 0) + #q_gimb2scope = np.quaternion(np.cos(-np.pi / 4), 0, 0, np.sin(-np.pi / 4)) + else: + raise ValueError() + + return q_gimb2scope + + +def get_q_scope2camera(): + """ + Returns the quaternion to rotate from the Scope frame to the Camera frame. + """ + + +def get_q_imu2camera(): + """ + Returns the quaternion to transform from the IMU frame to the Camera frame. + """ + # Rotate -90° around y_imu so that z_imu' points along z_camera + q1 = np.quaternion(np.cos(-np.pi / 4), 0, np.sin(-np.pi / 4), 0) + # Rotate -90° around z_imu' to align with the camera cooridnates + q2 = np.quaternion(np.cos(-np.pi / 4), 0, 0, np.sin(-np.pi / 4)) + q_imu2cam = q1 * q2 # Intrinsic rotation: q1 followed by q2 + + return q_imu2cam + + +def get_q_camera2imu(): + """ + Returns the quaternion to transform from the Camera frame to the IMU frame. + """ + q_imu2cam = get_q_imu2camera() + return q_imu2cam.conjugate() + + +def get_gimb_angles_altaz_mount(az, alt): + """ + Returns the gimbal angles for an Altaz mount. + + EXAMPLE: + gimb_az, gimb_alt = get_gimb_angles_altaz_mount(az, alt) + """ + return az, alt # Returns: gimb_az, gimb_alt + + +def get_gimb_angles_equatorial_mount(ha, dec): + """ + Returns the gimbal angles for an EQ mount. + + EXAMPLE: + gimb_az, gimb_alt = get_gimb_angles_equatorial_mount(ha, dec) + """ + # Correct for East - for west, need to do a meridian flip?? + gimb_az = ha + np.pi / 2 # HA is clockwise, around z_mnt (looking down from +z_mnt) + # Anti-clockwise turn around x_mnt increases dec + # + # NOTE: For a GEM, when scope is on E side, an anti-clockwise turn will + # decrease the dec + gimb_alt = np.pi / 2 - dec + + return gimb_az, gimb_alt + +def get_q_horiz2scope(az, alt): + """ + Returns the quaternion to rotate from the horizontal frame to the scope frame + at coordinates (az, alt) for an ideal AltAz mount. + + INPUTS: + az: [rad] Azimuth of scope axis + alt: [rad] Alt of scope axis + """ + return np.quaternion(np.cos(-(az + np.pi/2) / 2), 0, 0, np.sin(-(az + np.pi/2) / 2)) \ + * np.quaternion(np.cos((np.pi / 2 - alt) / 2), np.sin((np.pi / 2 - alt) / 2), 0, 0) From 07ba1e1db1d60e56d7ddbe8038cf6b2c6408c4ea Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 21 Jun 2025 23:02:06 +0100 Subject: [PATCH 021/253] Add comments --- python/PiFinder/pointing_model/pointing_model.py | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/python/PiFinder/pointing_model/pointing_model.py b/python/PiFinder/pointing_model/pointing_model.py index a7d392ed0..87ba2a496 100644 --- a/python/PiFinder/pointing_model/pointing_model.py +++ b/python/PiFinder/pointing_model/pointing_model.py @@ -1,6 +1,12 @@ """ Pointing model functions. +The quaternions use the notation in the form `q_a2b` for a quaternion that +rotates frame `a` to frame `b` using intrinsic rotation (by post-multiplying the +quaternions). For example: + +q_a2c = q_a2b * q_a2c + NOTE: * All angles are in radians. From 150dc89d77f84fd2d3ecda14730865a68ca55afe Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 21 Jun 2025 23:04:06 +0100 Subject: [PATCH 022/253] pointing_model.py - remove unused funcs for now --- .../PiFinder/pointing_model/pointing_model.py | 154 ------------------ 1 file changed, 154 deletions(-) diff --git a/python/PiFinder/pointing_model/pointing_model.py b/python/PiFinder/pointing_model/pointing_model.py index 87ba2a496..4d3aeb6fb 100644 --- a/python/PiFinder/pointing_model/pointing_model.py +++ b/python/PiFinder/pointing_model/pointing_model.py @@ -21,160 +21,6 @@ import numpy as np import quaternion -# Mount type enumerations -mount_type_altaz = 1 -mount_type_gem = 2 - - -def get_q_horiz2mnt_altaz_mount(): - """ - Quaternion rotation from horizontal to the mount frame for a perfect - altaz mount. - - For a perfect altaz mount, y_mnt points to zenith (+z_hor), z_mnt points North (-x_hor) and - x_mnt points West (-y_hor). - """ - q_horiz2mnt = np.quaternion(np.cos(np.pi / 4), 0, 0, np.sin(np.pi / 4)) \ - * np.quaternion(np.cos(np.pi / 4), np.sin(np.pi / 4), 0, 0) * np.quaternion(0, 0, 1, 0) - return q_horiz2mnt - - -def get_q_horiz2mnt_equatorial_mount(lat): - """ - Returns the quaternion to rotate from the Horizontal frame to the equatorial - frame for a perfect equatorial mount. - """ - colat = np.pi / 2 - lat - # Rotate 90° around x_hor so that y' points to zenith - q1 = np.quaternion(np.cos(np.pi / 4), np.sin(np.pi / 4), 0, 0) - # Tilt so that y_mnt points to north polse - q2 = np.quaternion(np.cos(colat / 2), 0, 0, np.sin(colat / 2)) - - q_horiz2mnt = q1 * q2 # Intrinsic rotation: q1 followed by q2 - - return q_horiz2mnt - - -def get_q_mnt_error_for_altaz_mount(az_err=0, alt_err=0): - """ - Returns the mount error for an altaz mount. - - PARAMETERS: - az_err: +ve rotates the mount around z_hor from North to East. - alt_err: +ve rotates the mount around y_hor (West-East axis) towards North. - """ - NotImplementedError() - - -def get_q_mnt_error_for_equatorial_mount(ra_err=0, dec_err=0): - """ - Returns the mount error for an equatorial mount. - - PARAMETERS: - """ - NotImplementedError() - - -def get_q_mnt2gimb(gimb_az, gimb_alt): - """" - Returns the quaternion to rotate from the Mount frame to the Gimbal frame - by the specified gimbal rotations. This assumes that the gimbals are - perpendicular. Later, non-perpendicularity will be incorporated here. - - INPUTS: - gimb_az: Gimbal rotation angle around y_mnt. +ve angle is a clockwise - rotation when looking down along the y_mnt axis (i.e. towards -y_mnt). - gimb_alt: Gimbal altitude angle. +ve angle is clockwise rotation around - when looking towards -x_mnt. - """ - # Step 1: Az: Rotate around the original az axis (y_mnt) - q_gimb_az = np.quaternion(np.cos(-gimb_az / 2), 0, np.sin(-gimb_az / 2), 0) - # Step 2: Alt: Rotate around the new alt axis (x_mnt') - q_gimb_alt = np.quaternion(np.cos(-gimb_alt / 2), np.sin(-gimb_alt / 2), 0, 0) - - # Combine az rotation followed by alt rotation using intrinsic rotation - # so that q_gimb_alt rotates the quaternion around the alt gimbal - # axis after rotation around the az axis. - q_mnt2gimb = q_gimb_az * q_gimb_alt # Intrinsic (az followed by alt) - - return q_mnt2gimb - - -def get_q_gimb2scope(mount_type): - """" - Returns the quaternion to rotate from the Gimbal frame to the Scope frame. - For the ideal case, the Scope frame is assumed to be the same as the Gimbal - frame. - - Misalignments and gravitational sag of the scope could be incroporated here. - """ - if mount_type == mount_type_altaz: - # Altaz - q_gimb2scope = np.quaternion(1, 0, 0, 0) # Invariant - elif mount_type == mount_type_gem: - # GEM - q_gimb2scope = np.quaternion(np.cos(-np.pi / 4), 0, np.sin(-np.pi / 4), 0) \ - * np.quaternion(np.cos(-np.pi / 4), np.sin(-np.pi / 4), 0, 0) - #q_gimb2scope = np.quaternion(np.cos(-np.pi / 4), 0, 0, np.sin(-np.pi / 4)) - else: - raise ValueError() - - return q_gimb2scope - - -def get_q_scope2camera(): - """ - Returns the quaternion to rotate from the Scope frame to the Camera frame. - """ - - -def get_q_imu2camera(): - """ - Returns the quaternion to transform from the IMU frame to the Camera frame. - """ - # Rotate -90° around y_imu so that z_imu' points along z_camera - q1 = np.quaternion(np.cos(-np.pi / 4), 0, np.sin(-np.pi / 4), 0) - # Rotate -90° around z_imu' to align with the camera cooridnates - q2 = np.quaternion(np.cos(-np.pi / 4), 0, 0, np.sin(-np.pi / 4)) - q_imu2cam = q1 * q2 # Intrinsic rotation: q1 followed by q2 - - return q_imu2cam - - -def get_q_camera2imu(): - """ - Returns the quaternion to transform from the Camera frame to the IMU frame. - """ - q_imu2cam = get_q_imu2camera() - return q_imu2cam.conjugate() - - -def get_gimb_angles_altaz_mount(az, alt): - """ - Returns the gimbal angles for an Altaz mount. - - EXAMPLE: - gimb_az, gimb_alt = get_gimb_angles_altaz_mount(az, alt) - """ - return az, alt # Returns: gimb_az, gimb_alt - - -def get_gimb_angles_equatorial_mount(ha, dec): - """ - Returns the gimbal angles for an EQ mount. - - EXAMPLE: - gimb_az, gimb_alt = get_gimb_angles_equatorial_mount(ha, dec) - """ - # Correct for East - for west, need to do a meridian flip?? - gimb_az = ha + np.pi / 2 # HA is clockwise, around z_mnt (looking down from +z_mnt) - # Anti-clockwise turn around x_mnt increases dec - # - # NOTE: For a GEM, when scope is on E side, an anti-clockwise turn will - # decrease the dec - gimb_alt = np.pi / 2 - dec - - return gimb_az, gimb_alt def get_q_horiz2scope(az, alt): """ From 001b2d1e6b2549a017a66fe7493263fb0d4b641a Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 21 Jun 2025 23:40:13 +0100 Subject: [PATCH 023/253] pointing_model: Add func --- .../PiFinder/pointing_model/pointing_model.py | 18 ++++++++++++++++++ 1 file changed, 18 insertions(+) diff --git a/python/PiFinder/pointing_model/pointing_model.py b/python/PiFinder/pointing_model/pointing_model.py index 4d3aeb6fb..72a40756b 100644 --- a/python/PiFinder/pointing_model/pointing_model.py +++ b/python/PiFinder/pointing_model/pointing_model.py @@ -33,3 +33,21 @@ def get_q_horiz2scope(az, alt): """ return np.quaternion(np.cos(-(az + np.pi/2) / 2), 0, 0, np.sin(-(az + np.pi/2) / 2)) \ * np.quaternion(np.cos((np.pi / 2 - alt) / 2), np.sin((np.pi / 2 - alt) / 2), 0, 0) + + +def get_altaz_from_q_hor2scope(q_hor2scope): + """ + Returns the (az, alt) pointing of the scope which is defined by the z axis + of the q_hor2scope quaternion. + + RETURNS: + az: [rad] + alt: [rad] + """ + pz = np.quaternion(0, 0, 0, 1) # Vector z represented as a pure quaternion + scope_axis = q_hor2scope * pz * q_hor2scope.conj() # Returns a pure quaternion along scope axis + + alt = np.pi / 2 - np.arccos(scope_axis.z) + az = np.pi - np.arctan2(scope_axis.y, scope_axis.x) + + return az, alt \ No newline at end of file From 64fadc14ab8172e33d590c81f9fee9ee3f803eb0 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 21 Jun 2025 23:40:37 +0100 Subject: [PATCH 024/253] pointing_model: Rename func --- python/PiFinder/pointing_model/pointing_model.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/python/PiFinder/pointing_model/pointing_model.py b/python/PiFinder/pointing_model/pointing_model.py index 72a40756b..7e47c5fe6 100644 --- a/python/PiFinder/pointing_model/pointing_model.py +++ b/python/PiFinder/pointing_model/pointing_model.py @@ -22,7 +22,7 @@ import quaternion -def get_q_horiz2scope(az, alt): +def get_q_hor2scope(az, alt): """ Returns the quaternion to rotate from the horizontal frame to the scope frame at coordinates (az, alt) for an ideal AltAz mount. From 756c5be398a8c4a832ed572aec1b87358d524a68 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 22 Jun 2025 00:03:08 +0100 Subject: [PATCH 025/253] Modify integrator.py to use quaternion-based IMU dead-reckoning --- python/PiFinder/integrator.py | 109 ++++++++++++++++++++++++++++------ 1 file changed, 90 insertions(+), 19 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 237a5917d..3a3a078dc 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -18,6 +18,7 @@ from PiFinder import state_utils import PiFinder.calc_utils as calc_utils from PiFinder.multiproclogging import MultiprocLogging +from PiFinder.pointing_model import pointing_model #IMU_ALT = 2 #IMU_AZ = 0 @@ -69,9 +70,12 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa "Dec": None, "Roll": None, }, + "imu": { + "q_hor2x": None, + }, "Roll_offset": 0, # May/may not be needed - for experimentation #"imu_pos": None, - "imu_quat": None, # IMU quaternion as numpy quaternion (scalar-first) + "imu_quat": None, # IMU quaternion as numpy quaternion (scalar-first) - TODO: Move to "imu" "Alt": None, # Alt of scope "Az": None, "solve_source": None, @@ -165,6 +169,16 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa roll_target_calculated + solved["Roll_offset"] ) + # Use plate-solved pointing and IMU measurement to set up + # IMU dead reckoning: + solved["imu"]["q_hor2x"] = get_imu_reference_frame(solved, shared_state) + # From the alignment. Add this offset to the camera center to get + # the scope altaz coordinates. TODO: This could be calculated once + # at alignment? + cam2scope_offset_az = solved["Az"] - solved["camera_center"]["Az"] + cam2scope_offset_alt = solved["Alt"] - solved["camera_center"]["Alt"] + # TODO: Do something similar for EQ mounts here + last_image_solve = copy.deepcopy(solved) solved["solve_source"] = "CAM" @@ -186,26 +200,29 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa # calc new alt/az #lis_imu = last_image_solve["imu_pos"] lis_imu_quat = last_image_solve["imu_quat"] - imu_quat = imu["quat"] - #imu_pos = imu["pos"] - # Current IMU pointing relative to horizontal frame, - # converted from scalar-last to a scalar-first Numpy - # quaternion data type - #q_hor2imu = np.quaternion(imu["quat"][3], - # imu["quat"][0], imu["quat"][1], imu["quat"][2]) - if imu_moved(lis_imu_quat, imu_quat): - # Estimate scope pointing using IMU dead-reckoning - #q_hor2scope = q_hor2imu * q_drift * q_imu2scope - - # Using pseudo code here: - lis_q_camera = altaz_to_quat(last_image_solve["camera_center"]["Az"], - last_image_solve["camera_center"]["Alt"]) - q_imu2camera = lis_imu_quat.conj() * lis_q_camera # For intrinsic rotations + # Get latest IMU meas: quaternion rot. of IMU rel. to some frame X + q_x2imu = imu["quat"] + #imu_pos = imu["pos"] - q_camera = imu_quat * q_imu2camera # Estimate current camera center using IMU - solved["Az"], solved["Alt"] = q_horiz2altaz(q_camera) - # Calculate for scope center + if imu_moved(lis_imu_quat, q_x2imu): + # Estimate camera pointing using IMU dead-reckoning + q_hor2x = last_image_solve["imu"]["q_hor2x"] + q_imu2cam = np.quaternion(1, 0, 0, 0) # Identity so this could be removed later (TODO) + q_hor2cam = q_hor2x * q_x2imu * q_imu2cam + q_hor2cam = q_hor2com.normalized() + # Store estimate: + az_rad, alt_rad = pointing.get_altaz_from_q_hor2scope(q_hor2cam) + solved["camera_center"]["Az"] = np.rad2deg(az_rad) + solved["camera_center"]["Alt"] = np.rad2deg(alt_rad) + + # Transform to scope center + solved["Az"] = solved["camera_center"]["Az"] + cam2scope_offset_az + solved["Alt"] = solved["camera_center"]["Alt"] + cam2scope_offset_alt + + # TODO: need to define q_cam2scope + #q_hor2scope = q_hor2cam * q_cam2scope + """ DISABLE - Use quaternions alt_offset = imu_pos[IMU_ALT] - lis_imu[IMU_ALT] @@ -295,3 +312,57 @@ def estimate_roll_offset(solved, dt): roll_offset = solved["camera_center"]["Roll"] - roll_camera_calculated return roll_offset + + +def get_imu_reference_frame(solved, shared_state) + """ + The IMU quaternion measurements, q_x2imu, are relative to some arbitrary + drifting frame X. This uses the latest plate solved coordinate with the + latest IMU measurement to solve for the IMU's reference frame X. The frame + X is expressed by the quaternion rotation q_hor2x from the Horizontal frame + to X. Once we know q_hor2x, we can infer the camera pointing using the IMU + data by dead reckoning: q_hor2cam = q_hor2x * q_x2imu * q_imu2cam + + This assumes that plate solving was successful and camera coordinates are + available. It also assumes that the IMU measurement is available. If these + conditions are not met, this function will return None. We also assume that + the plate solve and IMU measurements availalbe are simultaneous. Note that + q_hor2x will drift over time. + + INPUT: + solved: Dictionary of the latest plate-solved data + + RETURNS: + q_hor2x: [numpy.quaternion] Quaternion of the IMU's drifting reference + frame X relative to the Horizontal frame. Returns None if the + plate-solved pointing or IMU data aren't available. + """ + q_hor2x = None + + if solved["Alt"]: + # Successfully plate solved & camera pointing exists + #imu = shared_state.imu() # TODO: Usage above. Remove? + imu_meas = solved["imu_quat"] # Should be the IMU measurement at the time of plate solving + if imu_meas: + # We have both the plate solved camera pointing and an IMU + # measurement (we'll assume that they are at the same timestamp). + + # Get plate-solved pointing from the camera as quaternion: + # Assumes that the PiFinder camera is on a perfect altaz mount + q_hor2cam = pointing.get_q_hor2scope( + np.deg2rad(solved["camera_center"]["Az"]), + np.deg2rad(solved["camera_center"]["Alt"])) + + # Get latest IMU data: quaternion rot. of IMU rel. to some drifting + # reference frame X that the IMU uses as its reference + q_x2imu = imu_meas # Rename to make the transformation expilicit + q_x2imu = q_x2imu.normalized() + + # Solve for the arbitrary drifting reference frame X using the + # camera pointing. This will be used during dead reckoning with + # the IMU until the next plate solve. + q_cam2imu = np.quaternion(1, 0, 0, 0) # Identity so this could be removed later (TODO) + q_hor2x = q_hor2cam * q_cam2imu * q_x2imu.conj() + q_hor2x = q_hor2x.normalized() + + return q_hor2x From 77b1b8875b6294cc4a625018bb7c7aa74f8e4637 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Sun, 22 Jun 2025 01:04:02 +0200 Subject: [PATCH 026/253] Add comments --- python/PiFinder/integrator.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 3a3a078dc..5badb914f 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -54,6 +54,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa logger.setLevel(logging.DEBUG) logger.debug("Starting Integrator") + # TODO: This dict is duplicated in solver.py - Refactor? solved = { "RA": None, # RA of scope "Dec": None, @@ -65,7 +66,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa "Alt": None, "Az": None, }, - "camera_solve": { + "camera_solve": { # camera_solve is NOT updated by IMU dead-reckoning "RA": None, "Dec": None, "Roll": None, From e7b50ea7b268a13287c3da3168fbda056f50c153 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 22 Jun 2025 00:12:44 +0100 Subject: [PATCH 027/253] Fix typo --- python/PiFinder/integrator.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 5badb914f..aae851c89 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -315,7 +315,7 @@ def estimate_roll_offset(solved, dt): return roll_offset -def get_imu_reference_frame(solved, shared_state) +def get_imu_reference_frame(solved, shared_state): """ The IMU quaternion measurements, q_x2imu, are relative to some arbitrary drifting frame X. This uses the latest plate solved coordinate with the From e96b71b6045cf23c2da69d01930b78b1ecac28d6 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 22 Jun 2025 00:23:31 +0100 Subject: [PATCH 028/253] Edit comment --- python/PiFinder/integrator.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index aae851c89..8f030756b 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -342,7 +342,7 @@ def get_imu_reference_frame(solved, shared_state): if solved["Alt"]: # Successfully plate solved & camera pointing exists - #imu = shared_state.imu() # TODO: Usage above. Remove? + #imu = shared_state.imu() # TODO: Usage above. Remove? Also remove shared_state as input? imu_meas = solved["imu_quat"] # Should be the IMU measurement at the time of plate solving if imu_meas: # We have both the plate solved camera pointing and an IMU From 983476f9388b1a746aa27eb9abada69f8ce86084 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 22 Jun 2025 00:24:24 +0100 Subject: [PATCH 029/253] Change usages of imu["pos"] to imu["quat"] --- python/PiFinder/ui/base.py | 2 +- python/PiFinder/ui/console.py | 2 +- python/PiFinder/ui/status.py | 4 ++-- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/python/PiFinder/ui/base.py b/python/PiFinder/ui/base.py index 53a0f0363..9ee2c6d03 100644 --- a/python/PiFinder/ui/base.py +++ b/python/PiFinder/ui/base.py @@ -223,7 +223,7 @@ def screen_update(self, title_bar=True, button_hints=True) -> None: (6, 1), _(self.title), font=self.fonts.bold.font, fill=fg ) imu = self.shared_state.imu() - moving = True if imu and imu["pos"] and imu["moving"] else False + moving = True if imu and imu["quat"] and imu["moving"] else False # GPS status if self.shared_state.altaz_ready(): diff --git a/python/PiFinder/ui/console.py b/python/PiFinder/ui/console.py index 2c3471ecf..2fc4a9d5c 100644 --- a/python/PiFinder/ui/console.py +++ b/python/PiFinder/ui/console.py @@ -135,7 +135,7 @@ def screen_update(self, title_bar=True, button_hints=True): ) self.draw.text((6, 1), self.title, font=self.fonts.bold.font, fill=fg) imu = self.shared_state.imu() - moving = True if imu and imu["pos"] and imu["moving"] else False + moving = True if imu and imu["quat"] and imu["moving"] else False # GPS status if self.shared_state.altaz_ready(): diff --git a/python/PiFinder/ui/status.py b/python/PiFinder/ui/status.py index 2f5324690..516a2046c 100644 --- a/python/PiFinder/ui/status.py +++ b/python/PiFinder/ui/status.py @@ -257,14 +257,14 @@ def update_status_dict(self): imu = self.shared_state.imu() if imu: - if imu["pos"] is not None: + if imu["quat"] is not None: if imu["moving"]: mtext = "Moving" else: mtext = "Static" self.status_dict["IMU"] = f"{mtext : >11}" + " " + str(imu["status"]) self.status_dict["IMU PS"] = ( - f"{imu['pos'][0] : >6.1f}/{imu['pos'][2] : >6.1f}" + f"{imu["quat"][0] : >6.1f}/{imu["quat"][2] : >6.1f}" # TODO: Quick hack for now. This was changed from imu["pos"] and should be changed. ) location = self.shared_state.location() sats = self.shared_state.sats() From 08d3004cc9c2ebec2445066620ca6b1275704e63 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 22 Jun 2025 00:27:02 +0100 Subject: [PATCH 030/253] Fix so that it's '..' inside "..." --- python/PiFinder/ui/status.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/python/PiFinder/ui/status.py b/python/PiFinder/ui/status.py index 516a2046c..fa562be3b 100644 --- a/python/PiFinder/ui/status.py +++ b/python/PiFinder/ui/status.py @@ -264,7 +264,7 @@ def update_status_dict(self): mtext = "Static" self.status_dict["IMU"] = f"{mtext : >11}" + " " + str(imu["status"]) self.status_dict["IMU PS"] = ( - f"{imu["quat"][0] : >6.1f}/{imu["quat"][2] : >6.1f}" # TODO: Quick hack for now. This was changed from imu["pos"] and should be changed. + f"{imu['quat'][0] : >6.1f}/{imu['quat'][2] : >6.1f}" # TODO: Quick hack for now. This was changed from imu["pos"] and should be changed. ) location = self.shared_state.location() sats = self.shared_state.sats() From 44f12b2fbcdbc6115a7bbf05dab64ad9a539f9de Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 22 Jun 2025 01:12:09 +0100 Subject: [PATCH 031/253] Removed astro_data/comets.txt that was mistakenly committed --- astro_data/comets.txt | 1203 ----------------------------------------- 1 file changed, 1203 deletions(-) delete mode 100644 astro_data/comets.txt diff --git a/astro_data/comets.txt b/astro_data/comets.txt deleted file mode 100644 index 4b650f6f4..000000000 --- a/astro_data/comets.txt +++ /dev/null @@ -1,1203 +0,0 @@ - PJ96R020 2026 06 15.6631 2.587044 0.314270 333.4862 40.0451 2.5990 20250607 11.5 4.0 P/1996 R2 (Lagerkvist) NK 1615 - PJ98V24S 2027 09 7.8207 3.419529 0.243582 244.8820 159.0401 5.0292 20250607 13.0 2.0 P/1998 VS24 (LINEAR) MPC 75703 - PJ99R28O 2025 10 30.3009 1.122847 0.672185 231.3524 137.8416 7.5670 20250607 20.0 2.0 P/1999 RO28 (LONEOS) NK 731 - PJ99XC0N 2025 12 21.6387 3.297889 0.211622 161.5994 285.2407 5.0298 20250607 13.5 2.0 P/1999 XN120 (Catalina) MPC 75704 - PK00R020 2025 12 2.2969 1.628195 0.530641 176.5814 160.2712 11.6788 20250607 18.0 4.0 P/2000 R2 (LINEAR) NK 744 - PK01H050 2030 10 22.6222 2.442745 0.599183 224.5860 328.6738 8.3720 20250607 12.0 4.0 P/2001 H5 (NEAT) MPC 43019 - PK02E57J 2018 06 20.2371 2.621487 0.593904 167.2783 330.2284 4.9889 20250607 12.5 4.0 P/2002 EJ57 (LINEAR) MPEC 2023-UR6 - CK02V94Q 2006 02 10.9809 6.755134 0.963821 99.8065 35.0990 70.6577 20250607 9.5 2.0 C/2002 VQ94 (LINEAR) MPC 75007 - CK03A020 2003 11 4.9613 11.358784 0.997924 346.4579 154.5067 8.0702 20250607 3.5 4.0 C/2003 A2 (Gleason) MPC184407 - PK03F020 2019 11 14.5137 3.013162 0.539112 192.9259 358.9192 11.6495 20250607 16.5 2.0 P/2003 F2 (NEAT) MPC 50354 - PK03T120 2024 07 3.7309 0.593884 0.770175 219.7925 174.5764 11.0235 20250607 17.0 4.0 P/2003 T12 (SOHO) MPC105235 - PK04FE0Y 2027 02 22.0486 4.011274 0.192745 254.2397 327.2620 2.1627 20250607 12.5 2.0 P/2004 FY140 (LINEAR) MPEC 2022-YN2 - PK04R030 2021 09 15.6937 3.539592 0.254472 37.2261 305.1202 12.8014 20250607 14.5 4.0 P/2004 R3 (LINEAR-NEAT) MPC 53304 - PK04V050 2027 08 6.2877 4.433603 0.448659 87.2012 47.7415 19.3379 20250607 8.0 4.0 P/2004 V5 (LINEAR-Hill) MPC 75705 - PK04V05b 2027 08 7.2597 4.433608 0.448677 87.2054 47.7419 19.3380 20250607 8.0 4.0 P/2004 V5-B (LINEAR-Hill) MPC 75705 - PK05E010 2023 09 28.1159 4.402632 0.377279 193.9221 335.4981 4.2606 20250607 10.0 4.0 P/2005 E1 (Tubbiolo) MPC 54164 - PK05J010 2025 07 11.7017 1.539551 0.569360 338.9133 268.7998 31.7405 20250607 16.5 4.0 P/2005 J1 (McNaught) MPC 79019 - PK05L010 2021 12 24.3227 2.935631 0.252620 160.0017 127.6738 8.5769 20250607 9.5 4.0 P/2005 L1 (McNaught) MPC 74246 - PK05S020 2029 01 25.9002 6.399698 0.198499 229.9970 161.3338 3.1385 20250607 7.5 4.0 P/2005 S2 (Skiff) MPC 75706 - PK05T030 2026 08 19.6558 6.253688 0.174377 7.0803 27.6229 6.2319 20250607 9.0 4.0 P/2005 T3 (Read) MPC 73461 - PK05T040 2034 05 27.9119 0.648203 0.930688 41.7987 25.8303 160.2515 20250607 15.0 4.0 P/2005 T4 (SWAN) MPC 73461 - PK05T050 2025 06 14.9420 3.253537 0.551769 304.7801 57.0620 21.3836 20250607 11.0 4.0 P/2005 T5 (Broughton) MPC 75706 - PK06H30R 2028 10 9.2542 1.219308 0.843615 117.5106 309.7590 31.9558 20250607 11.0 4.0 P/2006 HR30 (Siding Spring) MPC 75707 - PK07C020 2026 03 21.2175 3.692565 0.474325 180.1208 275.2340 8.6130 20250607 10.0 4.0 P/2007 C2 (Catalina) MPC 75707 - CK07D010 2007 06 14.0365 8.739347 0.992912 339.7507 171.0421 41.5133 20250607 3.5 4.0 C/2007 D1 (LINEAR) MPC 84315 - PK07K020 2027 01 26.4813 2.312371 0.686419 347.0918 188.4259 7.5950 20250607 14.0 4.0 P/2007 K2 (Gibbs) MPEC 2024-GJ3 - PK07Q020 2020 11 25.0393 1.875009 0.668787 162.8493 172.2261 10.1936 20250607 16.0 4.0 P/2007 Q2 (Gilmore) MPC 60925 - PK07S010 2022 10 6.4356 2.528059 0.337946 245.2735 141.3271 5.9632 20250607 13.0 4.0 P/2007 S1 (Zhao) MPC 73462 - CK07S020 2008 09 3.9818 5.535672 0.556952 210.1455 296.1300 16.9160 20250607 6.5 4.0 C/2007 S2 (Lemmon) MPEC 2024-GJ3 - PK07S24A 2022 12 1.7764 2.683412 0.568947 107.8067 233.2428 17.1112 20250607 12.6 4.0 P/2007 SA24 (Lemmon) MPC184407 - PK07T020 2023 11 17.5014 0.652963 0.785459 359.6677 3.3929 9.7481 20250607 18.5 4.0 P/2007 T2 (Kowalski) MPC 61994 - CK08E010 2008 08 22.3547 4.812629 0.552886 270.3589 188.9234 34.8644 20250607 7.0 4.0 C/2008 E1 (Catalina) MPEC 2024-GJ3 - PK08O030 2031 12 23.5938 2.494071 0.696168 341.2019 47.6075 32.3107 20250607 13.0 4.0 P/2008 O3 (Boattini) MPC 64114 - PK08Y030 2031 10 6.1790 4.435041 0.448196 238.1279 262.8392 38.7791 20250607 8.5 4.0 P/2008 Y3 (McNaught) MPC 75710 - PK09B010 2026 06 30.4285 2.448428 0.635945 129.0025 297.1087 22.2596 20250607 13.0 4.0 P/2009 B1 (Boattini) MPC 75710 - CK09G010 2009 04 17.3298 1.135790 0.997493 175.5077 120.8728 108.0359 20250607 9.0 4.0 C/2009 G1 (STEREO) MPC 66466 - PK09K37F 2026 01 17.7518 2.835003 0.310567 143.9722 111.9438 11.3881 20250607 14.9 4.0 P/2009 KF37 MPC184407 - PK09O030 2031 01 25.8804 2.439262 0.686160 154.4228 183.7170 16.2524 20250607 12.5 4.0 P/2009 O3 (Hill) MPC 75710 - PK09Q050 2029 12 18.2032 2.901108 0.609330 209.2043 160.2071 40.9542 20250607 10.0 4.0 P/2009 Q5 (McNaught) MPC 68902 - PK09T020 2031 06 11.2689 1.792320 0.767477 216.0034 216.3137 27.5993 20250607 14.0 4.0 P/2009 T2 (La Sagra) MPC112389 - PK09W51X 2026 04 15.0730 0.802412 0.739678 118.2942 31.5224 9.5979 20250607 19.0 2.0 P/2009 WX51 (Catalina) MPC105235 - PK09Y020 2026 12 1.7362 2.370734 0.637400 172.2414 262.0833 29.9731 20250607 13.0 4.0 P/2009 Y2 (Kowalski) MPC 74247 - PK10C010 2028 09 21.8475 5.248095 0.263857 2.9170 141.5904 9.1157 20250607 9.5 4.0 P/2010 C1 (Scotti) MPC 75008 - PK10D020 2027 07 9.4680 3.682828 0.451700 120.0136 319.8763 57.1352 20250607 16.0 4.0 P/2010 D2 (WISE) MPC 75008 - PK10E020 2035 08 1.5776 2.410277 0.720879 8.2124 177.8262 15.4258 20250607 14.0 4.0 P/2010 E2 (Jarnac) MPC 75009 - PK10H020 2025 03 9.6617 3.075967 0.197745 128.0513 64.1887 14.2792 20250607 6.0 4.0 P/2010 H2 (Vales) MPC 72851 - PK10H030 2026 05 25.2323 0.043785 0.985575 26.0715 77.1824 23.1483 20250607 20.0 2.0 P/2010 H3 (SOHO) MPC 70361 - PK10H040 2027 05 21.6248 4.850297 0.267092 179.0805 44.7463 2.3178 20250607 10.5 4.0 P/2010 H4 (Scotti) MPEC 2024-GJ3 - PK10H050 2029 05 21.8734 6.058627 0.155233 174.9000 24.5167 14.0527 20250607 13.0 2.0 P/2010 H5 (Scotti) MPC 74637 - PK10J030 2037 07 19.1961 2.479028 0.724184 157.4193 106.5395 13.2265 20250607 11.0 4.0 P/2010 J3 (McMillan) MPC 98558 - PK10J81C 2034 05 29.1727 1.798140 0.778084 12.5056 30.8516 38.7689 20250607 9.0 4.0 P/2010 JC81 (WISE) MPC 84315 - PK10K43G 2023 08 26.6335 2.885502 0.482916 354.3851 325.6891 13.6502 20250607 12.7 4.0 P/2010 KG43 MPC184408 - AK10LD5N 2011 05 25.1513 1.747047 0.999955 181.5725 184.8515 64.4600 20250607 14.0 2.0 A/2010 LN135 MPEC 2024-H77 - PK10LF5H 2025 04 9.0228 2.224047 0.405984 308.5231 221.1195 8.8068 20250607 14.3 4.0 P/2010 LH155 MPC184408 - PK10T020 2024 02 23.7559 3.768461 0.325775 350.2116 57.8187 7.8597 20250607 11.5 4.0 P/2010 T2 (PANSTARRS) MPC 74248 - PK10U010 2026 09 9.8898 4.875212 0.248382 86.5374 280.8069 8.2274 20250607 9.5 4.0 P/2010 U1 (Boattini) MPC 82316 - CK10U030 2019 02 28.0286 8.439075 0.999655 88.0835 42.9923 55.5467 20250607 1.0 4.0 C/2010 U3 (Boattini) MPEC 2023-J95 - PK10U55H 2028 06 2.2941 2.893950 0.564697 225.3112 232.8274 8.0368 20250607 11.0 4.0 P/2010 UH55 (Spacewatch) MPC 79021 - PK11C020 2032 02 4.1782 5.400215 0.271120 160.2807 11.9604 10.8951 20250607 9.0 4.0 P/2011 C2 (Gibbs) MPC 84021 - PK11FE3R 2029 02 1.3026 3.767600 0.452555 349.6492 190.8478 15.9624 20250607 14.0 2.0 P/2011 FR143 (Lemmon) MPC 79866 - PK11J15B 2032 01 11.5095 5.057223 0.314768 110.6992 153.5861 19.1256 20250607 9.0 4.0 P/2011 JB15 (Spacewatch-Boattini) MPC 82317 - PK11N010 2027 12 30.9343 2.833536 0.545461 330.4938 77.6285 35.7860 20250607 11.5 4.0 P/2011 N1 (ASH) MPC 87913 - PK11P010 2030 12 21.6293 5.026331 0.326370 349.1757 4.2587 5.6519 20250607 9.0 4.0 P/2011 P1 (McNaught) MPEC 2022-ED3 - PK11S010 2014 08 24.4875 6.868388 0.200997 192.9473 218.8973 2.6885 20250607 8.0 4.0 P/2011 S1 (Gibbs) MPEC 2022-HC2 - PK11V010 2026 04 23.5464 1.742157 0.548369 269.6087 46.4914 7.3829 20250607 15.5 4.0 P/2011 V1 (Boattini) MPEC 2023-UR6 - PK11W010 2022 02 9.4392 3.325909 0.288474 283.0319 161.8074 3.7161 20250607 11.5 4.0 P/2011 W1 (PANSTARRS) MPC 82718 - PK11Y020 2027 10 2.1955 1.798814 0.711201 132.0710 309.3201 6.3919 20250607 15.0 4.0 P/2011 Y2 (Boattini) MPC 79342 - PK12B010 2030 03 8.6275 3.858979 0.410122 161.9202 36.2097 7.6055 20250607 9.0 4.0 P/2012 B1 (PANSTARRS) MPEC 2022-K19 - PK12C030 2011 10 6.7469 3.605925 0.630111 344.9542 135.3677 9.0920 13.0 4.0 P/2012 C3 (PANSTARRS) MPC 78590 - PK12F020 2029 03 19.2652 2.916443 0.540542 33.1595 226.9537 14.6982 20250607 12.0 4.0 P/2012 F2 (PANSTARRS) MPC 84931 - PK12G010 2029 03 27.9895 2.790801 0.329538 266.0173 283.2373 12.1680 20250607 15.0 4.0 P/2012 G1 (PANSTARRS) MPEC 2022-ED3 - PK12K030 2026 07 15.9127 2.100790 0.421688 172.1395 125.8057 13.1816 20250607 15.0 4.0 P/2012 K3 (Gibbs) MPC 80898 - CK12K51A 2011 11 6.2419 4.866640 0.990866 93.9909 344.8390 70.7310 20250607 8.7 4.0 C/2012 KA51 MPC184408 - PK12N00J 2037 02 1.4393 1.299842 0.846492 338.3867 315.6944 84.3223 20250607 14.5 4.0 P/2012 NJ (La Sagra) MPC 88326 - PK12O010 2025 11 1.1140 1.440107 0.593567 238.2789 91.9402 7.4280 20250607 17.5 4.0 P/2012 O1 (McNaught) MPC 81470 - PK12O020 2026 04 1.5193 1.701652 0.531233 183.4108 120.6616 24.4555 20250607 17.0 4.0 P/2012 O2 (McNaught) MPC 80899 - PK12T020 2027 01 21.0961 4.790638 0.162089 311.1848 73.8756 12.5699 20250607 10.0 4.0 P/2012 T2 (PANSTARRS) MPC 82320 - PK12T030 2027 08 9.9441 2.367430 0.615592 195.4656 114.3253 9.5537 20250607 15.0 4.0 P/2012 T3 (PANSTARRS) MPC 80900 - PK12U020 2031 12 5.7929 3.559504 0.500479 228.4442 185.2727 10.7582 20250607 12.5 4.0 P/2012 U2 (PANSTARRS) MPC 82720 - PK13A76L 2029 06 28.0735 2.044172 0.685530 27.1165 146.0925 144.9137 20250607 16.0 4.0 P/2013 AL76 (Catalina) MPC 82721 - PK13G010 2032 01 19.0838 3.384753 0.509956 51.3674 221.3161 5.4571 20250607 11.0 4.0 P/2013 G1 (Kowalski) MPC 91612 - PK13G040 2022 06 19.1364 2.617985 0.409393 214.5193 339.5876 5.9201 20250607 15.0 4.0 P/2013 G4 (PANSTARRS) MPC 84025 - PK13J020 2029 03 13.7527 2.143851 0.655853 37.8582 289.2900 15.5002 20250607 13.0 4.0 P/2013 J2 (McNaught) MPC 91613 - PK13N030 2034 04 9.7756 3.029650 0.590906 323.8815 17.5931 2.1671 20250607 13.0 4.0 P/2013 N3 (PANSTARRS) MPC 86229 - PK13N050 2031 04 2.4677 1.825797 0.731474 176.9595 187.1596 23.4123 20250607 17.0 4.0 P/2013 N5 (PANSTARRS) MPC 85834 - PK13P010 2013 02 15.6232 3.415962 0.602454 138.1273 160.7029 18.6870 20250607 12.0 4.0 P/2013 P1 (PANSTARRS) MPC 85834 - PK13R030 2024 03 20.8635 2.193182 0.277062 11.4970 341.8131 0.8653 20250607 14.0 4.0 P/2013 R3 (Catalina-PANSTARRS) MPEC 2022-V95 - PK13R03a 2024 03 20.4872 2.193199 0.276995 11.5747 341.7677 0.8644 20250607 9.0 4.0 P/2013 R3-A (Catalina-PANSTARRS) unp - PK13R03b 2024 03 20.8864 2.193234 0.277038 11.5103 341.8240 0.8656 20250607 9.0 4.0 P/2013 R3-B (Catalina-PANSTARRS) MPEC 2015-M77 - PK13T010 2027 10 12.9757 2.204063 0.623574 346.1733 10.0851 24.2694 20250607 16.5 4.0 P/2013 T1 (PANSTARRS) MPC 85835 - PK13T020 2026 06 11.3905 1.746153 0.500195 345.5649 0.8062 9.4468 20250607 16.0 4.0 P/2013 T2 (Schwartz) MPC 86643 - PK13W010 2027 03 15.9301 1.415444 0.593830 1.2454 117.8352 4.7000 20250607 17.5 4.0 P/2013 W1 (PANSTARRS) MPC 91613 - PK13Y46G 2023 01 18.8456 1.731822 0.469455 244.3077 47.0369 7.5578 20250607 10.0 4.0 P/2013 YG46 (Spacewatch) MPC101095 - PK14A020 2028 03 14.1665 2.092086 0.646684 356.2009 106.6562 24.5634 20250607 15.0 4.0 P/2014 A2 (Hill) MPC 89728 - PK14C010 2028 07 2.9813 2.646987 0.342335 188.2518 39.8494 3.2112 20250607 15.5 4.0 P/2014 C1 (TOTAS) MPEC 2024-F34 - CK14F030 2021 05 27.5683 5.731053 0.601747 5.1337 325.9777 6.5210 20250607 6.0 4.0 C/2014 F3 (Sheppard-Trujillo) MPEC 2022-WD2 - PK14L020 2030 05 26.3477 2.233338 0.646190 182.6910 149.3375 5.1905 20250607 12.0 4.0 P/2014 L2 (NEOWISE) MPC 98560 - PK14L030 2014 06 21.2414 1.873632 0.771059 178.6565 115.5303 6.2539 20250607 16.0 4.0 P/2014 L3 (Hill) MPC 90769 - PK14M040 2029 03 18.9566 2.368594 0.596002 148.1263 263.1999 3.3471 20250607 15.0 4.0 P/2014 M4 (PANSTARRS) MPC 91614 - PK14O030 2035 02 25.9971 4.685733 0.382432 204.6596 87.6245 7.7890 20250607 10.5 4.0 P/2014 O3 (PANSTARRS) MPC 98560 - CK14Od2G 2022 01 4.3116 9.984053 0.185391 255.3166 145.8258 9.0324 20250607 6.0 4.0 C/2014 OG392 (PANSTARRS) MPC182878 - PK14U040 2027 09 13.8687 1.883510 0.463730 347.8421 11.9266 6.4222 20250607 18.0 4.0 P/2014 U4 (PANSTARRS) MPC 91616 - CK14UR1N 2031 01 16.3616 10.960341 1.004214 326.0780 189.9605 95.4443 20250607 2.5 3.2 C/2014 UN271 (Bernardinelli-Bernstein) MPC184408 - PK14V010 2027 11 27.5749 2.557617 0.533410 177.6483 166.1812 22.4995 20250607 14.0 4.0 P/2014 V1 (PANSTARRS) MPC 95211 - PK14W040 2032 11 23.8926 4.243056 0.355118 67.7441 33.3049 15.2835 20250607 11.0 4.0 P/2014 W4 (PANSTARRS) MPC105542 - PK14X010 2030 06 14.9937 1.791810 0.710910 33.9522 61.5443 26.0486 20250607 15.0 4.0 P/2014 X1 (Elenin) MPC 94281 - PK15A030 2015 02 23.2702 1.165935 0.850837 249.6640 277.4863 172.5514 20250607 20.0 4.0 P/2015 A3 (PANSTARRS) MPC 92275 - PK15B010 2015 09 6.4760 5.997856 0.366905 188.6689 352.8499 18.0881 20250607 8.5 4.0 P/2015 B1 (PANSTARRS) MPC 99270 - PK15B040 2015 02 9.1014 3.719811 0.562610 227.0983 266.1369 1.7676 20250607 11.0 4.0 P/2015 B4 (Lemmon-PANSTARRS) MPC109141 - PK15C010 2032 02 2.6215 2.827617 0.568056 178.0452 348.7525 13.8943 20250607 12.5 4.0 P/2015 C1 (TOTAS-Gibbs) MPC101096 - PK15D050 2014 04 10.4649 4.544583 0.491895 39.6263 74.0873 20.5513 20250607 9.0 4.0 P/2015 D5 (Kowalski) MPC109141 - PK15D060 2034 07 1.5480 4.537333 0.362660 125.8972 45.3907 20.3017 20250607 10.5 4.0 P/2015 D6 (Lemmon-PANSTARRS) MPEC 2024-R10 - PK15K050 2032 11 2.8651 3.016874 0.551598 106.0976 134.3107 39.9256 20250607 13.5 4.0 P/2015 K5 (PANSTARRS) MPC 95213 - PK15M020 2015 08 31.0927 5.966040 0.177686 225.7394 86.6990 3.9678 20250607 8.5 4.0 P/2015 M2 (PANSTARRS) MPC107684 - PK15P040 2030 12 11.5230 2.509921 0.585033 280.7421 104.6759 8.7222 20250607 14.0 4.0 P/2015 P4 (PANSTARRS) MPC 99819 - PK15PM9D 2034 12 14.9145 4.864313 0.325090 352.6811 342.7489 2.0202 20250607 11.5 2.0 P/2015 PD229 (Cameron-ISON) MPEC 2022-K19 - PK15Q020 2015 09 13.2728 1.820502 0.752251 244.6449 228.5277 146.5501 20250607 15.5 4.0 P/2015 Q2 (Pimentel) MPC 96867 - PK15R010 2029 10 7.6452 2.160385 0.632891 300.5112 48.3912 22.6813 20250607 14.0 4.0 P/2015 R1 (PANSTARRS) MPC 98562 - PK15R020 2024 12 15.7150 2.454967 0.451987 149.8745 168.6021 15.4827 20250607 14.5 4.0 P/2015 R2 (PANSTARRS) MPC 95734 - PK15T19O 2025 11 23.5299 2.911400 0.359598 89.3407 321.6615 6.5055 20250607 14.0 4.0 P/2015 TO19 (Lemmon-PANSTARRS) MPC102953 - PK15TK0P 2016 11 3.4497 3.359965 0.537358 82.5966 6.9062 8.7784 20250607 11.0 4.0 P/2015 TP200 (LINEAR) MPC110080 - PK15W020 2015 10 8.5391 2.660623 0.635215 117.7154 294.0712 11.6206 20250607 13.0 4.0 P/2015 W2 (Catalina) MPC101098 - PK15X030 2026 10 23.6322 2.799444 0.439846 306.9750 77.2550 24.4222 20250607 15.0 4.0 P/2015 X3 (PANSTARRS) MPEC 2023-J29 - PK15X060 2025 05 11.3915 2.273712 0.174120 329.7154 106.9299 4.5658 20250607 16.0 4.0 P/2015 X6 (PANSTARRS) MPC115881 - PK16A030 2017 04 26.6068 4.822033 0.387088 340.8015 187.1299 8.5213 20250607 10.0 4.0 P/2016 A3 (PANSTARRS) MPEC 2022-OB6 - PK16A070 2027 05 27.8262 2.181421 0.569669 352.7835 220.6216 16.2782 20250607 16.0 4.0 P/2016 A7 (PANSTARRS) MPC102098 - PK16G010 2025 05 16.1423 2.041076 0.210032 111.0871 204.0104 10.9699 20250607 14.0 4.0 P/2016 G1 (PANSTARRS) MPEC 2021-P47 - CK16J020 2016 04 12.7304 1.496302 1.000364 318.2637 186.2734 130.3741 20250607 17.0 4.0 C/2016 J2 (Denneau) MPEC 2024-C04 - PK16P010 2027 03 5.9567 2.283277 0.287314 271.0395 319.0256 24.4452 20250607 15.0 4.0 P/2016 P1 (PANSTARRS) MPC102099 - PK16P050 2023 05 22.2692 4.430991 0.057299 33.8740 185.3765 7.0379 20250607 13.2 4.0 P/2016 P5 (COIAS) MPC184408 - CK16Q020 2021 05 11.6394 7.079919 1.002407 84.5284 322.3491 109.3264 20250607 6.0 4.0 C/2016 Q2 (PANSTARRS) MPEC 2024-H50 - PK16R040 2028 11 19.4852 2.803744 0.474735 174.0998 168.2668 10.8638 20250607 12.5 4.0 P/2016 R4 (Gibbs) MPEC 2022-K19 - PK16S010 2017 03 20.5657 2.380071 0.712074 273.1590 227.6434 94.7320 20250607 12.0 4.0 P/2016 S1 (PANSTARRS) MPC105543 - PK16W48M 2017 02 27.5582 1.764110 0.784169 36.1801 59.9454 117.6184 20250607 15.0 4.0 P/2016 WM48 (Lemmon) MPC106345 - CK16X010 2019 04 30.7500 7.560500 0.997211 224.6120 256.3011 26.4694 20250607 6.0 4.0 C/2016 X1 (Lemmon) MPEC 2021-P47 - CK17B030 2019 01 30.1130 3.933162 0.998824 284.7625 2.2458 54.2231 20250607 6.0 4.0 C/2017 B3 (LINEAR) MPEC 2022-OB6 - PK17B040 2017 01 5.8178 2.800894 0.364952 11.0197 121.4578 20.0584 14.5 4.0 P/2017 B4 (PANSTARRS) MPC103847 - PK17D010 2027 01 30.9520 2.710914 0.437817 8.0825 82.1923 20.7713 20250607 14.0 4.0 P/2017 D1 (Fuls) MPEC 2022-OB6 - PK17D040 2016 09 10.7516 2.785804 0.630626 212.1330 264.9132 10.5614 20250607 13.0 4.0 P/2017 D4 (PANSTARRS) MPEC 2022-OB6 - PK17F36L 2025 08 8.5709 2.830976 0.032725 90.1943 313.4516 15.6870 20250607 14.7 4.0 P/2017 FL36 (PANSTARRS) MPC184408 - PK17G010 2016 04 21.1123 2.511165 0.650855 225.2545 247.1370 5.1551 20250607 13.5 4.0 P/2017 G1 (PANSTARRS) MPEC 2024-C04 - PK17G020 2017 06 10.3877 2.821261 0.648903 105.2091 79.8960 47.9682 20250607 13.0 4.0 P/2017 G2 (PANSTARRS) MPC108595 - CK17K020 2022 12 18.5999 1.799832 0.999017 236.1748 88.2219 87.6439 20250607 1.5 4.0 C/2017 K2 (PANSTARRS) MPC184408 - PK17K030 2030 07 31.1385 2.351476 0.579118 253.2878 354.1866 4.2723 20250607 14.5 4.0 P/2017 K3 (Gasparovic) MPEC 2021-N06 - CK17K050 2020 03 25.5273 7.677590 1.002952 171.9401 102.4575 82.2791 20250607 5.0 4.0 C/2017 K5 (PANSTARRS) MPEC 2021-P47 - CK17M040 2019 01 17.6387 3.236150 1.000194 167.4132 66.0122 105.6271 20250607 6.0 4.0 C/2017 M4 (ATLAS) MPEC 2022-OB6 - PK17P010 2018 06 19.1403 5.473277 0.309012 122.7747 221.4693 7.6880 20250607 10.0 4.0 P/2017 P1 (PANSTARRS) MPC114599 - PK17S080 2027 05 4.5027 1.691831 0.391131 254.9201 191.5086 29.8401 20250607 16.0 4.0 P/2017 S8 (PANSTARRS) MPEC 2022-OB6 - CK17T020 2020 05 6.0385 1.603945 0.998995 92.7794 64.4369 57.2844 20250607 5.0 4.0 C/2017 T2 (PANSTARRS) MPEC 2024-A43 - PK17T13W 2018 06 23.7542 2.065164 0.710659 120.0174 322.1231 44.8832 20250607 15.0 2.0 P/2017 TW13 (Lemmon) MPC115882 - PK17U030 2030 03 15.7510 4.423528 0.100836 296.4524 165.0570 15.9222 20250607 11.0 4.0 P/2017 U3 (PANSTARRS) MPEC 2022-K19 - CK17U070 2019 09 16.2385 6.419353 1.002731 326.4189 276.3203 142.6394 20250607 8.3 2.0 C/2017 U7 (PANSTARRS) MPEC 2023-A50 - PK17W030 2018 02 26.6644 3.854171 0.507046 327.7722 210.0686 18.1881 20250607 10.5 4.0 P/2017 W3 (Gibbs) MPC114601 - CK17Y020 2020 11 4.9168 4.621500 1.001077 147.8089 66.0298 128.4479 20250607 15.0 4.0 C/2017 Y2 (PANSTARRS) MPEC 2024-DC6 - PK17Y030 2018 02 6.3762 1.276999 0.869622 67.3287 154.0206 27.6300 20250607 16.5 4.0 P/2017 Y3 (Leonard) MPC111770 - CK18A030 2019 01 8.6721 3.293329 0.990471 86.5118 194.3574 139.6082 20250607 8.5 4.0 C/2018 A3 (ATLAS) MPEC 2021-P47 - PK18A050 2031 01 31.2907 2.674393 0.524494 359.5535 87.7836 23.6241 20250607 15.0 4.0 P/2018 A5 (PANSTARRS) MPC109147 - CK18A060 2019 07 10.2877 3.016795 0.798837 264.2674 340.4579 77.1597 20250607 9.0 4.0 C/2018 A6 (Gibbs) MPEC 2024-JU4 - PK18C010 2031 07 31.0591 2.640219 0.532661 235.8064 270.1941 5.1014 20250607 13.5 4.0 P/2018 C1 (Lemmon-Read) MPC114601 - CK18D04O 2019 08 17.0981 2.421737 0.905123 176.4219 251.3950 160.4453 20250607 11.0 4.0 C/2018 DO4 (Lemmon) MPEC 2022-M88 - CK18F010 2018 12 10.1367 2.991277 0.986220 71.4247 177.3216 46.1741 20250607 11.5 4.0 C/2018 F1 (Grauer) MPEC 2021-R75 - CK18F040 2019 11 30.8722 3.448581 0.998027 263.1952 26.5384 78.1374 20250607 11.0 6.0 C/2018 F4 (PANSTARRS) MPEC 2023-A50 - CK18F04a 2019 11 30.8603 3.448449 0.997974 263.1919 26.5386 78.1376 20250607 11.0 6.0 C/2018 F4-A MPEC 2021-Y10 - CK18F04b 2019 11 30.7971 3.448266 0.998063 263.1777 26.5380 78.1386 20250607 11.0 6.0 C/2018 F4-B MPEC 2023-D41 - PK18H020 2027 03 18.2732 2.028743 0.539854 119.1890 67.9854 7.4169 20250607 16.6 2.0 P/2018 H2 (PANSTARRS) MPC114602 - CK18K03J 2019 09 8.7371 3.617435 0.994796 217.5340 91.6952 136.6205 20250607 12.2 2.0 C/2018 KJ3 (Lemmon) MPEC 2021-R75 - CK18L020 2018 11 29.5042 1.721614 0.992696 56.3444 242.9899 67.2171 20250607 10.0 4.0 C/2018 L2 (ATLAS) MPEC 2021-P47 - PK18L040 2029 07 28.5976 1.691044 0.658289 140.5037 145.2212 26.5944 20250607 17.5 4.0 P/2018 L4 (PANSTARRS) MPC114603 - CK18N020 2019 11 12.0841 3.135556 1.002015 25.3242 24.5271 77.4962 20250607 6.0 4.0 C/2018 N2 (ASASSN) MPEC 2022-YN2 - PK18P040 2018 11 6.9803 3.689153 0.449038 8.5163 353.1586 23.0782 20250607 12.0 4.0 P/2018 P4 (PANSTARRS) MPC114603 - CK18P050 2019 02 25.6615 4.603604 0.641580 132.0336 216.2708 7.2465 20250607 11.0 4.0 C/2018 P5 (PANSTARRS) MPEC 2021-P47 - CK18R030 2019 06 8.0040 1.284393 0.999284 112.8064 324.3614 69.6873 20250607 9.5 4.0 C/2018 R3 (Lemmon) MPC118841 - CK18R050 2019 01 10.7774 3.637852 0.841696 178.2719 171.2693 103.6829 20250607 11.5 4.0 C/2018 R5 (Lemmon) MPC114603 - CK18S020 2018 11 5.3549 5.491210 0.617860 290.9505 85.1076 64.1107 20250607 7.5 4.0 C/2018 S2 (TESS) MPEC 2022-QC6 - CK18U010 2021 11 2.1430 4.985979 1.000137 180.3529 75.5139 108.3258 20250607 5.0 4.0 C/2018 U1 (Lemmon) MPC184408 - CK18V010 2018 12 4.1309 0.390689 1.000461 89.5771 129.6073 144.2018 20250607 12.0 4.0 C/2018 V1 (Machholz-Fujikawa-Iwamoto) MPC114604 - CK18V020 2018 11 26.3883 2.492213 0.901297 319.2890 357.2235 159.1614 20250607 15.0 4.0 C/2018 V2 (ATLAS) MPC115884 - PK18V02N 2026 08 15.7390 2.119325 0.478155 138.9250 226.4381 18.2569 20250607 15.0 4.0 P/2018 VN2 (Leonard) MPEC 2025-A40 - AK18V030 2019 09 10.4700 1.329916 0.989547 3.5754 308.8207 164.9131 20250607 15.7 2.0 A/2018 V3 MPEC 2025-A40 - CK18V040 2019 03 2.3988 3.203854 0.985176 0.0990 78.2467 69.0427 20250607 12.5 4.0 C/2018 V4 (Africano) MPEC 2022-M21 - PK18V050 2018 10 6.1754 4.708263 0.475773 260.8902 171.2921 10.5775 20250607 12.5 4.0 P/2018 V5 (Trujillo-Sheppard) MPEC 2021-P47 - CK18W010 2019 05 13.9091 1.351473 0.937839 251.1664 233.6321 83.3960 20250607 15.5 2.0 C/2018 W1 (Catalina) MPEC 2021-P47 - CK18W020 2019 09 5.7173 1.465415 1.000942 158.2375 181.9813 116.5371 20250607 9.5 4.0 C/2018 W2 (Africano) MPEC 2021-P47 - AK18W030 2021 04 13.1623 4.281970 0.993893 313.8642 251.6879 104.8380 20250607 10.7 2.0 A/2018 W3 MPEC 2023-M14 - CK18X020 2019 07 9.8325 2.111030 0.985017 162.0079 340.6351 23.1075 20250607 12.0 4.0 C/2018 X2 (Fitzsimmons) MPC119996 - CK18X030 2019 01 1.6370 2.694627 0.782903 359.8669 78.7968 43.4258 20250607 14.5 4.0 C/2018 X3 (PANSTARRS) MPC114604 - CK18Y010 2019 02 3.3789 1.293307 0.989765 357.8669 147.3364 160.4824 20250607 11.5 4.0 C/2018 Y1 (Iwamoto) MPEC 2024-A43 - PK18Y020 2019 01 4.6154 3.877713 0.480016 162.3886 297.1170 11.6953 20250607 11.5 4.0 P/2018 Y2 (Africano) MPC114605 - PK19A010 2030 05 6.9099 2.196809 0.570301 150.7861 312.2107 13.7719 20250607 16.0 4.0 P/2019 A1 (PANSTARRS) MPC114605 - PK19A020 2018 11 24.2564 3.521740 0.383282 323.9571 139.3670 14.8735 20250607 10.5 4.0 P/2019 A2 (ATLAS) MPEC 2021-P47 - PK19A030 2024 03 2.7533 2.304560 0.267513 325.6567 31.2701 15.3555 20250607 16.0 4.0 P/2019 A3 (PANSTARRS) MPEC 2022-M21 - PK19A040 2027 05 26.8446 2.385964 0.087418 343.2376 119.3537 13.3058 20250607 15.0 4.0 P/2019 A4 (PANSTARRS) MPEC 2022-L66 - CK19A050 2019 06 7.0260 6.312613 0.706451 355.8263 146.5139 67.5511 20250607 9.5 4.0 C/2019 A5 (PANSTARRS) MPEC 2021-P47 - PK19A060 2031 01 25.5628 1.926517 0.640361 156.2505 280.1736 33.2982 20250607 16.0 4.0 P/2019 A6 (Lemmon-PANSTARRS) MPC114605 - CK19A090 2019 07 27.2174 1.426565 0.963709 237.8789 278.4704 84.3987 20250607 15.0 4.0 C/2019 A9 (PANSTARRS) MPC118842 - CK19B010 2019 03 18.2587 1.603638 0.988521 174.8265 290.2340 123.4919 20250607 16.0 4.0 C/2019 B1 (Africano) MPEC 2022-L66 - PK19B020 2027 02 24.3398 2.523184 0.357708 0.5964 175.6527 16.9514 20250607 14.5 4.0 P/2019 B2 (Groeller) MPC115885 - CK19B030 2021 01 19.5922 6.829860 0.998140 263.9977 358.4023 66.6036 20250607 5.5 4.0 C/2019 B3 (PANSTARRS) MPEC 2024-JU4 - CK19C010 2020 05 4.5580 6.567327 0.990459 319.0168 212.3696 36.0382 20250607 10.0 4.0 C/2019 C1 (ATLAS) MPEC 2021-P47 - CK19D010 2019 05 8.8149 1.592131 0.988339 70.7163 231.6664 34.0111 20250607 13.0 4.0 C/2019 D1 (Flewelling) MPEC 2022-O08 - CK19E030 2023 11 15.6281 10.313267 0.998094 280.7189 347.1958 84.3147 20250607 2.5 4.0 C/2019 E3 (ATLAS) MPC182878 - CK19F010 2021 06 21.1716 3.608383 1.000313 251.3041 38.6641 54.2523 20250607 5.5 4.0 C/2019 F1 (ATLAS-Africano) MPEC 2024-GJ3 - CK19F020 2019 09 7.7544 2.239065 0.864765 11.6106 175.3470 19.3344 20250607 12.0 4.0 C/2019 F2 (ATLAS) MPEC 2025-A40 - CK19G020 2019 12 6.4882 2.305763 0.994256 82.7815 208.2360 159.2528 20250607 15.0 4.0 C/2019 G2 (PANSTARRS) MPEC 2024-E01 - AK19G030 2018 12 3.6909 2.836511 0.834271 161.7303 49.8933 156.8086 20250607 17.1 2.0 A/2019 G3 MPEC 2022-VC5 - PK19G21G 2019 05 9.6453 3.946111 0.471650 208.5911 340.5655 6.0831 20250607 12.0 4.0 P/2019 GG21 (PANSTARRS) MPC114607 - CK19H010 2019 04 26.8796 1.839938 0.991933 19.2422 269.3120 104.3575 20250607 15.5 4.0 C/2019 H1 (NEOWISE) MPEC 2022-M21 - CK19J010 2019 04 5.9084 2.481788 0.962673 167.5701 98.2355 24.5224 20250607 12.0 4.0 C/2019 J1 (Lemmon) MPEC 2023-A50 - CK19J020 2019 07 21.1460 1.714287 0.989295 98.5503 25.4646 105.2137 20250607 13.0 4.0 C/2019 J2 (Palomar) MPEC 2021-R75 - CK19J030 2019 08 1.9360 2.361675 0.999899 16.4923 270.6554 131.2940 20250607 13.5 4.0 C/2019 J3 (ATLAS) MPC117071 - CK19J06U 2019 06 2.8910 2.031730 0.999865 94.7738 21.6881 148.2998 20250607 14.5 4.0 C/2019 JU6 (ATLAS) MPEC 2022-M21 - CK19K010 2020 02 10.9125 2.021314 0.999316 265.7810 73.3114 87.0181 20250607 10.0 4.0 C/2019 K1 (ATLAS) MPEC 2022-O08 - CK19K040 2019 06 15.2946 2.275831 0.998603 140.0207 180.2964 105.2880 20250607 12.5 4.0 C/2019 K4 (Ye) MPC119997 - CK19K050 2019 06 21.3378 2.054940 0.987793 175.1427 177.2762 15.2926 20250607 13.0 4.0 C/2019 K5 (Young) MPEC 2021-P47 - CK19K060 2020 05 18.5745 3.917397 0.995796 187.4327 42.9796 132.3893 20250607 11.5 4.0 C/2019 K6 (PANSTARRS) MPEC 2021-P47 - CK19K070 2020 06 17.1324 4.474306 1.000350 27.3577 308.0355 103.4781 20250607 6.0 4.0 C/2019 K7 (Smith) MPEC 2024-GJ3 - CK19K080 2019 07 20.1988 3.198434 0.998094 85.3722 290.9898 93.0493 20250607 11.5 4.0 C/2019 K8 (ATLAS) MPEC 2021-R75 - CK19L010 2019 08 7.1551 2.905220 0.704097 50.0115 254.4272 9.9738 20250607 13.5 4.0 C/2019 L1 (PANSTARRS) MPEC 2023-A50 - CK19L020 2019 04 3.8262 1.621031 0.935537 18.8489 12.5816 152.1494 20250607 16.0 4.0 C/2019 L2 (NEOWISE) MPC115886 - PK19L02D 2020 01 30.8495 4.491880 0.131061 116.4901 178.7603 11.6100 20250607 8.5 4.0 P/2019 LD2 (ATLAS) MPEC 2024-GJ3 - CK19L030 2022 01 10.1130 3.558530 1.003131 171.7472 290.7181 48.3457 20250607 4.5 4.0 C/2019 L3 (ATLAS) MPC184408 - PK19L04M 2019 06 19.9686 2.360036 0.586138 68.2081 72.8893 36.4164 20250607 9.5 4.0 P/2019 LM4 (Palomar) MPEC 2024-YC7 - CK19L07B 2019 03 27.5408 2.494982 0.928766 336.7737 4.0006 164.2792 20250607 17.0 4.0 C/2019 LB7 (Kleyna) MPC118095 - CK19M030 2018 12 31.4276 2.424744 0.999514 87.9348 155.0477 99.6477 20250607 12.2 4.0 C/2019 M3 (ATLAS) MPC118095 - CK19M040 2019 09 9.6901 9.191044 1.000464 260.3428 52.6427 65.6901 20250607 5.0 4.0 C/2019 M4 (TESS) MPEC 2023-JA2 - CK19N010 2020 11 30.5348 1.703133 0.998252 193.3450 13.5150 82.5267 20250607 7.5 4.0 C/2019 N1 (ATLAS) MPEC 2023-C45 - AK19N020 2019 08 22.4476 1.940413 0.998304 347.0719 276.2229 89.3219 20250607 12.5 2.0 A/2019 N2 MPEC 2023-CD8 - CK19N03J 2020 10 22.2849 4.362925 1.001466 246.8732 142.4921 99.3378 20250607 9.0 4.0 C/2019 NJ3 (Lemmon) MPEC 2022-A21 - CK19O020 2023 04 6.0927 9.681030 0.835173 129.5768 48.2626 93.3005 20250607 5.0 4.0 C/2019 O2 (PANSTARRS) MPC184408 - CK19O030 2021 03 8.4843 8.820771 1.002797 60.1021 300.4753 89.7968 20250607 3.5 4.0 C/2019 O3 (Palomar) MPC182878 - AK19O040 2020 02 11.1386 3.642513 0.890395 61.8267 354.9267 115.0075 20250607 15.5 2.0 A/2019 O4 MPEC 2021-P47 - CK19Q010 2020 07 22.1516 5.002964 1.002371 56.2554 42.4664 155.7220 20250607 8.5 4.0 C/2019 Q1 (Lemmon) MPEC 2024-EF7 - AK19Q020 2019 07 23.6013 1.261031 0.978545 176.5074 188.1204 158.9738 20250607 18.0 2.0 A/2019 Q2 MPC117072 - PK19S020 2029 06 21.4470 3.775654 0.204677 216.9392 93.1805 10.4637 20250607 13.5 4.0 P/2019 S2 (PANSTARRS) MPC117072 - PK19S030 2025 12 19.1649 1.807089 0.470760 213.0946 150.1411 8.6940 20250607 18.3 4.0 P/2019 S3 (PANSTARRS) MPEC 2022-CN4 - CK19S040 2020 04 9.3386 3.439256 0.986161 71.3710 63.1561 92.0969 20250607 11.0 4.0 C/2019 S4 (Lemmon) MPEC 2021-S45 - AK19T010 2021 01 14.9521 4.274970 0.889713 90.9858 6.9309 120.8229 20250607 13.0 2.0 A/2019 T1 MPEC 2023-N01 - CK19T020 2021 04 22.5340 2.643422 0.999247 239.3889 155.6549 111.3753 20250607 9.0 4.0 C/2019 T2 (Lemmon) MPEC 2023-R20 - CK19T030 2021 03 4.6965 5.953506 0.998677 112.4875 139.5427 121.8729 20250607 6.8 4.0 C/2019 T3 (ATLAS) MPEC 2023-UR6 - CK19T040 2022 06 8.6611 4.237680 0.995185 351.1092 199.9039 53.6247 20250607 5.0 4.0 C/2019 T4 (ATLAS) MPC182878 - PK19T050 2019 08 3.4061 1.523141 0.809784 189.6222 247.6125 33.4937 20250607 15.0 4.0 P/2019 T5 (ATLAS) MPEC 2021-P47 - PK19T060 2019 11 8.9102 2.054685 0.622490 329.0578 71.2472 18.6988 20250607 15.5 4.0 P/2019 T6 (PANSTARRS) MPEC 2021-P47 - PK19U040 2026 04 28.5197 1.844757 0.475757 181.0805 200.0024 11.6954 20250607 19.0 4.0 P/2019 U4 (PANSTARRS) MPC118096 - CK19U050 2023 03 29.4647 3.624215 1.000219 181.4509 2.6141 113.5124 20250607 4.5 4.0 C/2019 U5 (PANSTARRS) MPC184408 - CK19U060 2020 06 18.3121 0.906750 0.997020 329.4329 235.7536 60.9844 20250607 10.0 4.0 C/2019 U6 (Lemmon) MPEC 2022-H04 - CK19V010 2020 07 17.5265 3.092879 0.998798 51.1918 83.1481 61.9482 20250607 11.0 4.0 C/2019 V1 (Borisov) MPEC 2022-N37 - PK19V020 2020 10 17.1943 5.007689 0.331847 335.6322 189.1399 11.8069 20250607 10.0 4.0 P/2019 V2 (Groeller) MPEC 2022-L66 - PK19W010 2029 01 22.2549 3.333179 0.267202 18.8852 35.3627 23.4670 20250607 12.9 4.0 P/2019 W1 (PANSTARRS) MPEC 2023-A50 - PK19X010 2019 07 24.6454 4.301760 0.303843 36.9831 43.6774 10.2460 20250607 10.4 4.0 P/2019 X1 (Pruyne) MPEC 2021-P47 - PK19X020 2026 11 15.2893 1.815397 0.500464 213.5123 250.8318 15.8947 20250607 18.0 4.0 P/2019 X2 (Pan-STARRS) MPEC 2020-C98 - CK19Y010 2020 03 17.1646 0.826439 0.990624 57.9144 31.4813 73.2852 20250607 13.7 4.0 C/2019 Y1 (ATLAS) MPC119999 - CK19Y040 2020 05 29.7096 0.257205 0.999224 177.4116 120.7883 44.9416 20250607 11.8 6.0 C/2019 Y4 (ATLAS) MPEC 2024-A43 - CK19Y04a 2020 05 29.7621 0.255360 1.001366 177.2438 121.1559 45.3766 20250607 11.6 6.0 C/2019 Y4-A (ATLAS) MPEC 2020-L06 - CK19Y04b 2020 05 29.7179 0.256893 0.999813 177.3707 120.8515 45.0231 20250607 12.1 6.0 C/2019 Y4-B (ATLAS) MPEC 2025-CE3 - CK19Y04c 2020 05 29.7157 0.256432 1.002095 177.2766 120.8832 45.1603 20250607 12.7 6.0 C/2019 Y4-C (ATLAS) MPEC 2020-L06 - CK19Y04d 2020 05 29.8045 0.255753 0.996202 177.4194 121.2451 45.2131 20250607 12.5 6.0 C/2019 Y4-D (ATLAS) MPEC 2020-L06 - CK19Y050 2019 08 16.6201 4.933453 0.992834 303.6621 51.7653 82.7732 20250607 11.0 4.0 C/2019 Y5 (PANSTARRS) MPEC 2023-A50 - AK20A010 2019 11 30.2879 1.671333 0.934371 302.4018 119.0673 149.0316 20250607 18.0 2.0 A/2020 A1 MPEC 2023-A50 - CK20A020 2020 01 7.1876 0.975117 0.998998 68.0146 286.1913 120.5076 20250607 13.5 4.0 C/2020 A2 (Iwamoto) MPEC 2022-YN2 - CK20A030 2019 06 26.9725 5.753209 0.998928 268.2389 120.7989 146.6221 20250607 8.0 4.0 C/2020 A3 (ATLAS) MPEC 2023-A50 - PK20A040 2019 11 24.4237 2.834211 0.654471 144.8988 312.2840 25.0022 20250607 15.0 4.0 P/2020 A4 (PANSTARRS-Lemmon) MPEC 2022-P91 - AK20B010 2019 12 27.6151 1.739119 0.966596 154.8721 309.8077 18.5397 20250607 21.0 2.0 A/2020 B1 MPEC 2020-N08 - CK20B020 2020 01 27.2646 2.756092 0.959396 143.6251 354.1828 55.7547 20250607 10.0 4.0 C/2020 B2 (Lemmon) MPEC 2020-HN5 - CK20B030 2019 10 20.7192 3.327567 0.996811 324.9263 185.7510 20.7068 20250607 13.0 4.0 C/2020 B3 (Rankin) MPEC 2022-N37 - PK20B040 2021 11 19.2169 6.435416 0.192857 342.0445 185.9505 11.6032 20250607 10.5 4.0 P/2020 B4 (Sheppard) MPEC 2023-KD6 - CK20F020 2022 07 12.5842 8.813556 1.002706 48.2395 250.3012 163.5896 20250607 4.5 4.0 C/2020 F2 (ATLAS) MPC184409 - CK20F030 2020 07 4.8900 0.293591 0.999268 37.3522 61.0792 129.1187 20250607 7.5 5.2 C/2020 F3 (NEOWISE) MPEC 2021-O56 - CK20F050 2021 03 16.2291 4.326248 0.973705 310.6213 350.5390 52.2309 20250607 6.5 3.2 C/2020 F5 (MASTER) MPEC 2024-UQ8 - CK20F060 2020 04 10.4152 3.498242 0.989826 344.3409 207.8439 174.5841 20250607 14.5 2.8 C/2020 F6 (PANSTARRS) MPEC 2020-L06 - CK20F070 2021 11 13.8481 5.334768 0.990629 227.9809 321.8236 93.9809 20250607 7.0 4.0 C/2020 F7 (Lemmon) MPEC 2024-A43 - CK20F080 2020 05 25.8895 0.432547 1.000069 68.1080 259.8021 110.5559 20250607 10.0 4.0 C/2020 F8 (SWAN) MPEC 2023-J29 - PK20G010 2027 01 24.2683 0.501998 0.860811 207.6459 240.0998 18.5075 20250607 17.0 4.0 P/2020 G1 (Pimentel) MPEC 2020-L06 - CK20H020 2020 04 26.9455 0.828532 0.995332 26.5869 277.6716 124.7810 20250607 14.0 3.2 C/2020 H2 (Pruyne) MPEC 2022-YB4 - CK20H030 2020 06 5.7161 2.300288 1.000000 30.4456 270.6227 62.5292 13.5 4.0 C/2020 H3 (Wierzchos) MPEC 2020-HM1 - CK20H040 2020 08 29.2557 0.927286 0.980619 117.5733 307.4623 84.4946 20250607 15.0 3.2 C/2020 H4 (Leonard) MPEC 2020-L06 - CK20H050 2020 12 9.9597 9.335266 0.998411 326.2665 210.6156 70.2305 20250607 5.0 4.0 C/2020 H5 (Robinson) MPC184409 - CK20H060 2021 09 29.6102 4.697042 0.997678 20.1959 213.6939 79.9878 20250607 8.0 3.2 C/2020 H6 (ATLAS) MPEC 2024-JU4 - CK20H070 2020 06 2.9509 4.419545 0.996854 82.6780 323.5194 135.9235 11.0 4.0 C/2020 H7 (Lemmon) MPEC 2020-KB7 - CK20H080 2020 06 4.7787 4.663848 0.992112 128.8241 68.4393 99.7033 20250607 10.5 4.0 C/2020 H8 (PANSTARRS) MPEC 2021-N06 - AK20H090 2019 12 21.8026 2.562294 0.992524 312.6276 213.1236 137.8740 20250607 18.0 2.0 A/2020 H9 MPEC 2022-ED3 - CK20H110 2020 09 12.6500 7.621066 0.999846 91.3687 303.0568 151.3741 20250607 8.5 4.0 C/2020 H11 (PANSTARRS-Lemmon) MPEC 2023-HN7 - CK20J010 2021 04 18.0746 3.345343 0.999707 341.5855 226.5878 142.3071 20250607 8.5 3.2 C/2020 J1 (SONEAR) MPEC 2023-KD6 - CK20K010 2023 05 8.7823 3.073945 0.998791 213.9710 94.3662 89.6715 20250607 5.5 4.0 C/2020 K1 (PANSTARRS) MPC184409 - CK20K020 2020 08 4.5239 8.880282 1.001071 67.3121 288.4330 90.9896 20250607 10.8 4.0 C/2020 K2 (PANSTARRS) MPEC 2021-N06 - CK20K030 2020 06 1.0031 1.583069 1.000000 64.4924 28.3546 129.0152 14.5 4.0 C/2020 K3 (Leonard) MPEC 2020-KF9 - CK20K040 2020 03 4.9542 1.744399 0.927098 308.7891 264.2742 125.5850 20250607 16.5 4.0 C/2020 K4 (PANSTARRS) MPEC 2020-L06 - CK20K050 2021 06 4.3091 1.540542 1.000824 249.6409 86.1419 67.0689 20250607 11.0 4.0 C/2020 K5 (PANSTARRS) MPEC 2021-R75 - CK20K060 2021 09 14.7971 5.866220 1.002202 44.2810 291.5985 103.6312 20250607 8.0 4.0 C/2020 K6 (Rankin) MPEC 2023-N01 - CK20K070 2019 10 25.3870 6.388756 0.932568 358.0878 286.1313 32.0444 20250607 8.0 4.0 C/2020 K7 (PANSTARRS) MPEC 2023-A50 - CK20K080 2020 09 15.6813 0.471455 1.000315 260.1502 181.3120 31.3845 20250607 15.0 3.2 C/2020 K8 (Catalina-ATLAS) MPEC 2021-P47 - PK20K090 2029 09 29.3024 2.860221 0.320166 197.0913 166.3114 23.1909 20250607 12.5 4.0 P/2020 K9 (Lemmon-PANSTARRS) MPEC 2021-BE3 - PK20M010 2019 12 23.2357 2.796900 0.473479 72.4980 142.6142 8.5345 20250607 14.5 4.0 P/2020 M1 (PANSTARRS) MPEC 2023-C45 - CK20M030 2020 10 25.7689 1.274863 0.953304 328.6658 71.1752 23.4705 20250607 14.5 4.0 C/2020 M3 (ATLAS) MPEC 2022-H30 - AK20M040 2020 11 22.8486 5.941110 0.999816 104.4856 348.6151 160.1033 20250607 14.5 2.0 A/2020 M4 MPEC 2023-N01 - PK20M04K 2027 04 18.3303 6.130381 0.015009 93.5441 0.6661 6.7816 20250607 8.0 4.0 P/2020 MK4 (PANSTARRS) MPEC 2024-NE4 - CK20M050 2021 08 19.7621 2.999886 1.000129 126.2459 352.0226 93.1751 20250607 9.0 4.0 C/2020 M5 (ATLAS) MPEC 2023-FK0 - CK20N010 2021 03 13.1169 1.317532 1.000850 186.8327 279.8579 29.7650 20250607 12.5 4.0 C/2020 N1 (PANSTARRS) MPEC 2022-GA9 - CK20N020 2020 08 24.3176 1.784198 0.982413 331.2079 257.1800 161.0386 20250607 16.0 3.2 C/2020 N2 (ATLAS) MPEC 2021-P47 - CK20O020 2021 08 27.3240 4.856870 0.999663 10.1789 256.7916 71.7622 20250607 8.0 3.2 C/2020 O2 (Amaral) MPEC 2024-JU4 - PK20O030 2021 01 25.1742 4.170403 0.102411 81.2177 266.8184 8.4445 20250607 12.0 4.0 P/2020 O3 (PANSTARRS) MPEC 2023-C45 - CK20P010 2020 10 21.1886 0.341720 1.000434 8.9310 53.4868 45.1169 20250607 14.0 3.2 C/2020 P1 (NEOWISE) MPEC 2021-BE3 - CK20P030 2021 04 22.8871 6.815891 1.003658 82.3472 19.4835 61.8572 20250607 6.0 4.0 C/2020 P3 (ATLAS) MPEC 2024-JU4 - CK20P06V 2021 09 25.8366 2.291157 0.945027 71.2847 329.1296 128.1565 20250607 10.0 4.0 C/2020 PV6 (PANSTARRS) MPEC 2022-PB4 - CK20Q010 2020 08 15.2711 1.319407 0.978829 10.0270 52.4106 142.9250 20250607 14.0 4.0 C/2020 Q1 (Borisov) MPEC 2022-L66 - CK20Q020 2020 01 24.9635 5.419456 0.488881 118.2130 179.8263 3.3357 20250607 12.0 3.2 C/2020 Q2 (PANSTARRS) MPEC 2023-CD7 - CK20R020 2022 02 25.3601 4.699062 0.989085 211.8826 195.1252 53.2165 20250607 9.0 4.0 C/2020 R2 (PANSTARRS) MPEC 2024-F34 - CK20R040 2021 03 2.2325 1.020830 0.989514 46.5186 323.2349 164.4053 20250607 13.5 4.0 C/2020 R4 (ATLAS) MPEC 2022-K19 - PK20R050 2020 05 27.5669 3.429509 0.313162 82.7558 272.9389 11.4395 20250607 9.5 6.0 P/2020 R5 (PANSTARRS) MPEC 2023-C45 - CK20R060 2019 09 6.8647 3.139364 0.989227 271.9984 12.2325 82.8877 20250607 11.0 4.0 C/2020 R6 (Rankin) MPEC 2021-Y10 - CK20R070 2022 09 16.0471 2.952033 0.999679 347.7650 268.3095 114.9031 20250607 7.0 3.2 C/2020 R7 (ATLAS) MPEC 2024-PC5 - PK20S010 2021 01 16.9719 2.959494 0.506899 255.1596 129.4919 13.7151 20250607 14.0 4.0 P/2020 S1 (PANSTARRS) MPEC 2021-BE3 - CK20S020 2020 12 22.0656 1.763558 0.827952 202.4217 197.7088 22.3764 20250607 17.0 4.0 C/2020 S2 (PANSTARRS) MPEC 2022-ST7 - CK20S030 2020 12 11.3810 0.392767 0.997224 350.0482 222.5234 20.0630 20250607 13.5 3.2 C/2020 S3 (Erasmus) MPEC 2024-JU4 - CK20S040 2023 02 9.5609 3.370380 1.002706 21.0567 117.6836 20.5699 20250607 8.5 3.2 C/2020 S4 (PANSTARRS) MPEC 2024-N80 - PK20S050 2028 10 11.2856 2.689218 0.337365 53.2759 316.0220 12.3403 20250607 14.5 4.0 P/2020 S5 (PANSTARRS) MPEC 2021-BE3 - PK20S070 2020 11 17.6246 2.973947 0.409541 40.6622 328.0835 16.0706 20250607 14.5 4.0 P/2020 S7 (PANSTARRS) MPEC 2021-BE3 - CK20S080 2021 04 10.3819 2.355765 0.990170 160.1328 24.0117 108.5424 20250607 12.5 4.0 C/2020 S8 (Lemmon) MPEC 2021-P47 - CK20T020 2021 07 10.5659 2.052772 0.992398 150.3491 83.0362 27.8394 20250607 11.0 3.2 C/2020 T2 (Palomar) MPEC 2022-TD3 - PK20T030 2027 08 27.4402 1.433037 0.592438 357.0787 73.9920 7.2986 20250607 18.0 3.2 P/2020 T3 (PANSTARRS) MPEC 2021-N06 - CK20T040 2021 07 6.0639 2.187751 1.000638 79.5710 50.6081 83.8300 20250607 13.0 3.2 C/2020 T4 (PANSTARRS) MPEC 2021-N06 - CK20T050 2020 10 7.7922 1.897722 0.996890 90.3835 237.8420 66.5562 20250607 16.0 4.0 C/2020 T5 (Lemmon) MPEC 2021-BE3 - PK20U020 2028 05 1.4483 1.846095 0.511341 84.7672 342.8188 6.4197 20250607 18.0 4.0 P/2020 U2 (PANSTARRS) MPEC 2021-N06 - CK20U030 2021 02 6.0276 2.285339 0.966218 124.5097 282.6018 30.1389 20250607 15.0 4.0 C/2020 U3 (Rankin) MPEC 2021-W31 - CK20U040 2022 04 9.9863 5.361749 1.001188 70.1722 120.4058 167.0033 20250607 7.0 4.0 C/2020 U4 (PANSTARRS) MPEC 2024-TD8 - CK20U050 2022 04 28.3593 3.756862 0.999633 75.4656 107.3132 97.3110 20250607 8.0 4.0 C/2020 U5 (PANSTARRS) MPEC 2024-GJ3 - CK20V020 2023 05 8.5206 2.229212 1.001042 162.4545 212.3975 131.6124 20250607 4.9 4.0 C/2020 V2 (ZTF) MPC184409 - PK20V030 2021 02 15.5037 6.239314 0.257887 249.7916 198.2685 23.0217 20250607 8.3 4.0 P/2020 V3 (PANSTARRS) MPEC 2023-D72 - PK20V040 2021 07 20.6315 5.153716 0.451584 257.2447 203.4888 14.2373 20250607 9.0 4.0 P/2020 V4 (Rankin) MPEC 2024-F34 - PK20W010 2020 04 10.4063 5.307350 0.265509 265.3900 124.3865 10.7773 20250607 10.0 4.0 P/2020 W1 (Rankin) MPEC 2021-BE3 - CK20W050 2020 11 30.9038 3.370670 1.002128 24.6030 75.4670 88.6158 20250607 15.0 4.0 C/2020 W5 (Lemmon) MPEC 2021-BE3 - PK20W05J 2021 06 30.5050 4.980199 0.172110 338.0844 177.7654 22.2881 20250607 8.5 4.0 P/2020 WJ5 (Lemmon) MPEC 2024-PC5 - PK20X010 2030 03 18.7650 2.882991 0.364433 323.5275 55.9872 31.6920 20250607 13.0 4.0 P/2020 X1 (ATLAS) MPEC 2024-F34 - CK20X020 2020 11 17.1666 3.832050 0.768311 347.5642 105.3570 18.1865 20250607 10.6 4.0 C/2020 X2 (ATLAS) MPEC 2024-A43 - CK20X040 2020 11 15.4578 5.224125 0.871305 140.2938 161.9526 80.6570 20250607 9.0 4.0 C/2020 X4 (Leonard) MPEC 2021-S45 - CK20Y020 2022 06 17.7974 3.146147 0.997554 266.4142 26.5385 101.2102 20250607 6.5 4.0 C/2020 Y2 (ATLAS) MPEC 2024-YC7 - CK20Y030 2020 12 3.2291 1.990414 0.985532 341.8517 191.3492 83.1414 20250607 13.5 4.0 C/2020 Y3 (ATLAS) MPEC 2021-R75 - CK21A010 2022 01 3.7850 0.615434 1.000239 225.1377 255.9115 132.7545 20250607 8.5 4.0 C/2021 A1 (Leonard) MPEC 2025-A40 - CK21A020 2021 01 21.8903 1.416044 0.993824 338.7973 125.0653 107.0525 20250607 13.5 4.0 C/2021 A2 (NEOWISE) MPEC 2025-A40 - CK21A040 2021 03 19.5685 1.150267 0.972946 204.7523 307.0900 111.6437 20250607 16.0 4.0 C/2021 A4 (NEOWISE) MPEC 2022-ED3 - PK21A050 2026 03 11.2539 2.620536 0.139804 61.5301 328.8096 18.1893 20250607 15.0 4.0 P/2021 A5 (PANSTARRS) MPEC 2021-BE3 - CK21A060 2021 05 3.0564 7.924680 0.999336 351.6242 164.0269 75.5646 20250607 7.0 4.0 C/2021 A6 (PANSTARRS) MPEC 2024-P23 - CK21A070 2021 07 15.1561 1.965149 0.998954 355.9994 154.4051 78.2156 20250607 10.0 4.0 C/2021 A7 (NEOWISE) MPEC 2022-M88 - CK21A090 2023 12 3.9478 7.763607 1.000154 211.6327 314.8532 158.0180 20250607 6.0 4.0 C/2021 A9 (PANSTARRS) MPC182879 - CK21A100 2021 03 14.7256 1.266610 0.985875 82.6383 188.8361 151.9933 20250607 19.0 4.0 C/2021 A10 (NEOWISE) MPEC 2021-N06 - CK21B020 2021 05 4.8409 2.514785 0.993828 335.1139 120.4407 38.0867 20250607 14.0 4.0 C/2021 B2 (PANSTARRS) MPEC 2022-L66 - CK21B030 2021 03 9.3261 2.168021 0.936650 293.6002 67.2814 119.4773 20250607 13.5 4.0 C/2021 B3 (NEOWISE) MPEC 2021-N06 - CK21C010 2020 12 5.7748 3.472916 0.998138 336.0629 186.8297 143.0429 20250607 11.5 4.0 C/2021 C1 (Rankin) MPEC 2023-KD6 - PK21C020 2021 02 24.5824 4.883788 0.488355 78.7211 66.4555 21.9385 20250607 12.0 4.0 P/2021 C2 (PANSTARRS) MPEC 2021-U31 - CK21C030 2021 02 11.1312 2.274046 0.962378 356.9768 181.8551 122.2061 20250607 14.0 4.0 C/2021 C3 (Catalina) MPEC 2024-M41 - CK21C040 2021 01 16.2019 4.493582 0.998850 320.0296 194.2305 132.8322 20250607 9.0 4.0 C/2021 C4 (ATLAS) MPEC 2022-M88 - CK21C050 2023 02 10.9796 3.240446 0.998104 270.8909 323.6735 50.8026 20250607 9.0 4.0 C/2021 C5 (PANSTARRS) MPEC 2024-N80 - CK21C060 2021 11 11.9242 3.284186 0.998783 203.8555 332.3268 164.6090 20250607 12.0 4.0 C/2021 C6 (Lemmon) MPEC 2022-YB4 - CK21D010 2021 02 27.3662 0.907968 0.991101 72.4544 311.1656 31.3577 20250607 13.0 4.0 C/2021 D1 (SWAN) MPEC 2022-F14 - CK21D020 2022 02 3.6634 2.949390 1.001436 125.0656 305.6295 83.7726 20250607 9.0 4.0 C/2021 D2 (ZTF) MPEC 2023-J29 - AK21E020 2020 12 8.9898 2.282957 0.988626 342.2234 190.7533 167.4935 20250607 15.0 2.0 A/2021 E2 MPEC 2022-UY9 - CK21E030 2022 06 11.1741 1.777480 0.999881 228.8021 104.4839 112.5254 20250607 8.5 4.0 C/2021 E3 (ZTF) MPEC 2024-GJ3 - AK21E040 2022 04 24.8335 4.679671 0.990725 48.2813 171.1423 116.3804 20250607 13.5 2.0 A/2021 E4 MPEC 2024-N80 - CK21F010 2022 04 6.7370 0.999184 0.995975 146.9431 203.5451 107.2924 20250607 13.5 4.0 C/2021 F1 (Lemmon-PANSTARRS) MPEC 2022-QD9 - CK21G010 2021 07 20.3922 3.427670 0.951791 107.4342 270.6978 131.5470 20250607 14.0 4.0 C/2021 G1 (Leonard) MPEC 2021-J72 - CK21G020 2024 09 9.1381 4.982300 1.000710 343.2670 221.0948 48.4673 20250607 5.5 4.0 C/2021 G2 (ATLAS) MPC184409 - CK21G030 2021 10 17.8526 5.182408 0.999409 10.5966 147.3473 102.8725 20250607 10.5 4.0 C/2021 G3 (PANSTARRS) MPEC 2022-X67 - PK21H00S 2021 08 4.8271 0.799110 0.809438 46.1195 262.3586 12.1545 20250607 22.0 4.0 P/2021 HS (PANSTARRS) MPEC 2021-Y10 - CK21J010 2021 02 19.4231 1.734109 0.933816 147.2016 88.4319 92.7078 20250607 15.5 4.0 C/2021 J1 (Maury-Attard) MPEC 2022-C56 - CK21J020 2021 09 20.8236 4.701472 0.958003 171.8860 23.3100 156.2116 20250607 12.0 4.0 C/2021 J2 (PANSTARRS) MPEC 2023-XP6 - PK21J030 2019 06 30.4082 4.895591 0.449374 125.6376 111.0061 14.5154 20250607 7.0 4.0 P/2021 J3 (ATLAS) MPEC 2024-F34 - CK21K010 2021 05 2.4345 2.502070 0.801523 184.2254 140.9236 16.2713 20250607 11.0 4.0 C/2021 K1 (ATLAS) MPEC 2022-O08 - CK21K020 2021 09 9.2652 5.463955 1.000476 343.2804 282.3370 100.8710 20250607 8.0 4.0 C/2021 K2 (MASTER) MPEC 2022-O01 - CK21K030 2022 02 3.6622 5.227832 1.004214 182.0155 114.6072 134.7805 20250607 10.0 4.0 C/2021 K3 (Catalina) MPEC 2022-L66 - PK21L020 2021 07 22.8578 1.939570 0.520801 51.4342 266.6533 21.0645 20250607 17.0 4.0 P/2021 L2 (Leonard) MPEC 2021-W31 - CK21L030 2022 02 14.9876 8.460199 1.004560 91.6503 345.0163 78.5393 20250607 6.0 4.0 C/2021 L3 (Borisov) MPEC 2024-H50 - PK21N010 2026 07 27.8496 0.966249 0.675728 21.2263 301.1355 11.4856 20250607 19.0 4.0 P/2021 N1 (ZTF) MPEC 2022-TA0 - PK21N020 2021 11 14.1845 3.805684 0.452162 177.6277 221.7427 13.0601 20250607 9.5 4.0 P/2021 N2 (Fuls) MPEC 2024-GJ3 - CK21N030 2020 08 16.9598 5.712295 0.959379 304.6036 337.5252 26.7630 20250607 8.5 4.0 C/2021 N3 (PANSTARRS) MPEC 2022-YB4 - CK21O010 2021 08 14.7476 0.782771 0.999837 74.4253 41.5444 27.5716 20250607 10.5 4.0 C/2021 O1 (Nishimura) MPEC 2022-A21 - CK21O030 2022 04 21.2790 0.285132 1.000051 300.0165 188.7945 56.8265 20250607 10.5 4.0 C/2021 O3 (PANSTARRS) MPEC 2022-L66 - CK21P010 2022 06 2.5785 4.379569 0.998387 40.5251 359.7108 51.6209 20250607 11.0 4.0 C/2021 P1 (PANSTARRS) MPEC 2024-F34 - CK21P020 2023 01 23.0778 5.068062 0.999611 76.7165 32.0943 150.0554 20250607 9.0 4.0 C/2021 P2 (PANSTARRS) MPC184409 - PK21P030 2021 05 28.3744 2.919184 0.338380 334.0109 358.2483 27.1602 20250607 14.0 4.0 P/2021 P3 (PANSTARRS) MPEC 2024-GJ3 - CK21P040 2022 07 30.4213 1.078644 0.996357 175.8072 348.0099 56.3727 20250607 9.5 4.0 C/2021 P4 (ATLAS) MPEC 2023-A50 - PK21P20E 2028 09 4.5434 1.236315 0.669952 210.4345 99.6248 20.0000 20250607 17.0 4.0 P/2021 PE20 (ATLAS) MPEC 2023-E68 - CK21Q030 2022 01 26.0869 5.208699 0.930647 114.1449 307.9094 77.7168 20250607 8.0 4.0 C/2021 Q3 (ATLAS) MPEC 2023-FK0 - CK21Q040 2023 06 11.1267 7.565158 1.001761 147.0577 183.3291 71.5308 20250607 6.0 4.0 C/2021 Q4 (Fuls) MPEC 2025-A40 - PK21Q050 2027 08 16.9857 1.234013 0.624570 180.9568 239.7555 10.7383 20250607 15.0 4.0 P/2021 Q5 (ATLAS) MPEC 2022-C56 - CK21Q060 2024 03 25.2207 8.707743 1.002785 141.0643 133.5742 161.8260 20250607 6.0 4.0 C/2021 Q6 (PANSTARRS) MPEC 2024-UA9 - CK21Q45M 2022 08 13.6825 2.778020 0.993202 72.9193 354.5964 22.7994 20250607 11.0 4.0 C/2021 QM45 (PANSTARRS) MPEC 2023-FK0 - PK21R010 2021 12 8.8778 4.884484 0.408246 220.0466 143.1106 5.5325 20250607 11.0 4.0 P/2021 R1 (PANSTARRS) MPEC 2022-X67 - CK21R020 2021 12 28.4483 7.316511 0.999301 32.5514 16.3366 134.4823 20250607 7.5 4.0 C/2021 R2 (PANSTARRS) MPEC 2022-X67 - PK21R030 2028 09 17.7153 2.519654 0.331530 2.5905 304.1942 19.9414 20250607 16.0 4.0 P/2021 R3 (PANSTARRS) MPEC 2021-W31 - PK21R040 2021 10 13.4411 2.333838 0.585290 56.7759 321.2822 21.0120 20250607 16.0 4.0 P/2021 R4 (Wierzchos) MPEC 2021-W31 - PK21R050 2022 01 12.4133 3.329986 0.305959 167.6057 219.9619 7.8538 20250607 12.0 4.0 P/2021 R5 (Rankin) MPEC 2024-JU4 - PK21R060 2021 10 31.9429 2.559320 0.593047 220.8794 176.1617 34.8921 20250607 14.5 4.0 P/2021 R6 (Groeller) MPEC 2021-W31 - CK21R070 2021 04 17.3065 5.654602 0.994322 140.3960 170.2005 158.8748 20250607 10.5 4.0 C/2021 R7 (PANSTARRS) MPEC 2022-X67 - PK21R080 2027 01 5.7856 2.136640 0.292557 190.8203 167.0660 2.2027 20250607 18.5 4.0 P/2021 R8 (Sheppard) MPEC 2021-Y10 - CK21S010 2022 03 1.9959 6.124948 1.002894 148.3065 299.8565 52.0384 20250607 7.0 4.0 C/2021 S1 (ATLAS) MPEC 2023-J29 - CK21S030 2024 02 14.6735 1.319790 1.000019 6.8372 215.6084 58.5389 20250607 5.5 4.0 C/2021 S3 (PANSTARRS) MPC184409 - CK21S040 2024 01 3.8162 6.691686 0.957228 73.0398 5.4532 17.4795 20250607 6.5 4.0 C/2021 S4 (Tsuchinshan) MPC184409 - CK21T010 2021 10 14.8469 3.060410 0.998910 51.5821 56.8478 140.3528 20250607 12.5 4.0 C/2021 T1 (Lemmon) MPEC 2022-OB6 - CK21T020 2022 06 8.3198 1.244243 1.000537 263.5303 223.2090 117.5134 20250607 12.0 4.0 C/2021 T2 (Fuls) MPEC 2023-A50 - CK21T040 2023 07 31.5176 1.481561 0.999707 329.7726 257.8897 160.7784 20250607 7.5 4.0 C/2021 T4 (Lemmon) MPC184409 - PK21T81R 2022 04 3.5989 1.464864 0.833029 272.0071 220.1771 36.8148 20250607 15.6 4.0 P/2021 TR81 (Lemmon) MPC184409 - PK21U010 2021 09 30.7736 2.453771 0.712665 145.2354 246.7942 30.5513 20250607 14.5 4.0 P/2021 U1 (Wierzchos) MPEC 2022-ED3 - PK21U030 2021 10 24.8639 1.891077 0.549418 335.3243 75.0940 69.9617 20250607 15.5 4.0 P/2021 U3 (Attard-Maury) MPEC 2022-L66 - CK21U040 2021 12 22.5427 1.787379 0.960707 237.3244 241.8058 152.8830 20250607 17.0 4.0 C/2021 U4 (Leonard) MPEC 2021-W31 - CK21U050 2022 01 26.9766 2.359144 0.989386 321.4594 182.6792 39.0401 20250607 13.0 4.0 C/2021 U5 (Catalina) MPEC 2022-WQ9 - CK21V010 2022 04 30.6156 3.019101 0.995790 195.2151 207.6973 71.4363 20250607 13.0 4.0 C/2021 V1 (Rankin) MPEC 2022-CN4 - PK21V020 2023 01 21.9705 3.497344 0.615254 259.9036 232.2763 12.6929 20250607 10.0 4.0 P/2021 V2 (Fuls) MPEC 2024-JU4 - CK21X010 2023 05 27.2796 3.234567 1.000590 334.6147 10.6146 140.1069 20250607 7.0 4.0 C/2021 X1 (Maury-Attard) MPEC 2024-TD8 - CK21X020 2022 07 8.3674 2.997954 1.001506 193.3838 228.8412 137.1542 20250607 13.0 4.0 C/2021 X2 (Bok) MPEC 2024-E08 - CK21Y010 2023 04 30.9232 2.032495 1.001576 245.8489 244.7667 77.1878 20250607 7.0 4.0 C/2021 Y1 (ATLAS) MPEC 2024-GJ3 - CK22A010 2022 01 31.1313 1.256062 0.996614 201.2816 285.4933 116.5716 20250607 18.0 4.0 C/2022 A1 (Sarneczky) MPEC 2022-YN2 - CK22A020 2023 02 18.1853 1.735370 1.000067 88.3667 171.6034 108.1677 20250607 9.5 4.0 C/2022 A2 (PANSTARRS) MPEC 2024-P23 - CK22A030 2023 09 28.9560 3.704365 0.995858 234.8705 325.4581 88.3494 20250607 8.0 4.0 C/2022 A3 (Lemmon-ATLAS) MPEC 2024-UQ8 - PK22B010 2022 02 25.9985 1.894403 0.653624 148.9349 325.3836 10.9943 20250607 16.5 4.0 P/2022 B1 (Wierzchos) MPEC 2022-K19 - AK22B030 2022 01 16.7301 3.704100 0.994170 150.7174 286.1765 132.0508 20250607 16.5 2.0 A/2022 B3 MPEC 2022-YB4 - CK22B040 2022 01 30.4291 1.375962 0.996607 153.0203 340.5189 20.0569 20250607 21.0 4.0 C/2022 B4 (Bok) MPEC 2022-GA9 - PK22B09V 2029 12 6.0502 3.346023 0.233561 16.3119 337.3087 11.9240 20250607 9.5 4.0 P/2022 BV9 (Lemmon) MPEC 2023-J29 - PK22C010 2021 11 5.4727 3.985092 0.449125 9.4570 113.0998 4.7631 20250607 12.0 4.0 P/2022 C1 (PANSTARRS) MPEC 2023-J29 - PK22C020 2022 08 5.8979 3.366634 0.441979 89.1385 135.2629 9.9848 20250607 12.5 4.0 P/2022 C2 (PANSTARRS) MPEC 2023-VM5 - PK22C030 2022 06 30.2059 4.370540 0.545491 93.8063 139.0407 12.8248 20250607 11.5 4.0 P/2022 C3 (PANSTARRS) MPEC 2023-UR6 - PK22D010 2021 08 28.7708 3.347542 0.547980 88.6628 47.9484 44.0670 20250607 12.5 4.0 P/2022 D1 (PANSTARRS) MPEC 2022-K19 - CK22D020 2022 03 28.0346 1.552672 0.996094 177.8525 312.3620 22.6800 20250607 17.0 4.0 C/2022 D2 (Kowalski) MPEC 2022-K19 - PK22E010 2022 06 9.3482 2.944576 0.220581 114.9011 113.3416 19.0070 20250607 13.5 4.0 P/2022 E1 (Christensen) MPEC 2022-L66 - CK22E020 2024 09 14.1400 3.666461 1.000390 41.7481 125.3976 137.1410 20250607 5.0 4.0 C/2022 E2 (ATLAS) MPC184409 - CK22E030 2023 01 12.5247 1.114104 0.999994 145.8268 302.5099 109.1749 20250607 7.5 4.0 C/2022 E3 (ZTF) MPEC 2024-GJ3 - CK22F010 2022 08 5.8226 5.977350 0.999413 278.3443 350.6346 58.0037 20250607 7.0 4.0 C/2022 F1 (ATLAS) MPEC 2024-PC5 - CK22F020 2022 03 22.3816 1.589437 0.933143 200.5932 58.7821 97.3170 20250607 14.5 4.0 C/2022 F2 (NEOWISE) MPEC 2022-QD9 - CK22H010 2024 01 18.6537 7.689230 0.990991 246.2917 6.3275 49.8600 20250607 6.0 4.0 C/2022 H1 (PANSTARRS) MPEC 2024-JU4 - CK22J010 2022 02 19.3331 1.600207 0.966312 305.6124 280.8021 105.9594 20250607 14.9 4.0 C/2022 J1 (Maury-Attard) MPEC 2022-VC5 - CK22J020 2022 10 26.7121 1.828181 0.979687 133.1453 252.6822 149.1415 20250607 9.0 4.0 C/2022 J2 (Bok) MPEC 2023-M14 - CK22J05K 2023 04 28.9763 2.695488 0.938604 247.3840 59.6519 16.8249 20250607 11.0 4.0 C/2022 JK5 (PANSTARRS) MPEC 2024-YC7 - CK22K010 2021 12 16.6229 3.986046 1.000876 142.5492 136.3589 41.9740 20250607 11.0 4.0 C/2022 K1 (Leonard) MPEC 2022-ST7 - CK22L010 2022 09 27.7531 1.591070 0.996279 59.8046 300.0319 123.4391 20250607 15.8 4.0 C/2022 L1 (Catalina) MPEC 2023-CD7 - CK22L020 2024 03 12.2038 2.693298 1.000868 199.9230 39.2435 129.3128 20250607 6.5 4.0 C/2022 L2 (ATLAS) MPC184409 - PK22L030 2022 10 29.8615 2.423858 0.627457 10.4121 29.8231 21.5377 20250607 16.5 4.0 P/2022 L3 (ATLAS) MPEC 2024-DC6 - CK22L040 2021 12 9.0718 3.008856 0.989335 125.2537 66.0616 141.2437 20250607 14.0 4.0 C/2022 L4 (PANSTARRS) MPEC 2022-N37 - CK22N010 2022 09 9.7789 1.479161 0.959613 40.9970 301.8787 164.7269 20250607 16.9 4.0 C/2022 N1 (Attard-Maury) MPEC 2024-GJ3 - CK22N020 2025 07 31.7948 3.825375 1.003302 75.3967 319.7401 5.5029 20250607 6.0 4.0 C/2022 N2 (PANSTARRS) MPC184410 - CK22O010 2022 02 15.4141 7.434842 1.001362 268.9419 49.9114 71.0506 20250607 6.0 4.0 C/2022 O1 (ATLAS) MPEC 2024-A43 - PK22O020 2023 01 6.7445 1.759350 0.720970 48.6668 330.4915 9.4187 20250607 16.2 4.0 P/2022 O2 (PANSTARRS) MPEC 2023-HD1 - CK22P010 2022 11 28.7012 1.592406 0.913784 249.8778 205.0694 154.5877 20250607 13.0 4.0 C/2022 P1 (NEOWISE) MPEC 2023-N01 - PK22P020 2022 07 11.0352 1.985286 0.558007 137.7713 291.1745 12.4409 20250607 12.5 4.0 P/2022 P2 (ZTF) MPEC 2023-XP6 - CK22P030 2022 07 27.5272 2.566240 0.990252 0.2182 72.2187 59.5163 20250607 9.0 4.0 C/2022 P3 (ZTF) MPEC 2023-HD1 - CK22Q020 2023 01 31.7222 1.641752 0.949932 44.0329 352.9616 151.4593 20250607 13.0 4.0 C/2022 Q2 (ATLAS) MPEC 2023-R20 - CK22Q78E 2025 09 11.5622 5.475978 1.003130 0.5781 119.8897 36.6127 20250607 5.0 4.0 C/2022 QE78 (ATLAS) MPC184410 - PK22R010 2023 10 4.3554 3.565587 0.501046 221.7894 175.6706 7.3777 20250607 11.5 4.0 P/2022 R1 (PANSTARRS) MPEC 2024-M41 - CK22R020 2022 10 25.5443 0.630268 0.998563 78.3208 60.3936 52.8938 20250607 17.0 4.0 C/2022 R2 (ATLAS) MPEC 2022-Y15 - CK22R030 2023 03 5.9140 5.131984 1.001524 72.9325 8.2588 43.0722 20250607 9.0 4.0 C/2022 R3 (Leonard) MPC184410 - PK22R040 2022 07 9.8981 1.959690 0.489471 197.4954 176.6351 21.0094 20250607 16.5 4.0 P/2022 R4 (PANSTARRS) MPEC 2022-X67 - PK22R050 2027 10 12.0615 2.472044 0.194743 240.5411 115.0432 15.2924 20250607 16.0 4.0 P/2022 R5 (PANSTARRS) MPEC 2022-WQ9 - CK22R060 2025 08 26.1862 6.565553 1.005023 319.9142 150.7855 57.0193 20250607 5.0 4.0 C/2022 R6 (PANSTARRS) MPC184410 - PK22S010 2022 08 19.0352 3.155498 0.507633 262.8458 136.0901 34.5672 20250607 15.1 4.0 P/2022 S1 (PANSTARRS) MPEC 2023-HD1 - CK22S030 2023 01 21.6281 0.838755 1.000385 267.9860 157.2527 78.4839 20250607 17.0 4.0 C/2022 S3 (PANSTARRS) MPEC 2022-VC5 - CK22S040 2024 07 18.7805 2.761844 0.998042 268.5621 220.1784 101.2157 20250607 8.0 4.0 C/2022 S4 (Lemmon) MPEC 2024-PC5 - CK22S050 2022 11 27.7762 2.177998 0.893851 232.8002 214.8652 136.5121 20250607 16.3 4.0 C/2022 S5 (PANSTARRS) MPEC 2023-HD1 - CK22T010 2024 02 17.4410 3.444329 1.000363 324.2933 236.9158 22.5422 20250607 9.0 4.0 C/2022 T1 (Lemmon) MPEC 2024-O39 - CK22U010 2024 03 26.0875 4.202263 1.000199 78.6124 72.5278 128.1481 20250607 8.5 4.0 C/2022 U1 (Leonard) MPC184410 - CK22U020 2023 01 14.2726 1.329591 0.986468 148.0078 304.4056 48.2495 20250607 16.0 4.0 C/2022 U2 (ATLAS) MPEC 2023-VM5 - CK22U030 2024 07 28.6616 4.826803 1.000196 189.1323 272.7883 33.6618 20250607 7.5 4.0 C/2022 U3 (Bok) MPC182880 - CK22U040 2023 08 3.6417 2.897353 0.998995 88.9862 132.9162 52.0525 20250607 10.5 4.0 C/2022 U4 (Bok) MPEC 2023-W26 - CK22V020 2023 11 1.8576 2.064184 0.943676 168.9544 332.8554 98.9020 20250607 12.0 4.0 C/2022 V2 (Lemmon) MPEC 2024-H50 - PK22W010 2022 09 16.1339 3.372687 0.516485 17.9288 38.8292 13.4641 20250607 12.5 4.0 P/2022 W1 (Rankin) MPEC 2023-CD7 - CK22W020 2023 03 8.7422 3.124810 0.990885 123.3139 320.4369 63.5026 20250607 11.5 4.0 C/2022 W2 (ATLAS) MPEC 2024-EF7 - CK22W030 2023 06 22.8205 1.396931 0.994975 116.5130 132.3023 103.5810 20250607 13.0 4.0 C/2022 W3 (Leonard) MPEC 2024-C04 - CK22Y010 2022 11 27.6753 2.960457 0.765304 174.8794 285.8772 18.8558 20250607 9.0 4.0 C/2022 Y1 (Hogan) MPEC 2023-M14 - CK22Y020 2023 03 22.4194 2.542047 0.871120 105.4732 216.3700 165.8910 20250607 13.5 4.0 C/2022 Y2 (Lemmon) MPEC 2023-TM6 - CK23A010 2023 03 18.5915 1.836022 0.991702 159.2631 318.2670 94.7412 20250607 14.5 4.0 C/2023 A1 (Leonard) MPEC 2024-GJ3 - CK23A020 2023 01 20.3647 0.945072 0.997681 142.4955 94.5082 94.7064 20250607 13.5 4.0 C/2023 A2 (SWAN) MPEC 2023-J95 - CK23A030 2024 09 27.7432 0.391505 1.000120 308.5071 21.5730 139.1112 20250607 6.5 3.2 C/2023 A3 (Tsuchinshan-ATLAS) MPC184410 - PK23B010 2023 05 3.7462 6.140625 0.130927 81.7065 78.5600 14.5884 20250607 5.5 4.0 P/2023 B1 (PANSTARRS) MPEC 2024-F34 - CK23B020 2023 03 10.6028 1.740681 0.997082 317.3632 218.0912 40.7669 20250607 14.5 4.0 C/2023 B2 (ATLAS) MPEC 2023-XP6 - PK23B030 2020 09 5.9334 3.993422 0.122381 240.3778 153.9861 9.1566 20250607 10.5 4.0 P/2023 B3 (PANSTARRS) MPEC 2023-F81 - CK23C020 2024 11 16.7867 2.368523 0.999028 357.4473 301.0045 48.3217 20250607 7.0 4.0 C/2023 C2 (ATLAS) MPC184410 - CK23E010 2023 06 30.8676 1.027505 0.946637 105.9509 164.5185 38.2811 20250607 15.5 4.0 C/2023 E1 (ATLAS) MPEC 2024-D33 - CK23F010 2023 06 28.1013 1.710205 0.993040 216.7329 25.3074 131.6941 20250607 16.0 4.0 C/2023 F1 (PANSTARRS) MPEC 2023-N01 - CK23F030 2025 02 2.6254 5.190781 1.003422 265.5326 109.4653 145.9636 20250607 6.0 4.0 C/2023 F3 (ATLAS) MPC184410 - CK23H010 2024 11 28.6409 4.447598 0.994146 333.7522 292.6467 21.7827 20250607 8.5 4.0 C/2023 H1 (PANSTARRS) MPC184410 - CK23H020 2023 10 29.1601 0.895248 0.996380 150.6863 217.0716 113.7478 20250607 14.0 4.0 C/2023 H2 (Lemmon) MPEC 2024-GJ3 - CK23H030 2024 02 18.3674 5.231858 0.615754 193.2680 55.0903 2.4889 20250607 10.0 4.0 C/2023 H3 (PANSTARRS) MPEC 2023-R20 - AK23H040 2023 08 8.7096 2.124079 0.985062 65.0179 230.8265 76.5692 20250607 18.0 2.0 A/2023 H4 MPEC 2023-SQ0 - CK23H050 2025 06 30.2758 4.312581 1.000464 60.0993 159.4785 97.8554 20250607 7.0 4.0 C/2023 H5 (Lemmon) MPC184410 - PK23J16N 2024 12 30.7664 2.299770 0.146928 353.2040 11.8728 3.7022 20250607 14.0 4.0 P/2023 JN16 (Lemmon) MPEC 2024-UA9 - CK23K010 2023 09 7.5805 2.038748 0.996736 337.4197 223.6981 137.9976 20250607 13.0 4.0 C/2023 K1 (ATLAS) MPEC 2024-GJ3 - PK23M010 2023 12 14.3278 2.826670 0.586824 79.6994 216.8598 12.2889 20250607 13.5 4.0 P/2023 M1 (PANSTARRS) MPEC 2023-N01 - PK23M020 2023 07 27.5154 3.515609 0.370007 243.4716 83.2501 19.7274 20250607 12.5 4.0 P/2023 M2 (PANSTARRS) MPEC 2024-TD8 - PK23M040 2022 04 13.6725 3.927295 0.278931 320.5223 296.2840 7.5919 20250607 7.5 4.0 P/2023 M4 (ATLAS) MPEC 2024-TP3 - CK23P010 2023 09 17.6213 0.224427 0.996023 116.2527 66.8314 132.4779 20250607 10.0 4.0 C/2023 P1 (Nishimura) MPEC 2024-MB8 - CK23Q010 2024 12 1.1274 2.575799 1.004990 84.4181 7.1241 36.6448 20250607 10.0 4.0 C/2023 Q1 (PANSTARRS) MPC184410 - CK23Q020 2024 06 23.9492 3.209123 0.990691 171.6918 92.6797 104.0618 20250607 11.5 4.0 C/2023 Q2 (PANSTARRS) MPEC 2024-N80 - CK23R010 2026 04 13.4847 3.569816 1.002199 144.2738 62.5623 149.3169 20250607 6.0 4.0 C/2023 R1 (PANSTARRS) MPC184410 - CK23R020 2024 08 12.1588 0.905101 1.000281 337.3129 188.8999 30.6893 20250607 10.5 4.0 C/2023 R2 (PANSTARRS) MPEC 2024-L77 - AK23R030 2023 12 18.1806 1.358648 0.998106 86.9417 347.3415 12.0809 20250607 20.0 2.0 A/2023 R3 MPEC 2023-UR6 - CK23R03N 2023 01 20.5090 5.180351 0.490603 130.6078 207.0645 10.3516 20250607 7.5 4.0 C/2023 RN3 (ATLAS) MPEC 2024-YC7 - CK23R61S 2028 12 1.1026 7.998302 0.327816 119.4045 347.0200 19.9446 20250607 6.8 4.0 C/2023 RS61 MPC184411 - PK23S010 2025 02 24.1745 2.619711 0.318474 180.3056 317.2904 9.1578 20250607 11.5 4.0 P/2023 S1 (PANSTARRS) MPC184411 - CK23S020 2023 10 15.3902 1.061415 0.993640 78.9402 229.4757 19.6629 20250607 15.0 4.0 C/2023 S2 (ATLAS) MPEC 2023-XP6 - CK23S030 2024 01 19.6482 0.829344 0.970828 281.5339 233.8238 140.4936 20250607 16.0 4.0 C/2023 S3 (Lemmon) MPEC 2024-P23 - PK23T010 2024 05 22.8559 2.817608 0.333228 202.8625 249.5765 6.6123 20250607 14.0 4.0 P/2023 T1 (PANSTARRS) MPEC 2024-BE0 - CK23T020 2023 12 22.7504 1.996241 0.991091 111.2150 317.5274 48.5913 20250607 14.5 4.0 C/2023 T2 (Borisov) MPEC 2024-GJ3 - CK23T030 2025 01 25.3523 3.548327 0.995846 302.8473 246.0018 27.2215 20250607 8.5 4.0 C/2023 T3 (Fuls) MPC184411 - CK23T22D 2024 09 16.3013 2.356700 0.951269 32.5408 5.5636 170.4899 20250607 12.5 4.0 C/2023 TD22 (Lemmon) MPEC 2024-VB7 - CK23U010 2024 10 12.9159 4.973072 0.998074 255.6438 305.8043 108.1458 20250607 8.0 4.0 C/2023 U1 (Fuls) MPC184411 - CK23V010 2025 07 13.0442 5.092567 1.000368 103.3151 15.0419 102.0138 20250607 8.5 4.0 C/2023 V1 (Lemmon) MPC184411 - PK23V020 2024 02 3.6810 3.104147 0.570075 330.5189 95.4745 9.8884 20250607 13.5 4.0 P/2023 V2 (PANSTARRS) MPC184411 - CK23V030 2023 08 4.1338 4.488241 0.651749 291.8520 91.2924 40.7034 20250607 11.5 4.0 C/2023 V3 (PANSTARRS) MPEC 2024-A43 - CK23V040 2024 05 30.3897 1.121895 1.001154 50.8693 66.3269 67.1258 20250607 12.0 4.0 C/2023 V4 (Camarasa-Duszanowicz) MPEC 2024-UQ8 - CK23V050 2023 12 13.9052 0.846313 1.009422 56.9682 31.5157 73.5516 20250607 21.5 4.0 C/2023 V5 (Leonard) MPEC 2024-GJ3 - PK23V060 2022 12 2.3358 4.366339 0.175560 192.5347 189.6581 3.9721 20250607 11.5 4.0 P/2023 V6 (PANSTARRS) MPEC 2025-A40 - CK23X010 2023 10 17.9784 0.951047 0.993900 321.4681 136.9938 110.5883 20250607 13.5 3.2 C/2023 X1 (Leonard) MPEC 2024-GJ3 - CK23X020 2025 12 28.1548 5.088824 1.000125 64.7625 66.3037 76.9830 20250607 8.5 3.2 C/2023 X2 (Lemmon) MPC184411 - PK23X030 2024 04 22.1386 3.030701 0.286187 40.8657 62.0136 4.4833 20250607 15.5 4.0 P/2023 X3 (PANSTARRS) MPEC 2024-A43 - CK23X040 2024 05 25.0460 3.658390 0.631261 100.5894 28.7694 11.5936 20250607 12.0 4.0 C/2023 X4 (Hogan) MPC184411 - CK23X070 2025 05 15.2159 4.820336 1.002599 354.3996 119.1982 69.0877 20250607 9.0 4.0 C/2023 X7 (PANSTARRS) MPEC 2024-DA2 - PK23Y010 2023 11 29.9149 2.080081 0.445359 51.4774 78.8560 6.3839 20250607 17.0 4.0 P/2023 Y1 (Gibbs) MPEC 2024-JU4 - PK23Y020 2023 08 10.1019 2.277287 0.392275 16.9000 79.2289 6.9927 20250607 15.5 4.0 P/2023 Y2 (Gibbs) MPEC 2025-A40 - CK24A010 2025 06 13.6964 3.875294 1.002392 353.3092 112.1356 94.4631 20250607 7.0 4.0 C/2024 A1 (ATLAS) MPC184411 - CK24A020 2024 04 28.8177 1.879458 0.941806 295.4973 78.1655 119.1148 20250607 12.5 4.0 C/2024 A2 (ATLAS) MPC182881 - CK24B010 2024 10 7.7179 1.633798 1.001017 66.2166 79.1884 70.9030 20250607 13.0 4.0 C/2024 B1 (Lemmon) MPC184411 - CK24B020 2023 10 5.8847 4.078123 0.998026 130.3387 294.3851 99.8677 20250607 11.5 4.0 C/2024 B2 (Lemmon) MPEC 2025-A40 - CK24C010 2024 08 31.0529 4.412871 0.582962 94.4879 83.8096 14.2269 20250607 11.5 4.0 C/2024 C1 (PANSTARRS) MPC184412 - CK24C020 2025 03 11.1495 8.991369 0.445864 87.5706 66.4454 27.2844 20250607 6.0 4.0 C/2024 C2 (PANSTARRS) MPEC 2024-JU4 - CK24C030 2023 11 8.6924 6.712987 0.424616 159.6863 359.7063 22.4552 20250607 9.0 4.0 C/2024 C3 (PANSTARRS) MPC184412 - CK24C040 2024 01 30.1903 1.470563 0.982384 321.4999 220.6723 79.2832 20250607 14.5 4.0 C/2024 C4 (ATLAS) MPEC 2024-Q20 - CK24D010 2027 12 3.3820 6.693542 0.999258 125.7735 179.6622 132.4501 20250607 7.3 4.0 C/2024 D1 (Lemmon) MPC184412 - CK24E010 2026 01 20.7601 0.565965 1.000069 243.6336 108.0802 75.2390 20250607 7.0 4.0 C/2024 E1 (Wierzchos) MPC184412 - CK24E020 2023 10 25.0686 7.694709 0.850673 358.1286 135.6531 155.6492 20250607 8.0 4.0 C/2024 E2 (Bok) MPEC 2024-JU4 - PK24F010 2023 10 25.7705 1.859838 0.459978 229.5757 251.5413 7.0053 20250607 16.0 4.0 P/2024 F1 (PANSTARRS) MPEC 2024-JU4 - CK24F020 2024 07 28.9781 3.967951 0.601104 112.8898 138.9401 13.7428 20250607 11.0 4.0 C/2024 F2 (PANSTARRS) MPEC 2024-Q20 - PK24F09G 2024 05 20.3990 1.596496 0.509915 245.9331 253.0426 1.7312 20250607 14.0 4.0 P/2024 FG9 (Nanshan-Hahn) MPEC 2024-UA9 - CK24G010 2024 10 21.0733 3.930126 0.967829 128.2240 30.6051 95.3941 20250607 10.0 4.0 C/2024 G1 (Wierzchos) MPC184412 - CK24G020 2025 06 13.5331 5.348242 0.992717 328.7372 171.3965 122.1259 20250607 7.0 4.0 C/2024 G2 (ATLAS) MPC184412 - CK24G030 2025 01 13.4274 0.093546 1.000007 108.1261 220.3434 116.8475 20250607 9.0 4.0 C/2024 G3 (ATLAS) MPC184412 - CK24G040 2026 03 21.6212 4.900411 0.998461 131.4209 152.9824 33.0264 20250607 8.0 4.0 C/2024 G4 (PANSTARRS) MPC184412 - CK24G050 2024 09 7.0515 2.953025 0.994819 209.5786 316.3932 50.3869 20250607 13.0 4.0 C/2024 G5 (Leonard) MPEC 2024-JC6 - CK24G060 2026 02 20.7641 6.429739 1.002178 23.4411 250.9518 120.4557 20250607 5.5 4.0 C/2024 G6 (ATLAS) MPC184412 - CK24G070 2025 02 10.1152 6.027666 1.001914 289.6572 191.9622 131.5155 20250607 7.0 4.0 C/2024 G7 (ATLAS) MPC184412 - AK24G080 2024 06 15.5855 1.172464 0.991726 249.1574 11.2484 97.4125 20250607 20.0 2.0 A/2024 G8 MPEC 2024-Q05 - PK24J010 2023 11 11.3025 2.636673 0.307717 200.3646 321.9389 13.1590 20250607 14.5 4.0 P/2024 J1 (PANSTARRS) MPEC 2024-JU4 - CK24J020 2025 03 19.7844 1.810894 0.987709 143.1605 189.0592 79.2971 20250607 11.5 4.0 C/2024 J2 (Wierzchos) MPC182882 - CK24J030 2026 11 25.3218 3.865136 1.000768 74.0888 285.9612 75.6399 20250607 5.0 4.0 C/2024 J3 (ATLAS) MPC184412 - CK24J040 2025 04 25.9991 5.695164 0.999103 127.8577 19.3058 117.5302 20250607 8.0 4.0 C/2024 J4 (Lemmon) MPC184412 - PK24K010 2024 05 8.9505 3.455517 0.495180 351.9289 251.6894 1.7862 20250607 13.5 4.0 P/2024 K1 (PANSTARRS) MPEC 2024-LB4 - CK24L010 2025 04 23.1525 5.348148 0.533564 171.7954 45.1395 99.1660 20250607 10.0 4.0 C/2024 L1 (PANSTARRS) MPC184413 - CK24L020 2025 06 12.8314 8.326292 0.982348 345.6194 266.2859 139.4875 20250607 7.5 3.2 C/2024 L2 (PANSTARRS) MPEC 2024-P23 - CK24L030 2023 11 24.1774 6.857968 1.003905 59.0777 294.9946 111.5923 20250607 9.5 4.0 C/2024 L3 (PANSTARRS) MPEC 2024-RQ6 - CK24L050 2025 03 10.3957 3.432418 1.037147 290.5150 139.1771 166.5730 20250607 9.0 4.0 C/2024 L5 (ATLAS) MPC184413 - CK24M010 2024 11 19.9979 1.703230 0.942863 345.5849 76.2146 73.7096 20250607 12.0 4.0 C/2024 M1 (ATLAS) MPC184413 - CK24N010 2025 10 18.9212 4.398081 1.000755 91.2577 323.0177 88.7770 20250607 10.5 4.0 C/2024 N1 (PANSTARRS) MPEC 2024-RQ6 - CK24N030 2025 04 11.4366 5.014572 1.001350 86.8850 82.6088 88.7289 20250607 8.0 4.0 C/2024 N3 (Sarneczky) MPC184413 - CK24N040 2025 01 10.1649 5.397759 1.004393 116.7023 339.6578 49.7739 20250607 7.5 4.0 C/2024 N4 (Sarneczky) MPC184413 - CK24O010 2023 01 28.5633 6.606926 1.000681 349.8910 303.3411 59.0788 20250607 8.5 4.0 C/2024 O1 (PANSTARRS) MPEC 2024-PC5 - PK24O020 2024 04 20.1610 3.697669 0.499118 310.7859 6.8056 28.9766 20250607 12.0 4.0 P/2024 O2 (PANSTARRS) MPEC 2024-UA9 - PK24O02C 2024 10 9.3166 0.592871 0.774187 258.5377 136.6170 7.6713 20250607 20.5 4.0 P/2024 OC2 (PANSTARRS) MPEC 2025-A40 - CK24P07N 2024 12 6.4352 1.524565 0.977350 74.2736 358.5841 101.2096 20250607 15.2 4.0 C/2024 PN7 (PANSTARRS) MPC184413 - PK24Q010 2024 06 14.6311 1.637488 0.534878 284.5039 23.1195 5.0126 20250607 17.0 4.0 P/2024 Q1 (PANSTARRS) MPEC 2024-UQ8 - CK24Q030 2025 03 5.2201 2.091554 1.001497 70.1278 337.2871 121.3783 20250607 15.0 4.0 C/2024 Q3 (PANSTARRS) MPC184413 - CK24Q040 2024 11 12.1968 5.419054 0.992351 133.0471 324.2755 3.3145 20250607 10.0 4.0 C/2024 Q4 (PANSTARRS) MPC182882 - PK24R010 2024 06 15.8313 1.750903 0.493109 230.6717 84.9824 12.7361 20250607 18.0 4.0 P/2024 R1 (PANSTARRS) MPEC 2024-TP3 - PK24R020 2024 10 1.7590 2.303147 0.268695 203.9418 193.0159 15.1155 20250607 15.5 4.0 P/2024 R2 (PANSTARRS) MPC182883 - PK24R030 2024 05 8.3366 2.345714 0.267200 309.2846 33.2506 14.7194 20250607 15.0 4.0 P/2024 R3 (PANSTARRS) MPEC 2024-YC7 - CK24R040 2027 10 26.6109 4.409098 1.002653 108.9915 345.9343 95.3611 20250607 6.5 4.0 C/2024 R4 (PANSTARRS) MPC184413 - CK24S010 2024 10 28.4812 0.007982 0.999909 69.4522 347.5022 142.0003 20250607 15.5 4.0 C/2024 S1 (ATLAS) MPC182883 - PK24S020 2024 09 16.3025 2.047676 0.593608 49.1695 8.3392 7.5256 20250607 15.0 4.0 P/2024 S2 (Rankin) MPEC 2025-A40 - PK24T010 2024 09 30.3924 2.287001 0.653458 164.8648 279.7109 17.6202 20250607 14.5 4.0 P/2024 T1 (Rankin) MPC182883 - PK24T020 2024 12 8.3295 1.972292 0.680429 343.8267 113.0615 12.9290 20250607 16.0 4.0 P/2024 T2 (Rankin) MPC184413 - CK24T030 2025 03 15.2407 3.716172 0.956859 336.8865 74.8331 53.4767 20250607 11.5 4.0 C/2024 T3 (PANSTARRS) MPC182883 - CK24T050 2027 05 6.3483 3.842066 1.001944 352.4367 100.6819 52.3871 20250607 5.5 4.0 C/2024 T5 (ATLAS) MPC182883 - CK24U010 2024 06 30.4360 4.836142 0.990111 188.0802 270.2639 128.7552 20250607 10.0 4.0 C/2024 U1 (PANSTARRS) MPC182883 - AK24U020 2026 01 14.3739 8.180888 1.003415 29.7694 56.0699 120.6712 20250607 12.1 2.0 A/2024 U2 MPC182883 - CK24V010 2025 04 4.1127 2.318468 0.990059 168.6681 328.1946 54.6257 20250607 14.8 4.0 C/2024 V1 (Borisov) MPC184413 - CK24V020 2024 11 3.8244 1.243049 0.968360 13.7225 102.2019 95.9718 20250607 19.0 4.0 C/2024 V2 (Sarneczky) MPEC 2024-YC7 - CK24W010 2025 03 19.1032 2.560721 0.942928 256.7386 310.7275 83.2004 20250607 15.0 4.0 C/2024 W1 (PANSTARRS) MPC182883 - AK24W020 2025 02 27.4255 3.720676 1.002713 168.0046 241.9386 116.6177 20250607 15.6 2.0 A/2024 W2 MPC182883 - CK24X010 2025 08 3.5284 3.816633 0.597196 124.3433 352.0222 6.4625 20250607 11.3 4.0 C/2024 X1 (Fazekas) MPC182884 - CK24X020 2025 07 7.8765 3.676300 0.927289 315.7809 122.5228 109.2212 20250607 9.6 4.0 C/2024 X2 (ATLAS) MPC184413 - PK24X030 2024 09 5.7781 2.614203 0.626208 352.9445 113.3648 2.9723 20250607 14.6 4.0 P/2024 X3 (PANSTARRS) MPC184413 - CK24X040 2025 09 1.9043 3.604765 0.641702 153.2897 258.9431 34.6691 20250607 12.6 4.0 C/2024 X4 (PANSTARRS) MPEC 2025-A40 - CK24Y010 2024 11 26.8717 0.822294 0.986778 238.1426 112.5427 64.7619 20250607 17.6 4.0 C/2024 Y1 (Masek) MPC182884 - AK25A010 2027 03 12.2766 5.342567 1.004196 68.0618 101.3302 33.4390 20250607 11.8 2.0 A/2025 A1 MPC182884 - PK25A020 2024 10 5.6488 3.446368 0.322127 278.0443 189.3196 20.7339 20250607 13.2 4.0 P/2025 A2 (PANSTARRS) MPC184414 - CK25A030 2026 03 15.0350 5.792320 0.431718 222.3061 322.4335 9.9768 20250607 9.0 4.0 C/2025 A3 (Tsuchinshan) MPC184414 - CK25A040 2025 01 13.1641 3.824243 0.653948 102.7981 69.9134 32.0255 20250607 12.4 4.0 C/2025 A4 (PANSTARRS) MPC184414 - CK25A060 2025 11 8.5335 0.529955 0.995744 132.9600 108.0964 143.6616 20250607 13.2 4.0 C/2025 A6 (Lemmon) MPC184414 - AK25A070 2025 03 28.1089 2.883440 0.999342 195.5676 348.8445 133.6497 20250607 14.0 2.0 A/2025 A7 MPC184414 - CK25B010 2025 06 26.7741 3.530888 1.001036 23.5274 102.8409 39.6797 20250607 12.0 4.0 C/2025 B1 (PANSTARRS) MPC182885 - CK25B020 2026 09 9.9854 8.244896 1.000040 78.7280 84.8734 91.7517 20250607 6.2 4.0 C/2025 B2 (Borisov) MPC184414 - PK25C010 2025 02 6.5574 2.746051 0.345477 186.7991 9.1028 7.5170 20250607 10.8 4.0 P/2025 C1 (ATLAS) MPC184414 - CK25D010 2028 05 20.0519 14.118888 1.002955 185.8926 312.8984 84.4648 20250607 1.2 4.0 C/2025 D1 (Groeller) MPC184414 - PK25D020 2028 11 5.4532 7.326765 0.178734 314.0559 256.7342 5.3344 20250607 8.2 4.0 P/2025 D2 (PANSTARRS) MPC182885 - PK25D030 2024 07 25.7823 2.965720 0.252352 294.4845 186.6354 9.6443 20250607 14.7 4.0 P/2025 D3 (PANSTARRS) MPC184414 - PK25D040 2025 02 14.2866 3.254933 0.634404 332.8895 233.1200 15.9405 20250607 13.2 4.0 P/2025 D4 (ATLAS) MPC184414 - CK25D050 2025 05 13.2912 2.012171 0.999402 211.4927 0.7379 73.3811 20250607 17.6 4.0 C/2025 D5 (PANSTARRS) MPC184415 - CK25D060 2024 12 11.3848 2.503917 0.998432 285.4043 151.4874 145.7902 20250607 13.2 4.0 C/2025 D6 (ATLAS) MPC184415 - CK25E010 2026 09 23.7485 3.998179 0.997214 274.4213 344.5972 69.0661 20250607 9.7 4.0 C/2025 E1 (PANSTARRS) MPC184415 - CK25F010 2025 04 20.4725 1.069976 0.996413 334.2283 122.7043 109.2363 20250607 18.0 4.0 C/2025 F1 (ATLAS) MPC184415 - CK25F020 2025 05 1.1615 0.333494 1.000105 153.8372 329.8408 90.3649 20250607 11.2 4.0 C/2025 F2 (SWAN) MPC184415 - CK25J010 2026 06 11.7763 3.573081 0.999561 166.7598 273.9986 95.4403 20250607 9.1 4.0 C/2025 J1 (Borisov) MPC184415 - CK25K010 2025 10 8.3397 0.335178 1.001393 270.8238 97.4939 147.8989 20250607 12.2 4.0 C/2025 K1 (ATLAS) MPEC 2025-KB0 - CK25K020 2025 11 1.3769 2.834449 0.779321 233.6299 113.4440 113.2794 20250607 13.7 4.0 C/2025 K2 (PANSTARRS) MPEC 2025-L17 - CK25K030 2028 12 13.7688 3.468840 1.001673 188.5944 350.6172 104.9329 20250607 6.4 4.0 C/2025 K3 (PANSTARRS) MPEC 2025-L43 -0001P 2061 08 30.5535 0.583481 0.967338 112.5343 59.6243 162.2163 20250607 4.0 6.0 1P/Halley 98, 1083 -0002P 2023 10 22.5891 0.339116 0.847119 187.2796 334.0146 11.3441 20250607 11.5 6.0 2P/Encke MPEC 2024-TP3 -0003D 2025 06 26.1985 0.822720 0.767566 192.2940 276.1865 7.8877 20250607 11.0 6.0 3D/Biela 76, 1135 -0003D a 2024 12 2.1226 0.826862 0.767116 192.1273 276.6832 7.2156 20250607 11.0 6.0 3D-A/Biela 76, 1135 -0003D b 2025 06 28.0742 0.821835 0.767864 192.2552 276.2012 7.8798 20250607 11.0 6.0 3D-B/Biela 76, 1135 -0004P 2021 09 9.0132 1.622634 0.576330 207.1418 192.9114 8.0031 20250607 8.0 6.0 4P/Faye MPEC 2023-FK0 -0005D 2023 04 17.3329 0.512075 0.837872 20.3027 94.9065 18.6308 20250607 10.5 6.0 5D/Brorsen 27, 116 -0006P 2028 04 1.6672 1.357392 0.611917 178.0521 138.9508 19.4997 20250607 7.5 16.0 6P/d'Arrest MPEC 2022-WD2 -0007P 2027 08 30.9415 1.196667 0.647152 172.5187 93.2818 22.5914 20250607 10.0 6.0 7P/Pons-Winnecke MPEC 2023-A50 -0008P 2021 08 28.5768 1.023012 0.820694 207.4757 270.1769 54.9840 20250607 8.0 8.0 8P/Tuttle MPEC 2022-HC2 -0009P 2028 02 5.1454 1.729676 0.473611 184.4495 67.3300 10.6707 20250607 5.5 10.0 9P/Tempel MPEC 2024-YC7 -0010P 2026 08 2.1518 1.417388 0.537382 195.4930 117.8007 12.0274 20250607 5.0 10.0 10P/Tempel MPC184415 -0011P 2026 11 9.8611 1.387313 0.577455 168.0493 238.8631 14.4329 20250607 17.0 4.0 11P/Tempel-Swift-LINEAR MPEC 2024-R10 -0012P 2024 04 21.1391 0.781108 0.954663 199.0069 255.8565 74.1895 20250607 5.0 6.0 12P/Pons-Brooks MPC184415 -0013P 2024 06 30.0751 1.175457 0.930474 64.4223 85.8467 44.6658 20250607 5.0 6.0 13P/Olbers MPC184415 -0014P 2026 09 18.9958 2.738319 0.356681 159.1933 202.0241 27.9182 20250607 5.5 12.0 14P/Wolf MPC184415 -0015P 2028 02 9.7562 0.996655 0.716126 347.8663 13.7487 6.7874 20250607 12.0 4.0 15P/Finlay MPEC 2022-ED3 -0016P 2028 04 20.8950 1.883633 0.485635 245.3734 138.8262 3.0099 20250607 7.5 10.0 16P/Brooks MPEC 2022-X67 -0017P 2028 01 31.7112 2.089013 0.426332 24.6154 326.6091 19.0070 20250607 10.0 6.0 17P/Holmes MPEC 2023-J29 -0018D 2024 08 29.154 1.59307 0.58953 238.210 158.451 17.660 20250607 9.0 4.0 18D/Perrine-Mrkos 19, 80 -0019P 2022 02 2.3257 1.307044 0.637780 352.0066 74.2151 29.3157 20250607 4.5 10.0 19P/Borrelly MPEC 2024-YC7 -0021P 2025 03 25.3579 1.008949 0.711046 172.9342 195.3305 32.0499 20250607 9.0 6.0 21P/Giacobini-Zinner MPEC 2024-YC7 -0022P 2028 07 12.9693 1.509714 0.557815 162.9650 120.2190 4.8170 20250607 3.0 10.4 22P/Kopff MPEC 2024-L77 -0023P 2059 05 31.2679 0.464379 0.972585 129.9760 311.1868 19.4644 20250607 10.0 6.0 23P/Brorsen-Metcalf MPC 14747 -0024P 2026 01 8.3018 1.183862 0.708188 58.4005 78.3675 11.5063 20250607 6.5 14.0 24P/Schaumasse MPC110085 -0025D 2025 05 11.4149 1.448317 0.550412 244.7972 279.9717 2.8087 20250607 12.5 6.0 25D/Neujmin 2 NK 378 -0026P 2023 12 25.3161 1.083442 0.640602 2.1243 211.5319 22.4368 20250607 12.0 16.0 26P/Grigg-Skjellerup MPEC 2024-TP3 -0027P 2011 08 2.7004 0.737593 0.919644 195.8471 250.7051 29.4349 20250607 12.0 8.0 27P/Crommelin MPC 78188 -0028P 2021 03 10.2668 1.586807 0.772691 347.4510 346.4105 14.2930 20250607 8.5 6.0 28P/Neujmin MPEC 2025-A40 -0029P 2019 05 2.0054 5.794510 0.043299 52.0914 312.4038 9.3559 20250607 4.0 4.0 29P/Schwassmann-Wachmann MPC184415 -0030P 2024 08 17.2293 1.813881 0.514396 9.5134 117.2331 8.0533 20250607 9.5 6.0 30P/Reinmuth MPC184416 -0031P 2028 03 18.8222 3.412669 0.193417 17.9084 114.1133 4.5497 20250607 5.0 8.0 31P/Schwassmann-Wachmann MPEC 2025-A40 -0032P 2024 04 20.6863 2.025139 0.555304 54.7061 54.5323 9.9200 20250607 6.5 8.0 32P/ComasSola MPC184416 -0033P 2024 11 10.8875 2.242484 0.451957 20.2566 66.2801 22.2940 20250607 10.0 12.0 33P/Daniel MPC184416 -0034D 2026 08 25.2219 1.213842 0.758079 218.0338 57.8627 10.5825 20250607 9.0 4.0 34D/Gale 9, 314 -0035P 2092 04 9.189 0.73346 0.97430 29.215 356.190 64.541 20250607 9.0 4.0 35P/Herschel-Rigollet 15, 452 -0036P 2028 11 4.9679 3.030774 0.268144 201.2039 181.8272 9.9460 20250607 8.5 6.0 36P/Whipple MPEC 2023-RF3 -0037P 2024 10 11.2372 1.617830 0.532663 330.0613 314.5487 8.9478 20250607 10.5 4.8 37P/Forbes MPC184416 -0038P 2018 11 13.8409 1.579529 0.859776 359.5908 77.8610 18.4144 20250607 3.5 12.0 38P/Stephan-Oterma MPEC 2024-YC7 -0039P 2023 09 7.7233 5.761905 0.172443 114.9963 289.2023 1.7222 20250607 7.0 6.0 39P/Oterma MPEC 2024-AF0 -0040P 2025 11 11.9064 1.823661 0.631575 52.0369 128.8986 11.6400 20250607 5.5 12.0 40P/Vaisala MPC184416 -0041P 2028 02 16.1461 1.050959 0.659640 62.2169 140.9720 9.2162 20250607 10.0 16.0 41P/Tuttle-Giacobini-Kresak MPEC 2023-SQ0 -0042P 2026 01 14.9655 2.029513 0.584065 147.1333 150.1599 3.9883 20250607 13.0 6.0 42P/Neujmin MPC184416 -0043P 2025 08 4.7053 2.442863 0.436248 223.8089 243.9939 9.3320 20250607 8.0 6.0 43P/Wolf-Harrington MPC184416 -0044P 2022 04 22.0818 2.114044 0.426744 57.9942 286.4219 5.8959 20250607 8.3 6.0 44P/Reinmuth MPEC 2024-F34 -0045P 2027 08 31.4858 0.557510 0.817617 327.9500 87.6862 4.3240 20250607 13.5 8.0 45P/Honda-Mrkos-Pajdusakova MPEC 2022-O01 -0046P 2024 05 19.0964 1.055235 0.658722 356.3416 82.1618 11.7497 20250607 14.0 6.0 46P/Wirtanen MPEC 2024-F91 -0047P 2025 10 27.9737 2.807476 0.318199 357.9098 356.8826 13.0385 20250607 1.0 11.2 47P/Ashbrook-Jackson MPC184416 -0048P 2025 03 2.6409 2.006586 0.426549 216.7739 110.0640 12.2017 20250607 10.0 6.0 48P/Johnson MPC184416 -0049P 2025 04 10.6074 1.431337 0.599026 332.9278 118.7910 19.0597 20250607 11.3 4.4 49P/Arend-Rigaux MPC184416 -0050P 2024 05 12.6306 1.921926 0.529703 49.3128 355.1447 19.1006 20250607 9.5 6.0 50P/Arend MPC184417 -0051P 2022 09 30.6770 1.694164 0.542783 269.2338 83.6588 5.4264 20250607 10.0 8.0 51P/Harrington MPEC 2023-J29 -0051P a 2022 10 3.2574 1.694015 0.542976 83.6431 269.2296 5.4262 20250607 10.0 8.0 51P-A/Harrington NK 3014 -0051P d 2022 10 1.1005 1.693843 0.542913 269.2519 83.6471 5.4269 20250607 16.0 8.0 51P-D/Harrington MPEC 2023-J29 -0052P 2021 10 6.2452 1.772338 0.541094 139.6148 336.7546 10.2378 20250607 13.5 6.0 52P/Harrington-Abell MPEC 2023-XP6 -0053P 2028 12 26.2057 2.449648 0.549643 134.3400 148.8521 6.6025 20250607 7.7 4.8 53P/VanBiesbroeck MPEC 2023-TM6 -0054P 2024 09 4.1482 2.172005 0.427033 2.0852 358.7511 6.0620 20250607 10.0 6.0 54P/deVico-Swift-NEAT MPEC 2024-YC7 -0055P 2031 05 22.5756 0.974524 0.905729 172.4929 235.4117 162.4843 20250607 9.0 4.0 55P/Tempel-Tuttle MPC 31070 -0056P 2027 12 19.4530 2.489320 0.508355 44.2185 345.8894 8.1549 20250607 8.5 6.0 56P/Slaughter-Burnham MPEC 2023-TM6 -0057P 2028 03 4.7859 1.716050 0.501283 115.0582 188.7423 2.8532 20250607 12.5 6.0 57P/duToit-Neujmin-Delporte MPEC 2024-DC6 -0058P 2028 09 4.2999 1.384169 0.661669 200.5826 159.0405 13.0878 20250607 15.5 6.0 58P/Jackson-Neujmin MPEC 2024-A43 -0059P 2028 03 15.4544 2.342473 0.477029 127.6677 312.7288 9.3558 20250607 7.0 6.0 59P/Kearns-Kwee MPEC 2023-A50 -0060P 2025 07 20.6135 1.645697 0.533836 216.9163 267.3963 3.5799 20250607 11.5 6.0 60P/Tsuchinshan MPC182887 -0061P 2022 10 23.4170 2.129156 0.423078 221.7082 162.9615 5.9969 20250607 6.0 10.0 61P/Shajn-Schaldach MPEC 2024-JU4 -0062P 2023 12 25.1982 1.265130 0.624709 47.3311 68.6656 4.7370 20250607 8.0 10.0 62P/Tsuchinshan MPC182887 -0063P 2026 07 6.2784 1.973367 0.650784 168.7961 357.7693 19.6200 20250607 10.5 6.0 63P/Wild MPC 84320 -0064P 2028 03 31.0128 1.387139 0.688440 97.3344 299.7732 8.9538 20250607 9.5 12.0 64P/Swift-Gehrels MPEC 2024-A43 -0065P 2025 06 16.4811 2.926255 0.248143 213.6757 61.9757 9.1753 20250607 5.0 6.0 65P/Gunn MPC184417 -0066P 2018 05 12.7648 1.305334 0.784969 257.3858 21.8372 18.6450 20250607 15.0 4.0 66P/duToit MPEC 2021-F20 -0067P 2028 04 9.0821 1.211062 0.649841 22.2106 36.3149 3.8685 20250607 11.0 4.0 67P/Churyumov-Gerasimenko MPEC 2024-C04 -0068P 2030 11 27.2994 1.807824 0.635780 153.2232 175.0913 11.0995 20250607 12.6 4.0 68P/Klemola MPEC 2023-HD1 -0069P 2026 11 12.3461 2.271254 0.414690 343.4962 104.8080 22.0613 20250607 9.5 12.0 69P/Taylor MPEC 2024-C04 -0070P 2028 11 20.8534 2.003882 0.454791 1.7925 119.2353 6.6030 20250607 11.0 6.0 70P/Kojima MPEC 2023-VM5 -0071P 2023 01 21.7233 1.627075 0.487386 210.3763 59.2535 9.3047 20250607 9.8 6.0 71P/Clark MPEC 2024-YC7 -0072P 2023 06 15.5820 0.782510 0.818342 346.7424 26.7204 10.9440 20250607 17.5 10.0 72P/Denning-Fujikawa MPEC 2023-VM5 -0073P 2027 12 11.6478 0.848301 0.719672 206.8065 60.6725 7.5519 20250607 11.5 6.0 73P/Schwassmann-Wachmann MPEC 2023-RF3 -0073P b 2028 01 22.2993 0.933166 0.696318 75.1585 193.1964 10.6840 20250607 9.0 4.0 73P-B/Schwassmann-Wachmann B NK 1613 -0073P c 2028 01 16.9506 0.933326 0.696126 75.0145 193.3767 10.6964 20250607 9.0 4.0 73P-C/Schwassmann-Wachmann NK 2710 -0073P e 2028 02 3.7712 0.933327 0.696660 75.4505 192.8710 10.6521 20250607 9.0 4.0 73P-E/Schwassmann-Wachmann NK 934 -0073P g 2006 06 8.096 0.93920 0.69330 198.772 69.909 11.388 9.0 4.0 73P-G/Schwassmann-Wachmann MPC 56796 -0073P h 2006 06 8.281 0.93918 0.69330 198.778 69.903 11.389 9.0 4.0 73P-H/Schwassmann-Wachmann MPC 56796 -0073P j 2006 06 8.141 0.93966 0.69330 198.673 69.983 11.386 9.0 4.0 73P-J/Schwassmann-Wachmann MPC 56796 -0073P k 2006 06 8.224 0.93903 0.69330 198.809 69.881 11.390 9.0 4.0 73P-K/Schwassmann-Wachmann MPC 56797 -0073P l 2006 06 8.340 0.93914 0.69330 198.772 69.911 11.388 9.0 4.0 73P-L/Schwassmann-Wachmann MPC 56797 -0073P m 2006 06 8.262 0.93912 0.69330 198.787 69.895 11.389 9.0 4.0 73P-M/Schwassmann-Wachmann MPC 56797 -0073P n 2006 06 8.261 0.93920 0.69330 198.754 69.909 11.389 9.0 4.0 73P-N/Schwassmann-Wachmann MPC 56797 -0073P p 2006 06 7.872 0.93917 0.69330 198.783 69.900 11.390 9.0 4.0 73P-P/Schwassmann-Wachmann MPC 56797 -0073P q 2006 06 7.725 0.93941 0.69330 198.717 69.944 11.387 9.0 4.0 73P-Q/Schwassmann-Wachmann MPC 56797 -0073P r 2006 06 8.185 0.93918 0.69330 198.776 69.904 11.388 9.0 4.0 73P-R/Schwassmann-Wachmann MPC 56797 -0073P s 2006 06 8.689 0.98977 0.69330 188.229 77.364 11.127 9.0 4.0 73P-S/Schwassmann-Wachmann MPC 56797 -0073P t 2027 12 9.7896 0.848041 0.719650 206.6988 60.7971 7.6034 20250607 9.0 4.0 73P-T/Schwassmann-Wachmann MPEC 2023-J29 -0073P u 2006 06 9.016 0.93962 0.69330 198.659 69.994 11.384 9.0 4.0 73P-U/Schwassmann-Wachmann MPC 56797 -0073P v 2006 06 8.477 0.91217 0.69330 204.943 65.236 11.651 9.0 4.0 73P-V/Schwassmann-Wachmann MPC 56797 -0073P w 2006 06 8.500 0.93906 0.69330 198.803 69.884 11.390 9.0 4.0 73P-W/Schwassmann-Wachmann MPC 56797 -0073P x 2006 06 8.566 0.93913 0.69330 198.778 69.900 11.388 9.0 4.0 73P-X/Schwassmann-Wachmann MPC 56798 -0073P y 2006 06 8.770 0.93911 0.69330 198.785 69.879 11.391 9.0 4.0 73P-Y/Schwassmann-Wachmann MPC 56798 -0073P z 2006 06 8.309 0.94204 0.69330 198.017 70.493 11.349 9.0 4.0 73P-Z/Schwassmann-Wachmann MPC 56798 -0073P aa 2006 06 9.086 0.93905 0.69330 198.804 69.883 11.390 9.0 4.0 73P-AA/Schwassmann-Wachmann MPC 56798 -0073P ab 2006 06 8.697 0.93906 0.69330 198.792 69.888 11.390 9.0 4.0 73P-AB/Schwassmann-Wachmann MPC 56798 -0073P ac 2006 06 8.693 0.93918 0.69330 198.766 69.914 11.387 9.0 4.0 73P-AC/Schwassmann-Wachmann MPC 56798 -0073P ad 2006 06 8.694 0.94167 0.69330 198.119 70.416 11.355 9.0 4.0 73P-AD/Schwassmann-Wachmann MPC 56798 -0073P ae 2006 06 8.352 0.93910 0.69330 198.790 69.891 11.390 9.0 4.0 73P-AE/Schwassmann-Wachmann MPC 56798 -0073P af 2006 06 6.841 0.94144 0.69330 198.217 70.302 11.356 9.0 4.0 73P-AF/Schwassmann-Wachmann MPC 56798 -0073P ag 2006 06 9.016 0.93921 0.69330 198.724 69.932 11.386 9.0 4.0 73P-AG/Schwassmann-Wachmann MPC 56798 -0073P ah 2006 06 8.628 0.94293 0.69330 197.755 70.695 11.331 9.0 4.0 73P-AH/Schwassmann-Wachmann MPC 56798 -0073P ai 2006 06 8.737 0.93912 0.69330 198.806 69.885 11.392 9.0 4.0 73P-AI/Schwassmann-Wachmann MPC 56798 -0073P aj 2006 06 8.740 0.93930 0.69330 198.663 70.041 11.385 9.0 4.0 73P-AJ/Schwassmann-Wachmann MPC 56799 -0073P ak 2006 06 8.395 0.93924 0.69330 198.822 69.784 11.389 9.0 4.0 73P-AK/Schwassmann-Wachmann MPC 56799 -0073P al 2006 06 8.456 0.93892 0.69330 198.857 69.843 11.395 9.0 4.0 73P-AL/Schwassmann-Wachmann MPC 56799 -0073P am 2006 06 8.266 0.93912 0.69330 198.815 69.876 11.394 9.0 4.0 73P-AM/Schwassmann-Wachmann MPC 56799 -0073P an 2006 06 8.328 0.93906 0.69330 198.820 69.870 11.393 9.0 4.0 73P-AN/Schwassmann-Wachmann MPC 56799 -0073P ao 2006 06 7.808 0.94408 0.69330 197.007 71.286 11.210 9.0 4.0 73P-AO/Schwassmann-Wachmann MPC 56799 -0073P ap 2006 06 6.685 0.93918 0.69330 198.794 69.895 11.393 9.0 4.0 73P-AP/Schwassmann-Wachmann MPC 56799 -0073P aq 2006 06 7.919 0.93920 0.69330 198.770 69.911 11.387 9.0 4.0 73P-AQ/Schwassmann-Wachmann MPC 56799 -0073P ar 2006 06 6.833 0.93937 0.69330 198.722 69.946 11.385 9.0 4.0 73P-AR/Schwassmann-Wachmann MPC 56799 -0073P as 2006 06 6.335 0.93922 0.69330 198.773 69.906 11.392 9.0 4.0 73P-AS/Schwassmann-Wachmann MPC 56799 -0073P at 2006 06 6.228 0.93925 0.69330 198.778 69.901 11.391 9.0 4.0 73P-AT/Schwassmann-Wachmann MPC 56799 -0073P au 2006 06 8.093 0.93929 0.69330 198.744 69.928 11.385 9.0 4.0 73P-AU/Schwassmann-Wachmann MPC 56799 -0073P av 2006 06 6.490 0.93930 0.69330 198.751 69.945 11.388 9.0 4.0 73P-AV/Schwassmann-Wachmann MPC 56800 -0073P aw 2006 06 7.766 0.93947 0.69330 198.673 69.982 11.377 9.0 4.0 73P-AW/Schwassmann-Wachmann MPC 56800 -0073P ax 2006 06 9.533 0.93912 0.69330 198.757 69.915 11.388 9.0 4.0 73P-AX/Schwassmann-Wachmann MPC 56800 -0073P ay 2006 06 8.760 0.93918 0.69330 198.750 69.923 11.385 9.0 4.0 73P-AY/Schwassmann-Wachmann MPC 56800 -0073P az 2006 06 6.515 0.93962 0.69330 198.644 70.002 11.371 9.0 4.0 73P-AZ/Schwassmann-Wachmann MPC 56800 -0073P ba 2006 06 6.436 0.93976 0.69330 198.588 70.042 11.364 9.0 4.0 73P-BA/Schwassmann-Wachmann MPC 56800 -0073P bb 2006 06 7.087 0.93912 0.69330 198.807 69.882 11.395 9.0 4.0 73P-BB/Schwassmann-Wachmann MPC 56800 -0073P bc 2006 06 6.670 0.93922 0.69330 198.778 69.901 11.391 9.0 4.0 73P-BC/Schwassmann-Wachmann MPC 56800 -0073P bd 2006 06 6.417 0.93998 0.69330 198.503 70.085 11.352 9.0 4.0 73P-BD/Schwassmann-Wachmann MPC 56800 -0073P be 2006 06 6.863 0.93902 0.69330 198.861 69.841 11.405 9.0 4.0 73P-BE/Schwassmann-Wachmann MPC 56800 -0073P bf 2006 06 6.992 0.93918 0.69330 198.752 69.908 11.390 9.0 4.0 73P-BF/Schwassmann-Wachmann MPC 56800 -0073P bg 2006 06 8.741 0.93915 0.69330 198.750 69.925 11.384 9.0 4.0 73P-BG/Schwassmann-Wachmann MPC 56800 -0073P bh 2006 06 8.568 0.93874 0.69330 198.947 69.752 11.410 9.0 4.0 73P-BH/Schwassmann-Wachmann MPC 56801 -0073P bi 2006 06 8.639 0.93905 0.69330 198.877 69.819 11.404 9.0 4.0 73P-BI/Schwassmann-Wachmann MPC 56801 -0073P bj 2006 06 8.669 0.93914 0.69330 198.776 69.905 11.389 9.0 4.0 73P-BJ/Schwassmann-Wachmann MPC 56801 -0073P bk 2006 06 8.884 0.93931 0.69330 198.698 69.970 11.379 9.0 4.0 73P-BK/Schwassmann-Wachmann MPC 56801 -0073P bl 2006 06 8.885 0.93923 0.69330 198.739 69.930 11.385 9.0 4.0 73P-BL/Schwassmann-Wachmann MPC 56801 -0073P bm 2006 06 8.938 0.93962 0.69330 198.546 70.086 11.364 9.0 4.0 73P-BM/Schwassmann-Wachmann MPC 56801 -0073P bn 2006 06 8.203 0.93905 0.69330 198.815 69.871 11.398 9.0 4.0 73P-BN/Schwassmann-Wachmann MPC 56801 -0073P bo 2006 06 8.259 0.93913 0.69330 198.765 69.903 11.390 9.0 4.0 73P-BO/Schwassmann-Wachmann MPC 56801 -0073P bp 2006 06 8.302 0.93910 0.69330 198.807 69.881 11.395 9.0 4.0 73P-BP/Schwassmann-Wachmann MPC 56801 -0073P bq 2006 06 8.297 0.93900 0.69330 198.862 69.836 11.404 9.0 4.0 73P-BQ/Schwassmann-Wachmann MPC 56801 -0073P br 2006 06 6.154 0.93921 0.69330 198.774 69.910 11.389 9.0 4.0 73P-BR/Schwassmann-Wachmann MPC 56957 -0073P bs 2006 06 5.831 0.93918 0.69330 198.814 69.885 11.399 9.0 4.0 73P-BS/Schwassmann-Wachmann MPC 56957 -0073P bt 2028 01 20.0279 0.933292 0.696310 75.0745 193.2962 10.6901 20250607 11.5 6.0 73P-BT/Schwassmann-Wachmann MPC106348 -0073P bu 2027 07 2.9875 0.927287 0.675740 73.0148 197.2653 10.8866 20250607 19.0 4.0 73P-BU/Schwassmann-Wachmann MPEC 2022-P18 -0073P bv 2028 01 16.7600 0.863298 0.719679 204.5446 62.0250 7.6840 20250607 19.0 4.0 73P-BV/Schwassmann-Wachmann MPEC 2022-X67 -0073P bw 2022 08 23.8290 0.966540 0.786581 71.6040 193.1064 10.2036 20250607 18.2 4.0 73P-BW/Schwassmann-Wachmann MPEC 2022-R15 -0073P bx 2028 01 2.0078 0.857999 0.719525 205.7595 61.0221 7.4975 20250607 17.5 4.0 73P-BX/Schwassmann-Wachmann MPEC 2023-A50 -0073P by 2027 11 23.1121 0.930864 0.691150 74.6070 194.0425 10.7561 20250607 17.4 4.0 73P-BY/Schwassmann-Wachmann MPEC 2022-R15 -0074P 2026 07 19.0322 4.824717 0.042284 68.1731 53.0564 6.1917 20250607 5.0 6.0 74P/Smirnova-Chernykh MPC184417 -0075D 2027 11 2.4526 1.770046 0.499517 175.5871 269.5527 5.9270 20250607 9.5 6.0 75D/Kohoutek CCO 7 -0076P 2026 04 13.5549 1.596863 0.539454 0.0042 84.1111 30.4885 20250607 8.0 12.0 76P/West-Kohoutek-Ikemura MPEC 2022-K19 -0077P 2023 04 2.8232 2.346824 0.351785 196.6203 14.7501 24.3249 20250607 7.0 8.0 77P/Longmore MPEC 2024-UA9 -0078P 2026 06 25.0255 2.004771 0.463069 192.7555 210.5042 6.2571 20250607 5.5 8.0 78P/Gehrels MPC184417 -0079P 2023 09 30.3288 1.120175 0.619323 281.7545 280.5072 3.1488 20250607 16.0 4.0 79P/duToit-Hartley MPEC 2024-PC5 -0080P 2022 12 8.2169 1.617842 0.597722 339.2746 259.7723 29.9270 20250607 9.0 8.0 80P/Peters-Hartley MPEC 2024-Q20 -0081P 2022 12 15.7903 1.595901 0.537630 41.5508 136.0988 3.2381 20250607 7.0 6.0 81P/Wild MPEC 2024-RQ6 -0082P 2026 11 15.9261 3.624382 0.122850 226.4740 239.2149 1.1294 20250607 15.0 4.0 82P/Gehrels MPC133426 -0083D 2028 12 2.6984 2.146707 0.441439 334.3790 226.2964 17.8309 20250607 9.0 4.0 83D/Russell NK 932 -0084P 2027 02 12.5931 1.719242 0.515728 281.6821 108.1420 7.5527 20250607 9.5 8.0 84P/Giclas MPEC 2020-FB5 -0085D 2020 07 30.3549 1.130926 0.775891 333.0902 65.2964 4.1729 20250607 6.5 8.0 85D/Boethin unp -0086P 2022 02 2.0648 2.323570 0.362807 181.0637 72.0960 15.5067 20250607 11.0 6.0 86P/Wild MPEC 2022-YB4 -0087P 2029 04 1.5167 3.413777 0.216922 51.8896 184.9577 2.6685 20250607 7.2 10.0 87P/Bus MPEC 2020-SI8 -0088P 2026 03 18.7905 1.357669 0.563230 235.8817 56.6687 4.3820 20250607 11.0 6.0 88P/Howell MPC184417 -0089P 2024 03 26.6073 2.222459 0.407483 250.4244 41.3448 12.0714 20250607 11.5 6.0 89P/Russell MPC182887 -0090P 2032 05 16.9647 2.962707 0.510632 29.1868 13.1869 9.6395 20250607 8.5 6.0 90P/Gehrels MPEC 2022-K19 -0091P 2028 10 23.3203 3.072257 0.257381 357.3521 242.4335 16.1982 20250607 7.5 6.0 91P/Russell MPEC 2023-VM5 -0092P 2027 07 15.3941 1.816790 0.660053 163.7807 181.3632 19.4794 20250607 12.0 6.0 92P/Sanguin MPEC 2014-J58 -0093P 2026 05 2.9105 1.688614 0.613962 75.0222 339.5513 12.2092 20250607 9.5 6.0 93P/Lovas MPEC 2024-R10 -0094P 2023 05 21.1754 2.225413 0.365987 92.3751 70.8479 6.1876 20250607 9.0 6.0 94P/Russell MPEC 2024-R10 -0095P 2046 08 14.1935 8.515863 0.378319 339.3547 209.1928 6.9282 20250607 6.5 2.0 95P/Chiron MPC 75717 -0096P 2023 01 31.3213 0.116080 0.961703 14.7370 93.9626 57.5860 20250607 13.0 4.8 96P/Machholz MPC182887 -0096P b 2023 01 31.1868 0.115948 0.961733 94.0147 14.5915 57.5036 20250607 13.0 4.8 96P-B/Machholz MPC106348 -0096P c 2012 07 14.6812 0.123794 0.958898 15.5380 94.3495 58.5311 9.0 4.0 96P-C/Machholz MPC103849 -0097P 2022 02 15.9771 2.575916 0.459958 230.1954 184.0743 17.9384 20250607 5.5 6.0 97P/Metcalf-Brewington MPEC 2024-GJ3 -0098P 2028 05 14.0028 1.638914 0.566579 157.7254 114.5115 10.6452 20250607 9.0 8.0 98P/Takamizawa MPEC 2021-W31 -0099P 2022 04 9.0547 4.699980 0.228745 174.5391 28.0659 4.3391 20250607 4.5 6.0 99P/Kowal MPEC 2024-R10 -0100P 2022 08 10.1800 2.019239 0.411360 181.9266 37.6857 25.5674 20250607 9.0 8.0 100P/Hartley MPEC 2023-OA6 -0101P 2020 01 13.0328 2.352434 0.595620 277.9812 116.1243 5.0485 20250607 10.0 4.8 101P/Chernykh MPEC 2024-R10 -0101P b 2020 01 30.8022 2.357488 0.595831 115.6010 278.5078 5.0502 20250607 9.0 4.0 101P-B/Chernykh MPC105241 -0102P 2028 07 10.7376 2.078137 0.456006 20.6754 339.3963 25.8545 20250607 6.5 8.0 102P/Shoemaker MPEC 2022-C56 -0103P 2023 10 12.4279 1.065232 0.693513 181.3270 219.7565 13.6080 20250607 8.5 8.0 103P/Hartley MPC184417 -0104P 2027 10 12.7835 1.072012 0.665902 227.3022 207.1844 5.7010 20250607 16.0 4.0 104P/Kowal MPEC 2023-G31 -0105P 2025 01 22.7537 2.052079 0.409144 46.3320 192.3939 9.1673 20250607 11.5 6.0 105P/SingerBrewster MPC184417 -0106P 2028 12 11.9614 1.531652 0.593542 353.7969 48.8659 19.5338 20250607 14.0 4.8 106P/Schuster MPEC 2024-R10 -0107P 2026 11 25.5853 0.969083 0.630969 95.5174 266.7278 2.7986 20250607 9.0 4.0 107P/Wilson-Harrington MPEC 2015-M77 -0108P 2028 12 8.2975 1.663382 0.555698 354.5319 50.3013 11.4325 20250607 8.0 12.0 108P/Ciffreo MPEC 2022-P82 -0109P 1992 12 20.6385 0.972799 0.962875 153.2777 139.7040 113.1148 20250607 4.0 6.0 109P/Swift-Tuttle 105, 420 -0110P 2028 08 22.2234 2.453304 0.319215 167.5590 287.4820 11.7114 20250607 1.0 12.0 110P/Hartley MPEC 2023-KD6 -0111P 2021 06 19.7841 3.707913 0.107169 1.4289 89.8101 4.2262 20250607 5.0 8.0 111P/Helin-Roman-Crockett MPC 75718 -0112P 2026 09 21.7990 1.441257 0.590839 21.5501 31.8130 24.2025 20250607 14.0 6.0 112P/Urata-Niijima MPEC 2021-S45 -0113P 2022 06 1.8054 2.144901 0.419678 115.7351 306.6219 5.2876 20250607 13.5 4.0 113P/Spitaler MPEC 2024-JU4 -0114P 2026 09 14.9513 1.571257 0.556139 172.8097 271.0265 18.3039 20250607 11.5 6.0 114P/Wiseman-Skiff MPEC 2023-A50 -0115P 2029 05 24.8501 2.059342 0.517846 120.9150 175.9849 11.6808 20250607 10.5 6.0 115P/Maury MPEC 2023-J29 -0116P 2022 07 16.7383 2.193852 0.370677 173.1590 20.9598 3.6045 20250607 2.5 10.0 116P/Wild MPEC 2024-RQ6 -0117P 2022 07 12.3732 3.075768 0.252846 224.6761 58.8222 8.6809 20250607 2.5 8.0 117P/Helin-Roman-Alu MPC182887 -0118P 2022 11 24.7387 1.829186 0.453806 314.9495 142.0552 10.0915 20250607 12.0 4.0 118P/Shoemaker-Levy MPEC 2024-MB8 -0119P 2022 08 12.4226 2.330826 0.388117 322.2686 104.5429 7.3928 20250607 3.5 8.0 119P/Parker-Hartley MPEC 2024-R10 -0120P 2029 04 4.6780 2.484476 0.374169 36.7831 358.7057 8.4815 20250607 12.0 4.0 120P/Mueller MPEC 2022-CN4 -0121P 2023 06 30.6763 3.732374 0.186710 11.9606 94.1051 20.1621 20250607 6.5 8.0 121P/Shoemaker-Holt MPC184417 -0122P 1995 10 1.6300 0.659529 0.962598 13.0037 79.7417 86.0276 20250607 7.5 5.2 122P/de Vico MPC 75718 -0123P 2026 09 22.2047 2.157258 0.444529 103.9556 45.9010 15.2799 20250607 12.2 4.0 123P/West-Hartley MPEC 2021-F20 -0124P 2026 06 23.6261 1.734320 0.486422 185.1176 359.9889 31.4045 20250607 13.5 2.8 124P/Mrkos MPEC 2024-UQ8 -0125P 2024 03 7.2317 1.526415 0.511989 87.1094 153.1496 9.9858 20250607 13.0 6.0 125P/Spacewatch MPEC 2024-UA9 -0126P 2023 07 5.0519 1.710632 0.696037 356.5607 357.8575 45.8713 20250607 6.0 8.0 126P/IRAS MPEC 2024-JU4 -0127P 2022 08 10.0280 2.215051 0.358764 6.3395 13.6163 14.2955 20250607 11.0 6.0 127P/Holt-Olmstead MPEC 2024-R10 -0128P 2026 07 16.7605 3.037356 0.322369 210.4909 214.3212 4.3709 20250607 8.5 4.0 128P/Shoemaker-Holt MPC 89014 -0129P 2022 12 3.4150 3.925044 0.085923 307.8668 184.8497 3.4414 20250607 11.0 4.0 129P/Shoemaker-Levy MPC184417 -0130P 2024 04 15.2661 1.825040 0.461237 246.3029 70.1805 6.0602 20250607 10.0 6.0 130P/McNaught-Hughes MPC184417 -0131P 2026 02 15.6207 2.407941 0.344760 179.2411 214.1364 7.3618 20250607 11.0 4.0 131P/Mueller MPEC 2025-A40 -0132P 2021 11 12.9507 1.696922 0.564039 216.5083 173.9792 5.3778 20250607 11.0 6.0 132P/Helin-Roman-Alu MPEC 2024-BE0 -0133P 2024 05 10.1023 2.670696 0.155666 131.8701 160.1011 1.3899 20250607 15.4 2.0 133P/Elst-Pizarro MPC 94676 -0134P 2030 01 8.5981 2.600476 0.585473 18.6592 201.9924 4.3331 20250607 11.5 4.0 134P/Kowal-Vavrova MPC 89012 -0135P 2022 04 6.1629 2.685828 0.293491 22.3772 213.0197 6.0630 20250607 7.0 8.0 135P/Shoemaker-Levy MPEC 2024-C04 -0136P 2025 01 3.4368 2.958464 0.293161 225.3159 137.4204 9.4273 20250607 11.0 4.0 136P/Mueller MPC182888 -0137P 2028 07 29.3193 1.931703 0.572981 141.2180 232.9270 4.8598 20250607 11.0 4.0 137P/Shoemaker-Levy MPEC 2023-J29 -0138P 2026 03 24.2998 1.694436 0.531550 95.6874 309.2718 10.0998 20250607 15.0 6.0 138P/Shoemaker-Levy MPEC 2016-U66 -0139P 2027 07 22.7826 3.392889 0.248310 165.9764 242.1800 2.3374 20250607 9.5 4.0 139P/Vaisala-Oterma MPEC 2020-HN5 -0140P 2031 10 5.4681 1.954760 0.695192 172.1562 343.3736 3.6971 20250607 11.5 6.0 140P/Bowell-Skiff MPEC 2015-E14 -0141P 2026 04 22.9724 0.807385 0.735894 153.6439 241.7761 13.9618 20250607 12.0 12.0 141P/Machholz MPEC 2024-R10 -0141P a 2026 04 23.3368 0.807389 0.735912 241.9272 153.5044 13.9416 20250607 12.0 12.0 141P-A/Machholz MPEC 2015-KD9 -0141P b 2026 04 15.3546 0.807689 0.735673 241.8162 153.5804 13.9856 20250607 9.0 4.0 141P-B/Machholz MPC 24216 -0141P d 2026 05 18.5845 0.806740 0.736858 242.1757 153.2303 13.8334 20250607 9.0 4.0 141P-D/Machholz MPC 37026 -0141P e 1994 09 19.2500 0.752528 0.750233 149.2667 246.1856 12.8152 9.0 4.0 141P-E/Machholz MPEC 2015-R12 -0141P f 1994 09 19.1963 0.752528 0.750009 149.2374 246.1881 12.7898 9.0 4.0 141P-F/Machholz MPEC 2015-R12 -0141P g 1994 09 19.1048 0.752528 0.749643 149.0784 246.3146 12.8259 9.0 4.0 141P-G/Machholz MPEC 2015-R12 -0141P h 2015 08 24.3866 0.761562 0.746822 149.4500 246.0900 12.8431 18.5 4.0 141P-H/Machholz MPC 95735 -0141P i 2026 04 13.6078 0.807222 0.735141 241.9370 153.4592 13.9417 20250607 17.5 4.0 141P-I/Machholz MPEC 2022-SU8 -0142P 2021 05 11.3105 2.521898 0.495968 174.0641 175.9595 12.2448 20250607 8.5 6.0 142P/Ge-Wang MPEC 2024-C04 -0143P 2026 12 25.8368 2.947370 0.383193 304.3260 242.5111 5.4508 20250607 13.5 2.0 143P/Kowal-Mrkos MPC182888 -0144P 2024 01 25.8202 1.399434 0.634966 216.3592 242.9246 3.9317 20250607 8.5 8.0 144P/Kushida MPEC 2024-YC7 -0145P 2026 01 31.9034 1.889824 0.542473 10.3792 26.7938 11.2765 20250607 13.5 4.0 145P/Shoemaker-Levy MPC108598 -0146P 2024 08 5.4182 1.418684 0.647579 317.0449 53.3588 23.1180 20250607 15.0 4.0 146P/Shoemaker-LINEAR MPC184418 -0147P 2023 12 7.4820 3.160491 0.211801 348.6036 91.6674 2.3115 20250607 14.0 4.0 147P/Kushida-Muramatsu MPEC 2024-UQ8 -0148P 2022 06 14.2794 1.627680 0.550388 8.0803 89.1952 3.6589 20250607 16.0 2.0 148P/Anderson-LINEAR MPEC 2024-JU4 -0149P 2026 12 16.5025 2.790002 0.324446 30.2359 143.7594 34.2352 20250607 8.0 8.0 149P/Mueller MPEC 2023-J29 -0150P 2024 03 12.5262 1.745410 0.549214 246.1239 272.0557 18.5484 20250607 13.5 4.0 150P/LONEOS MPEC 2024-NE4 -0151P 2029 08 17.9186 2.464821 0.572554 216.1557 143.1233 4.7254 20250607 10.0 6.0 151P/Helin MPEC 2022-K19 -0152P 2022 01 13.3702 3.109256 0.306872 164.4435 91.7755 9.8798 20250607 11.5 4.0 152P/Helin-Lawrence MPC182888 -0153P 2002 03 12.2852 0.496820 0.990158 34.2224 93.8008 28.4977 20250607 9.0 4.0 153P/Ikeya-Zhang MPC 46101 -0154P 2024 06 13.2145 1.552474 0.676277 47.9314 342.9957 17.6381 20250607 2.5 12.0 154P/Brewington MPC184418 -0155P 2019 11 17.3735 1.789732 0.727668 14.5310 97.1568 6.4107 20250607 10.0 4.8 155P/Shoemaker MPEC 2022-YN2 -0156P 2027 04 30.4841 1.333572 0.614870 0.5258 35.3344 17.2610 20250607 15.5 2.0 156P/Russell-LINEAR MPEC 2023-J29 -0157P 2022 09 10.1596 1.572474 0.556799 155.1773 287.4983 12.4243 20250607 10.0 4.0 157P/Tritton MPEC 2024-D33 -0157P b 2028 02 25.6658 1.551697 0.499895 287.2084 153.8813 12.4252 20250607 15.7 4.0 157P-B/Tritton MPEC 2022-VC5 -0158P 2022 09 4.9627 5.016906 0.117410 229.2637 124.4475 7.4482 20250607 9.0 4.0 158P/Kowal-LINEAR MPC182888 -0159P 2018 05 26.1980 3.615253 0.382550 4.7263 54.9389 23.4836 20250607 10.0 4.0 159P/LONEOS MPEC 2024-DC6 -0160P 2027 04 7.2141 1.795322 0.525010 12.7801 333.3492 15.5950 20250607 15.5 2.0 160P/LINEAR MPEC 2022-K19 -0161P 2026 11 27.9684 1.266729 0.835823 47.0675 1.5145 95.8181 20250607 8.5 6.0 161P/Hartley-IRAS MPC 75721 -0162P 2026 05 17.8212 1.289487 0.582940 357.2370 30.8767 27.5535 20250607 12.0 4.0 162P/SidingSpring MPEC 2025-A40 -0163P 2026 11 23.9149 2.055501 0.453480 349.6342 102.0725 12.7212 20250607 14.5 4.0 163P/NEAT MPEC 2021-S45 -0164P 2025 05 27.4029 1.675101 0.541313 325.9523 88.2690 16.2774 20250607 11.0 4.0 164P/Christensen MPEC 2024-TD8 -0165P 2000 06 13.8547 6.783297 0.619226 125.8783 0.6769 15.9084 20250607 11.5 2.0 165P/LINEAR MPC 75721 -0166P 2002 06 6.5566 8.541915 0.382884 321.8517 64.4387 15.3778 20250607 5.5 4.0 166P/NEAT MPC 75722 -0167P 2001 03 27.1522 11.898661 0.267848 344.4500 295.8361 19.0752 20250607 9.5 2.0 167P/CINEOS MPEC 2023-J29 -0168P 2026 05 26.2446 1.358408 0.621272 15.1000 355.3888 21.5949 20250607 15.5 4.0 168P/Hergenrother MPEC 2023-J29 -0169P 2026 09 21.3273 0.603920 0.768047 218.1215 176.0585 11.2869 20250607 16.0 2.0 169P/NEAT MPC184418 -0170P 2023 04 15.7014 2.913968 0.305265 224.7384 142.6378 10.1295 20250607 12.0 4.0 170P/Christensen MPC184418 -0171P 2025 09 25.0455 1.766303 0.502770 347.0896 101.7000 21.9508 20250607 13.5 4.0 171P/Spahr MPC102102 -0172P 2025 11 2.5261 3.358145 0.204898 208.8955 30.8826 11.2231 20250607 13.0 4.0 172P/Yeung MPC184418 -0173P 2021 12 17.8454 4.215990 0.262369 29.2903 100.3460 16.4934 20250607 7.5 4.0 173P/Mueller MPEC 2023-N01 -0174P 2015 04 20.0111 5.865233 0.454848 163.4309 173.3387 4.3409 20250607 9.4 2.0 174P/Echeclus MPC 92985 -0175P 2026 09 2.9999 2.303115 0.376034 74.6824 109.8170 4.9273 20250607 14.0 4.0 175P/Hergenrother MPC114608 -0176P 2022 11 19.8242 2.582357 0.191833 34.4714 345.6320 0.2312 20250607 15.1 2.0 176P/LINEAR MPC 89015 -0177P 2006 08 30.1704 1.121708 0.954235 60.7589 271.8625 31.0065 20250607 15.0 4.0 177P/Barnard MPEC 2020-L06 -0178P 2027 06 21.3903 1.880757 0.482287 297.9618 102.7847 11.0925 20250607 13.5 4.0 178P/Hug-Bell MPEC 2024-R10 -0179P 2022 05 31.8463 4.123731 0.305425 297.2135 115.5083 19.8900 20250607 2.5 8.0 179P/Jedicke MPEC 2024-EF7 -0180P 2023 07 12.1366 2.499272 0.353827 94.6044 84.5589 16.8619 20250607 11.0 4.0 180P/NEAT MPEC 2024-F34 -0181P 2022 01 8.2830 1.164514 0.699801 336.2927 35.4405 17.4744 20250607 11.5 4.0 181P/Shoemaker-Levy MPC 89012 -0182P 2027 06 5.3774 0.990976 0.663934 54.2080 72.4549 16.2309 20250607 18.0 4.0 182P/LONEOS MPEC 2024-UQ8 -0183P 2027 09 16.5050 4.224695 0.102658 162.7099 3.5479 18.7278 20250607 12.5 2.0 183P/Korlevic-Juric MPEC 2024-VJ2 -0184P 2028 03 23.8107 1.711079 0.549810 186.5614 173.2678 4.5700 20250607 13.5 4.0 184P/Lovas MPEC 2020-W26 -0185P 2023 07 12.7923 0.931716 0.699416 181.9200 214.1225 14.0099 20250607 15.0 4.0 185P/Petriew MPEC 2024-F91 -0186P 2029 08 25.1242 4.254476 0.123834 268.4981 325.8854 28.6548 20250607 7.5 4.0 186P/Garradd MPEC 2022-X67 -0187P 2028 02 3.9606 3.840235 0.156087 131.6378 109.8449 13.6673 20250607 9.0 4.0 187P/LINEAR MPEC 2020-SI8 -0188P 2026 04 13.2649 2.546204 0.416705 26.8280 358.9140 10.5247 20250607 11.5 4.0 188P/LINEAR-Mueller MPEC 2023-J29 -0189P 2027 09 13.5794 1.203548 0.590621 16.1831 281.6845 20.1200 20250607 19.0 4.0 189P/NEAT MPEC 2022-QD9 -0190P 2024 12 24.1533 2.019409 0.522666 50.5502 335.4758 2.1747 20250607 13.0 4.0 190P/Mueller MPC182889 -0191P 2028 02 29.6475 2.238640 0.385137 284.2680 98.1790 8.8395 20250607 13.0 4.0 191P/McNaught MPEC 2024-TD8 -0192P 2024 05 24.5066 1.462848 0.773402 313.0401 51.5815 24.5800 20250607 15.0 4.0 192P/Shoemaker-Levy MPC182889 -0193P 2028 06 1.4387 2.174171 0.392609 8.1166 335.1861 10.6791 20250607 14.0 4.0 193P/LINEAR-NEAT MPEC 2024-R10 -0194P 2024 02 4.3188 1.800038 0.563391 128.6173 349.5116 11.8035 20250607 16.0 4.0 194P/LINEAR MPEC 2024-GJ3 -0195P 2025 08 5.6118 4.440568 0.310949 250.5995 243.0986 36.4168 20250607 8.5 4.0 195P/Hill MPC184418 -0196P 2022 10 29.1836 2.178953 0.427533 12.1370 24.1242 19.2950 20250607 13.5 4.0 196P/Tichy MPEC 2024-GJ3 -0197P 2027 11 20.6129 1.107031 0.619279 189.9473 66.2028 25.3240 20250607 16.5 2.0 197P/LINEAR MPEC 2023-UR6 -0198P 2025 10 7.1122 1.994799 0.444656 69.0495 358.4690 1.3400 20250607 12.5 4.0 198P/ODAS MPEC 2024-VJ2 -0199P 2023 08 7.3568 2.910924 0.504415 191.7635 92.3438 24.9392 20250607 10.0 4.0 199P/Shoemaker MPEC 2024-Q20 -0200P 2030 08 6.2574 3.312886 0.331172 134.3852 234.8103 12.0951 20250607 9.0 4.0 200P/Larsen MPEC 2022-C56 -0201P 2027 07 20.1277 1.216021 0.637512 19.8020 41.5254 5.7371 20250607 14.0 4.0 201P/LONEOS MPC 93588 -0202P 2024 05 17.2938 3.069940 0.251079 274.4959 177.3005 2.1418 20250607 13.5 4.0 202P/Scotti MPC182889 -0203P 2030 04 8.8221 3.191439 0.316385 154.9356 290.2218 2.9760 20250607 14.5 2.0 203P/Korlevic MPEC 2025-A40 -0204P 2022 11 17.2747 1.834082 0.488286 356.7280 108.4733 6.5979 20250607 14.0 4.0 204P/LINEAR-NEAT MPEC 2024-JU4 -0205P 2028 09 13.5869 1.533512 0.567187 154.1547 179.6235 15.3004 20250607 13.0 4.0 205P/Giacobini MPEC 2023_O39 -0206P 2027 09 12.9880 1.567174 0.551138 189.5764 202.3418 33.6176 20250607 19.0 4.0 206P/Barnard-Boattini MPC 75725 -0207P 2024 01 31.8681 0.938406 0.758524 273.0274 198.1389 10.1986 20250607 16.0 4.0 207P/NEAT MPEC 2024-NE4 -0208P 2024 08 24.2113 2.529177 0.374103 310.7650 36.3327 4.4113 20250607 12.5 4.0 208P/McMillan MPC182889 -0209P 2024 07 14.4925 0.964175 0.674029 152.4816 62.7647 21.2828 20250607 17.0 2.0 209P/LINEAR MPEC 2024-TD8 -0210P 2025 11 22.7191 0.524456 0.834072 345.9167 93.8249 10.2819 20250607 13.5 4.0 210P/Christensen MPC105242 -0211P 2022 10 5.1555 2.326375 0.344481 4.3500 117.1009 18.9246 20250607 12.5 4.0 211P/Hill MPEC 2024-JU4 -0212P 2024 04 25.1487 1.612888 0.586754 14.0596 97.9719 22.1490 20250607 17.0 2.0 212P/NEAT MPEC 2024-GJ3 -0213P 2023 11 13.3326 1.981627 0.409641 6.4763 310.9338 10.4233 20250607 10.5 4.0 213P/VanNess MPC184418 -0213P b 2023 11 13.2013 1.981984 0.409514 6.4955 310.9302 10.4227 20250607 17.0 4.0 213P-B/Van Ness MPEC 2025-GB9 -0213P c 2023 11 12.3629 1.981014 0.409529 312.0709 5.2771 10.3509 20250607 17.5 4.0 213P-C/Van Ness MPC 76570 -0214P 2022 09 26.3643 1.857939 0.486262 190.1204 348.2119 15.1927 20250607 13.0 4.0 214P/LINEAR MPC 92986 -0215P 2028 11 24.3165 3.620663 0.164936 262.2519 56.6780 10.5763 20250607 11.0 4.0 215P/NEAT MPC184418 -0216P 2024 01 6.9898 2.126974 0.449009 151.7693 359.7818 9.0616 20250607 13.0 4.0 216P/LINEAR MPEC 2024-N80 -0217P 2025 05 24.9443 1.226374 0.689075 247.0363 125.3714 12.8655 20250607 12.0 4.0 217P/LINEAR MPC184418 -0218P 2026 03 3.8636 1.129972 0.630929 61.4031 174.6836 2.7263 20250607 16.0 4.0 218P/LINEAR MPEC 2022-K19 -0219P 2024 02 15.0848 2.355846 0.355752 107.9586 230.9019 11.5176 20250607 11.0 4.0 219P/LINEAR MPC182889 -0220P 2026 06 14.1438 1.558894 0.500395 180.5839 150.0915 8.1209 20250607 15.0 4.0 220P/McNaught MPEC 2024-A43 -0221P 2028 04 2.8350 1.621531 0.521280 41.4818 226.9766 10.9095 20250607 14.5 4.0 221P/LINEAR MPEC 2022-UY9 -0222P 2024 05 12.8887 0.826010 0.714804 346.2749 6.7547 5.0973 20250607 20.0 4.0 222P/LINEAR MPC 92277 -0223P 2027 07 24.7596 2.427373 0.416254 37.9819 346.7057 27.0059 20250607 12.0 4.0 223P/Skiff MPEC 2023-A50 -0224P 2022 09 30.1513 2.049091 0.405571 16.8136 40.0413 13.3015 20250607 15.5 4.0 224P/LINEAR-NEAT MPEC 2024-L77 -0225P 2023 08 7.8609 1.319774 0.638165 3.9063 14.2106 21.3614 20250607 18.0 4.0 225P/LINEAR MPEC 2024-F91 -0226P 2023 12 27.0656 1.773971 0.528864 341.0320 54.0132 44.0449 20250607 12.5 4.0 226P/Pigott-LINEAR-Kowalski MPEC 2024-MB8 -0227P 2024 03 8.3221 1.623605 0.527698 105.5931 36.8025 7.5073 20250607 16.5 2.0 227P/Catalina-LINEAR MPEC 2024-R10 -0228P 2028 09 5.1280 3.423857 0.177397 114.7985 30.9551 7.9156 20250607 14.1 4.0 228P/LINEAR MPEC 2022-HC2 -0229P 2025 03 5.7996 2.440390 0.378008 224.2231 157.8807 26.0965 20250607 13.0 4.0 229P/Gibbs MPC182889 -0230P 2028 08 20.4601 1.570485 0.545455 313.5802 106.9269 15.4721 20250607 13.0 4.0 230P/LINEAR MPC184419 -0231P 2027 08 4.7040 3.086582 0.240024 43.7267 132.7826 12.2723 20250607 14.5 2.0 231P/LINEAR-NEAT MPEC 2023-SQ0 -0232P 2028 09 20.5806 2.967638 0.336109 53.2986 56.0109 14.6429 20250607 11.5 4.0 232P/Hill MPC112394 -0233P 2026 01 8.1407 1.776702 0.412971 27.0258 74.8974 11.2889 20250607 15.0 4.0 233P/La Sagra MPEC 2021-N06 -0234P 2024 10 23.6852 2.820910 0.257280 357.4457 179.5649 11.5337 20250607 12.0 4.0 234P/LINEAR MPC184419 -0235P 2025 12 22.6035 1.978073 0.426123 352.1610 200.1786 9.8125 20250607 12.0 4.0 235P/LINEAR MPC184419 -0236P 2025 02 3.8327 1.828122 0.509273 119.4267 245.5692 16.3554 20250607 14.0 4.0 236P/LINEAR MPEC 2024-P23 -0237P 2023 05 14.4249 1.995252 0.432681 25.5322 245.3579 14.0114 20250607 14.5 2.0 237P/LINEAR MPC182890 -0238P 2028 01 24.0320 2.373692 0.250615 324.2657 51.6485 1.2637 20250607 14.5 4.0 238P/Read MPEC 2024-L77 -0239P 2028 06 17.6631 1.644945 0.631495 220.3823 255.9373 11.3067 20250607 17.5 2.0 239P/LINEAR MPEC 2021-F20 -0240P 2025 12 19.9922 2.121690 0.450335 352.0749 74.9134 23.5371 20250607 11.0 4.0 240P/NEAT MPEC 2024-YC7 -0241P 2021 07 26.1985 1.921092 0.610144 111.6127 305.4186 21.0948 20250607 13.5 4.0 241P/LINEAR MPEC 2022-J42 -0242P 2024 12 23.3627 3.971675 0.282836 244.9766 180.2471 32.4231 20250607 8.0 4.0 242P/Spahr MPC184419 -0243P 2026 02 25.5309 2.448047 0.360311 283.7011 87.6477 7.6441 20250607 12.5 4.0 243P/NEAT MPEC 2022-K19 -0244P 2022 11 20.0911 3.924390 0.199835 93.5046 354.0076 2.2576 20250607 9.0 4.0 244P/Scotti MPEC 2024-L77 -0245P 2026 03 31.1959 2.205471 0.455804 316.5013 316.8853 21.1714 20250607 14.0 4.0 245P/WISE MPEC 2022-CN4 -0246P 2029 10 20.8243 3.349306 0.220436 185.4957 74.2175 17.4879 20250607 10.5 4.0 246P/NEAT MPEC 2024-YC7 -0247P 2026 10 25.9558 1.484153 0.625583 47.5037 53.9871 13.6581 20250607 16.5 2.0 247P/LINEAR MPEC 2021-F20 -0248P 2025 09 14.9263 2.157756 0.639286 209.9803 207.8066 6.3520 20250607 14.0 4.0 248P/Gibbs MPC 75730 -0249P 2025 02 1.6973 0.499542 0.819377 65.7503 239.0417 8.3848 20250607 15.5 4.0 249P/LINEAR MPEC 2022-YN2 -0250P 2025 05 16.7319 2.272327 0.398374 45.7061 73.3031 13.1521 20250607 14.5 4.0 250P/Larson MPC182890 -0251P 2024 02 13.1500 1.741149 0.504214 31.1929 219.3373 23.3884 20250607 16.5 2.0 251P/LINEAR MPEC 2024-TD8 -0252P 2026 11 7.7416 1.003712 0.671047 343.3749 190.9062 10.4199 20250607 17.5 4.0 252P/LINEAR MPEC 2021-S45 -0253P 2024 10 21.0322 2.026499 0.415181 230.8501 146.8343 4.9449 20250607 14.5 4.0 253P/PANSTARRS MPC182890 -0254P 2020 09 28.4499 3.148687 0.318474 219.7264 129.1793 32.5387 20250607 11.0 4.0 254P/McNaught MPC184419 -0255P 2027 09 25.4980 0.847219 0.712054 186.0449 275.6366 13.4053 20250607 9.0 4.0 255P/Levy NK 2214 -0256P 2023 03 11.9393 2.697564 0.418010 124.0662 81.3247 27.6234 20250607 14.0 2.0 256P/LINEAR MPEC 2024-L77 -0257P 2028 01 1.6961 2.152357 0.428773 117.7268 207.7287 20.2156 20250607 11.5 4.0 257P/Catalina MPEC 2023-A50 -0258P 2029 08 28.8224 3.469190 0.209546 25.6082 126.2360 6.7511 20250607 13.0 4.0 258P/PANSTARRS MPEC 2021-U31 -0259P 2026 08 12.1614 1.804866 0.338733 257.4883 51.3732 15.8982 20250607 15.5 4.0 259P/Garradd MPC106349 -0260P 2026 08 4.9899 1.417605 0.608790 18.4922 349.3050 15.0430 20250607 13.5 4.0 260P/McNaught MPEC 2022-O01 -0261P 2025 12 27.3783 2.014210 0.422809 67.3645 291.0505 6.0733 20250607 14.0 4.0 261P/Larson MPEC 2021-J28 -0262P 2030 12 15.0434 1.264102 0.815979 171.0696 217.8865 29.2496 20250607 13.5 4.0 262P/McNaught-Russell MPC 82322 -0263P 2023 01 30.9050 1.234436 0.594051 35.0217 105.5039 11.5267 20250607 18.0 4.0 263P/Gibbs MPEC 2024-L77 -0264P 2027 03 15.6281 2.657770 0.340392 341.1331 219.1493 25.1457 20250607 13.0 4.0 264P/Larsen MPC114608 -0265P 2021 02 8.6987 1.505233 0.646726 33.5635 342.9219 14.3408 20250607 14.5 4.0 265P/LINEAR MPC 79870 -0266P 2026 12 7.3131 2.325141 0.340932 97.7901 4.9467 3.4283 20250607 14.7 4.0 266P/Christensen MPEC 2021-F20 -0267P 2024 04 24.9239 1.235637 0.614866 114.1983 228.5543 6.1399 20250607 19.5 4.0 267P/LONEOS MPC114608 -0268P 2024 12 18.4801 2.412697 0.474492 0.0167 125.6325 15.6615 20250607 14.0 4.0 268P/Bernardi MPC184419 -0269P 2033 07 11.3513 3.998541 0.433512 225.7307 241.7646 7.0839 20250607 10.0 4.0 269P/Jedicke MPEC 2023-J29 -0270P 2030 08 16.6594 3.522829 0.470186 209.9285 223.0252 2.9248 20250607 8.0 4.0 270P/Gehrels MPC 88332 -0271P 2032 03 21.7304 4.248477 0.395879 36.6173 9.2795 6.8667 20250607 11.0 4.0 271P/van Houten-Lemmon MPC 92277 -0272P 2022 07 17.4948 2.429559 0.455501 27.8897 109.4391 18.0822 20250607 16.0 2.0 272P/NEAT MPEC 2023-D41 -0273P 2012 12 21.9541 0.813485 0.974520 20.1264 320.3843 136.3695 20250607 11.5 4.0 273P/Pons-Gambart MPC 82723 -0274P 2022 04 9.1604 2.450906 0.440240 38.4945 81.3175 15.8206 20250607 13.0 4.0 274P/Tombaugh-Tenagra MPEC 2024-GJ3 -0275P 2026 10 27.9935 1.659053 0.713749 173.8955 348.6850 21.2543 20250607 17.0 4.0 275P/Hermann MPC 81862 -0276P 2024 12 11.0147 3.898631 0.273536 199.3543 211.2699 14.7753 20250607 11.5 4.0 276P/Vorobjov MPC184419 -0277P 2028 07 25.8343 1.902137 0.506401 152.4366 276.2601 16.7929 20250607 15.1 4.0 277P/LINEAR MPEC 2021-F20 -0278P 2027 09 15.1224 1.998232 0.451225 240.3306 12.7683 6.6126 20250607 14.0 4.0 278P/McNaught MPEC 2021-S45 -0279P 2023 04 18.7535 2.142821 0.399448 5.6319 346.0999 5.0529 20250607 14.0 4.0 279P/LaSagra MPEC 2024-A43 -0280P 2023 08 4.3950 2.638607 0.416823 104.6390 131.3778 11.7754 20250607 12.5 4.0 280P/Larsen MPEC 2024-RQ6 -0281P 2023 02 4.2051 4.036817 0.173922 27.0087 87.1662 4.7176 20250607 11.0 4.0 281P/MOSS MPEC 2023-D41 -0282P 2021 10 22.6766 3.440664 0.187654 9.0939 217.6073 5.8137 20250607 13.5 2.0 282P MPC133426 -0283P 2021 09 8.3060 2.127946 0.484975 22.1445 161.1234 14.4684 20250607 16.0 2.0 283P/Spacewatch MPEC 2022-K19 -0284P 2028 10 1.6411 2.301840 0.374316 202.4637 144.2643 11.8530 20250607 13.0 4.0 284P/McNaught MPEC 2024-D33 -0285P 2023 01 11.8208 1.720703 0.618075 178.3851 185.5139 25.0327 20250607 15.0 4.0 285P/LINEAR MPEC 2024-L77 -0286P 2022 05 12.5129 2.321274 0.430899 24.0456 283.5748 17.2245 20250607 14.0 4.0 286P/Christensen MPEC 2024-LE0 -0287P 2023 07 10.5451 3.044328 0.272883 190.4031 138.6932 16.3397 20250607 13.5 4.0 287P/Christensen MPEC 2025-A40 -0288P 2027 06 28.9933 2.441595 0.199617 280.2869 83.1061 3.2383 20250607 16.0 2.0 288P MPC133426 -0289P 2025 04 14.3174 0.954331 0.686460 9.8759 68.8910 5.9002 20250607 19.0 4.0 289P/Blanpain MPEC 2024-O39 -0290P 2029 07 22.2171 2.310011 0.628239 181.8587 302.6723 20.0452 20250607 10.5 4.0 290P/Jager MPC 95214 -0291P 2023 05 3.9973 2.567361 0.433871 173.5637 237.6618 6.3096 20250607 13.0 4.0 291P/NEAT MPEC 2024-YC7 -0292P 2029 03 3.6850 2.500034 0.589886 319.6607 90.8953 24.3225 20250607 12.5 4.0 292P/Li MPEC 2022-K19 -0293P 2027 11 29.0390 2.111547 0.419531 40.9855 78.3612 9.0610 20250607 14.5 4.0 293P/Spacewatch MPEC 2022-L66 -0294P 2025 08 11.1904 1.273051 0.600960 237.5841 309.6004 17.7429 20250607 15.5 4.0 294P/LINEAR MPC184419 -0295P 2026 07 22.7289 2.026083 0.617634 73.0414 7.3806 21.0849 20250607 12.0 4.0 295P/LINEAR MPEC 2022-K19 -0296P 2027 03 20.4442 1.784476 0.485992 350.2391 263.5270 25.3750 20250607 14.0 4.0 296P/Garradd MPEC 2021-N06 -0297P 2027 10 18.3866 2.552024 0.285073 142.3655 92.1754 11.2481 20250607 15.0 4.0 297P/Beshore MPC102956 -0298P 2027 06 24.7748 2.199813 0.386919 100.6203 52.7858 7.8723 20250607 15.0 4.0 298P/Christensen MPC114609 -0299P 2024 04 30.0134 3.155804 0.280934 323.6180 271.5804 10.4690 20250607 11.5 4.0 299P/Catalina-PANSTARRS MPEC 2024-TD8 -0300P 2023 04 11.0102 0.830213 0.692095 222.8782 95.6225 5.6766 20250607 16.0 4.0 300P/Catalina MPEC 2023-VM5 -0301P 2028 05 17.1193 2.379948 0.586227 193.4329 351.0625 10.3288 20250607 13.0 4.0 301P/LINEAR-NEAT MPC 89014 -0302P 2025 03 9.3965 3.288628 0.229338 208.6251 121.7156 6.0357 20250607 12.5 4.0 302P/Lemmon-PANSTARRS MPEC 2024-YC7 -0303P 2026 02 19.9151 2.468158 0.510275 357.0297 347.9490 7.0162 20250607 13.5 4.0 303P/NEAT MPC 92278 -0304P 2026 03 18.1981 1.257203 0.600846 335.2794 58.9379 2.6056 20250607 16.5 4.0 304P/Ory MPEC 2022-K19 -0305P 2024 11 17.1375 1.418282 0.694088 147.4036 240.0993 11.6706 20250607 18.0 4.0 305P/Skiff MPC182890 -0306P 2025 08 1.6474 1.272974 0.592573 0.8972 341.3519 8.3029 20250607 19.0 4.0 306P/LINEAR MPC 92278 -0307P 2028 12 2.2678 1.881082 0.675007 222.2539 158.1133 4.4346 20250607 15.0 4.0 307P/LINEAR MPC 92278 -0308P 2032 04 30.5504 4.197447 0.364151 333.7577 63.0994 4.8521 20250607 13.0 2.0 308P/Lagerkvist-Carsenty MPEC 2022-C56 -0309P 2024 03 28.9491 1.670158 0.618217 49.9181 10.1387 17.0199 20250607 15.0 4.0 309P/LINEAR MPC184419 -0310P 2023 10 23.1355 2.416294 0.422074 31.5182 8.8835 13.1202 20250607 13.5 4.0 310P/Hill MPC182891 -0311P 2024 01 1.8907 1.935914 0.115493 144.2911 279.1689 4.9713 20250607 17.0 4.0 311P/PANSTARRS MPC184419 -0312P 2027 03 15.4912 1.990855 0.426671 207.6982 144.6358 19.7461 20250607 16.0 4.0 312P/NEAT MPEC 2024-NE4 -0313P 2025 12 2.7313 2.421615 0.234469 254.9845 105.9254 10.9810 20250607 15.0 4.0 313P/Gibbs MPEC 2024-N80 -0314P 2016 10 13.6273 4.214850 0.418570 213.8651 267.6230 3.9920 20250607 9.5 4.0 314P/Montani MPC105243 -0315P 2027 11 16.5178 2.359080 0.522084 65.9152 68.6388 17.7349 20250607 11.0 4.0 315P/LONEOS MPEC 2023-J29 -0316P 2024 10 4.6046 3.717662 0.156619 187.0292 245.8867 9.8739 20250607 13.5 4.0 316P/LONEOS-Christensen MPC182891 -0317P 2025 10 30.8645 1.266631 0.572017 334.8876 275.4729 11.9748 20250607 17.5 4.0 317P/WISE MPEC 2020-C98 -0318P 2015 10 22.5560 2.455268 0.673274 313.3025 35.6057 17.8645 20250607 8.5 6.0 318P/McNaught-Hartley MPC102103 -0319P 2022 03 30.5813 1.188413 0.666415 203.5954 111.3650 15.0967 20250607 15.0 4.0 319P/Catalina-McNaught MPC184420 -0320P 2026 06 27.8606 0.975539 0.684898 0.7569 295.9405 4.9028 20250607 20.5 4.0 320P/McNaught MPC 96281 -0321P 2023 10 26.5036 0.046007 0.981005 172.7403 165.0264 20.0548 20250607 20.0 4.0 321P/SOHO MPC105243 -0322P 2023 08 21.1627 0.050350 0.979930 57.0765 351.3451 11.4483 20250607 19.0 4.0 322P/SOHO MPC102103 -0323P 2025 03 14.2315 0.040388 0.983449 353.3260 323.9472 5.2114 20250607 20.0 4.0 323P/SOHO MPC182891 -0323P b 2025 12 16.2395 0.040099 0.986125 353.9663 323.4632 5.4606 20250607 26.0 4.0 323P-B/SOHO MPEC 2024-F21 -0323P c 2025 04 7.1008 0.039790 0.984767 353.2123 324.1881 5.3377 20250607 27.0 4.0 323P-C/SOHO MPEC 2024-F21 -0324P 2026 10 14.7649 2.623998 0.152801 57.4188 270.5691 21.3992 20250607 13.0 4.0 324P/LaSagra MPEC 2021-W31 -0325P 2022 03 24.0978 1.465242 0.587192 344.9151 256.8575 16.8469 20250607 14.0 4.0 325P/Yang-Gao MPEC 2024-LE0 -0326P 2023 12 28.3698 2.761392 0.320498 278.0740 99.7608 2.4737 20250607 13.5 4.0 326P/Hill MPEC 2024-LE0 -0327P 2022 09 1.8680 1.558756 0.562520 185.0403 173.9985 36.2309 20250607 16.0 4.0 327P/VanNess MPEC 2024-M41 -0328P 2024 07 27.9351 1.872486 0.553147 30.6760 341.5489 17.6792 20250607 14.5 4.0 328P/LONEOS-Tucker MPEC 2024-YC7 -0329P 2027 09 25.6045 1.664065 0.678881 343.6018 87.6876 21.7189 20250607 13.5 4.0 329P/LINEAR-Catalina MPC101101 -0330P 2033 09 5.4910 2.973039 0.550571 188.8366 293.0837 15.7400 20250607 12.0 4.0 330P/Catalina MPEC 2023-J29 -0331P 2025 12 24.5831 2.878519 0.041442 185.5961 216.7425 9.7407 20250607 12.0 4.0 331P/Gibbs MPEC 2024-Q20 -0332P 2027 01 19.7205 1.574393 0.489842 152.2975 3.7544 9.3858 20250607 18.0 4.0 332P/Ikeya-Murakami MPEC 2016-K18 -0332P a 2027 01 19.7220 1.574361 0.489850 3.7383 152.3146 9.3856 20250607 9.0 4.0 332P-A/Ikeya-Murakami MPEC 2016-K18 -0332P b 2016 03 17.1650 1.572891 0.489707 152.3711 3.8028 9.3805 19.0 4.0 332P-B/Ikeya-Murakami MPEC 2016-EI8 -0332P c 2027 01 19.6116 1.574327 0.489855 3.7387 152.3058 9.3847 20250607 16.5 4.0 332P-C/Ikeya-Murakami MPEC 2016-K18 -0332P d 2016 03 17.2819 1.572064 0.489778 152.4393 3.7923 9.3761 19.0 4.0 332P-D/Ikeya-Murakami MPEC 2016-ED0 -0332P e 2016 03 17.0610 1.573139 0.489220 152.2825 3.8228 9.3774 21.0 4.0 332P-E/Ikeya-Murakami MPEC 2016-ED0 -0332P f 2016 03 17.8554 1.584174 0.499189 152.8203 3.4757 9.5293 21.0 4.0 332P-F/Ikeya-Murakami MPEC 2016-ED0 -0332P g 2016 03 19.5375 1.549652 0.492004 154.4000 3.6955 9.2523 19.0 4.0 332P-G/Ikeya-Murakami MPEC 2016-ED0 -0332P h 2027 01 20.1452 1.574308 0.489891 3.7384 152.3065 9.3852 20250607 19.0 4.0 332P-H/Ikeya-Murakami MPC100285 -0332P i 2016 03 17.3515 1.573073 0.489555 152.3297 3.8048 9.3791 20.5 2.0 332P-I/Ikeya-Murakami MPEC 2016-ED0 -0332P j 2016 03 17.7739 1.575357 0.494294 152.7712 3.6729 9.4296 20.5 2.0 332P-J/Ikeya-Murakami MPEC 2016-EI8 -0333P 2024 11 29.2982 1.112998 0.736284 26.0208 115.7067 132.0224 20250607 15.0 4.0 333P/LINEAR MPC182891 -0334P 2017 06 4.3958 4.422518 0.351964 90.0699 90.3619 20.3646 20250607 10.5 4.0 334P/NEAT MPEC 2023-J29 -0335P 2022 08 12.5222 1.620968 0.546866 162.3214 330.7916 7.2978 20250607 16.8 4.0 335P/Gibbs MPEC 2023-M14 -0336P 2028 05 14.4625 2.788726 0.446150 308.6902 298.1716 17.8712 20250607 13.5 4.0 336P/McNaught MPC105244 -0337P 2022 06 25.9826 1.726803 0.483226 166.1615 102.1071 16.9967 20250607 17.0 4.0 337P/WISE MPEC 2024-A43 -0338P 2024 08 3.3180 2.287593 0.412786 4.6326 9.7459 25.3761 20250607 12.0 4.0 338P/McNaught MPC182891 -0339P 2023 08 30.9794 1.347015 0.635797 172.6745 27.4580 5.7346 20250607 17.0 4.0 339P/Gibbs MPC101101 -0340P 2025 08 29.2589 3.057947 0.279977 36.0649 291.6595 2.0790 20250607 14.3 4.0 340P/Boattini MPC133426 -0341P 2025 04 22.7088 2.506426 0.415050 312.3622 29.9526 3.7965 20250607 12.5 4.0 341P/Gibbs MPEC 2023-J29 -0342P 2027 02 7.6938 0.051751 0.982981 27.6513 73.3085 11.6901 20250607 9.0 4.0 342P/SOHO MPC101101 -0343P 2029 11 4.6256 2.266022 0.584823 137.6081 257.0545 5.5976 20250607 14.0 4.0 343P/NEAT-LONEOS MPEC 2024-PC5 -0344P 2027 07 24.8358 2.797731 0.423741 140.6245 273.1014 3.4996 20250607 13.0 4.0 344P/Read MPEC 2023-J29 -0345P 2024 08 31.0096 3.139774 0.221345 196.7603 154.5068 2.7280 20250607 12.0 4.0 345P/LINEAR MPEC 2024-TP3 -0346P 2026 08 1.2529 2.216448 0.503910 336.0765 102.4579 22.2194 20250607 14.0 4.0 346P/Catalina MPEC 2022-K19 -0347P 2023 07 19.2503 2.206971 0.386957 98.0936 260.9915 11.7660 20250607 15.0 4.0 347P/PANSTARRS MPEC 2024-RQ6 -0348P 2027 09 19.1383 2.182497 0.307498 135.7760 312.9127 17.7427 20250607 14.0 4.0 348P/PANSTARRS MPEC 2022-ED3 -0349P 2024 05 26.9507 2.509649 0.298594 255.7502 331.7388 5.4892 20250607 14.0 4.0 349P/Lemmon MPEC 2024-LE0 -0350P 2026 03 17.4107 3.694352 0.094709 140.0563 65.2953 7.3655 20250607 14.0 4.0 350P/McNaught MPC184420 -0351P 2025 03 26.1607 3.131866 0.294732 352.5578 283.3862 12.7789 20250607 12.5 4.0 351P/Wiegert-PANSTARRS MPC184420 -0352P 2017 06 18.5716 2.555944 0.615969 309.3709 28.0508 21.0036 20250607 13.2 4.0 352P/Skiff MPEC 2023-J29 -0353P 2026 07 1.4691 2.211773 0.469711 230.4855 121.5095 28.4192 20250607 14.5 4.0 353P/McNaught MPEC 2020-AA5 -0354P 2023 10 14.2523 2.005325 0.124449 132.9363 320.0587 5.2507 20250607 15.5 4.0 354P/LINEAR MPEC 2024-EF7 -0355P 2024 04 1.2457 1.705961 0.507961 336.2591 51.4242 11.0460 20250607 15.5 2.0 355P/LINEAR-NEAT MPEC 2023-CD7 -0356P 2026 06 12.3230 2.674656 0.355868 226.2159 160.7914 9.6419 20250607 14.0 4.0 356P/WISE MPEC 2022-F14 -0357P 2027 10 29.6424 2.512565 0.436012 1.5056 44.5679 6.3126 20250607 15.5 4.0 357P/Hill MPC114609 -0358P 2023 11 9.5161 2.392365 0.239479 299.3321 85.6673 11.0668 20250607 18.0 4.0 358P/PANSTARRS MPEC 2024-EF7 -0359P 2027 08 24.4275 3.142462 0.323116 200.2814 149.7455 10.2618 20250607 13.5 4.0 359P/LONEOS MPC110086 -0360P 2024 10 3.8284 1.851750 0.499394 354.3254 2.1565 24.1054 20250607 19.5 6.0 360P/WISE MPEC 2025-A40 -0361P 2029 06 21.6251 2.764802 0.439527 219.1327 203.2288 13.8976 20250607 12.0 4.0 361P/Spacewatch MPEC 2023-CD7 -0363P 2024 11 13.2231 1.720986 0.518561 340.7629 146.7583 5.3938 20250607 17.5 4.0 363P/Lemmon MPC184420 -0364P 2023 05 12.7369 0.819619 0.717485 212.8214 45.8295 11.8874 20250607 17.0 2.0 364P/PANSTARRS MPEC 2024-M41 -0365P 2023 10 9.5116 1.320420 0.581653 67.4151 86.6558 9.8499 20250607 17.0 4.0 365P/PANSTARRS MPC111775 -0366P 2025 01 30.8881 2.279975 0.348650 152.9939 70.7230 8.8567 20250607 15.0 4.0 366P/Spacewatch MPC114610 -0367P 2025 01 11.5227 2.527941 0.280141 172.6817 58.6609 8.4591 20250607 17.5 2.0 367P/Catalina MPC112395 -0368P 2031 09 23.7580 2.072167 0.625636 118.9858 257.8564 15.4825 20250607 14.0 4.0 368P/NEAT MPC114610 -0369P 2027 12 18.9450 1.944545 0.555899 13.2411 47.2842 10.3194 20250607 15.0 4.0 369P/Hill MPC114610 -0370P 2018 06 12.7357 2.478543 0.615147 356.7862 55.0864 19.4170 20250607 13.0 4.0 370P/NEAT MPEC 2021-F20 -0371P 2027 04 25.9766 2.188217 0.476573 308.5665 67.2837 17.3837 20250607 16.0 4.0 371P/LINEAR-Skiff MPC114610 -0372P 2028 05 24.1762 3.830510 0.151214 325.9547 27.5495 9.5038 20250607 13.5 4.0 372P/McNaught MPEC 2020-K19 -0373P 2026 09 4.9523 2.301629 0.393816 221.1400 231.9304 13.7707 20250607 14.5 4.0 373P/Rinner MPEC 2021-F20 -0374P 2030 02 14.2866 2.666529 0.463617 51.5881 7.8651 10.7604 20250607 14.0 4.0 374P/Larson MPC114610 -0375P 2018 12 23.7806 1.884058 0.660253 119.4548 359.8306 17.3748 20250607 16.0 4.0 375P/Hill MPEC 2021-F20 -0376P 2019 09 13.0402 2.798454 0.513751 285.3446 312.8501 1.1662 20250607 12.5 4.0 376P/LONEOS MPEC 2024-RQ6 -0377P 2020 07 9.5016 5.011329 0.251454 354.8934 225.9300 9.0321 20250607 9.5 4.0 377P/Scotti MPEC 2022-N37 -0378P 2020 10 6.3545 3.373616 0.463391 193.3032 93.7910 19.1600 20250607 12.0 4.0 378P/McNaught MPEC 2025-A40 -0379P 2026 02 22.8127 2.263425 0.350190 184.6969 30.4474 12.4366 20250607 15.0 4.0 379P/Spacewatch MPC115889 -0380P 2028 08 8.3300 2.960208 0.333859 87.6880 127.7067 8.0341 20250607 12.5 4.0 380P/PANSTARRS MPEC 2023-C45 -0381P 2019 09 25.0716 2.282641 0.680530 173.8476 173.3215 28.3365 20250607 17.5 2.0 381P/LINEAR-Spacewatch MPEC 2021-J28 -0382P 2021 10 29.5070 4.327115 0.265256 162.4166 170.1174 8.2729 20250607 8.0 4.0 382P/Larson MPC182891 -0383P 2026 07 2.5861 1.425045 0.598474 133.7223 207.8549 12.3167 20250607 18.0 4.0 383P/Christensen MPEC 2022-OB6 -0384P 2024 09 19.1196 1.111873 0.616253 37.7015 354.1877 7.2841 20250607 19.5 4.0 384P/Kowalski MPC182891 -0385P 2028 08 4.8709 2.565567 0.401845 44.4646 357.0334 16.8222 20250607 13.0 4.0 385P/Hill MPEC 2021-F20 -0386P 2028 10 13.7436 2.358494 0.417515 353.1051 134.9159 15.2470 20250607 14.5 4.0 386P/PANSTARRS MPEC 2021-L04 -0387P 2030 03 13.1125 1.261845 0.736977 162.8531 259.2388 8.9379 20250607 15.0 4.0 387P/Boattini MPEC 2021-J28 -0388P 2019 07 26.8058 1.994877 0.619357 42.3719 37.0081 23.8776 20250607 13.0 4.0 388P/Gibbs MPEC 2021-S45 -0389P 2019 12 31.3658 1.656768 0.705725 249.3209 218.8495 160.0792 20250607 16.0 4.0 389P/Siding Spring MPEC 2022-OB6 -0390P 2020 03 22.3468 1.706662 0.706652 232.5597 152.1999 18.5218 20250607 12.0 4.0 390P/Gibbs MPEC 2024-EF7 -0391P 2028 05 11.1802 4.136292 0.118368 186.9236 124.7736 21.2568 20250607 8.0 4.0 391P/Kowalski MPEC 2021-F20 -0392P 2020 04 2.9856 1.941400 0.683938 71.9684 24.8005 4.9284 20250607 14.5 4.0 392P/LINEAR MPEC 2021-J28 -0393P 2030 05 7.1159 4.228917 0.119079 329.2023 36.4019 16.7833 20250607 11.0 4.0 393P/Spacewatch-Hill MPC182892 -0394P 2028 11 30.1102 2.732685 0.368375 54.4531 98.1022 8.5280 20250607 16.0 2.4 394P/PANSTARRS MPEC 2020-KB7 -0395P 2022 02 20.4995 4.240018 0.411371 100.7037 220.9653 3.5695 20250607 10.0 4.0 395P/Catalina-NEAT MPC182892 -0396P 2019 08 29.2252 3.963556 0.417014 8.3089 136.6070 5.4426 20250607 12.0 4.0 396P MPEC 2020-KB7 -0397P 2027 12 21.1783 2.281817 0.404576 14.5880 8.2082 10.9198 20250607 12.0 4.0 397P/Lemmon MPEC 2022-OB6 -0398P 2026 07 7.9247 1.300485 0.583766 127.5514 320.1346 11.0276 20250607 15.5 4.0 398P/Boattini MPEC 2021-L04 -0399P 2028 10 12.5248 2.096827 0.447279 214.4505 207.1161 13.3161 20250607 14.0 4.0 399P/PANSTARRS MPEC 2023-XP6 -0400P 2027 11 3.0223 2.103038 0.409589 238.9537 176.3469 10.9251 20250607 15.5 2.8 400P/PANSTARRS MPEC 2024-TD8 -0401P 2019 12 3.1834 2.435737 0.578346 309.3502 359.9230 12.8003 20250607 12.5 4.0 401P/McNaught MPEC 2022-K19 -0402P 2021 12 16.0424 3.942863 0.440016 326.9953 123.0442 30.8290 20250607 9.0 4.0 402P/LINEAR MPEC 2024-LE0 -0403P 2020 09 17.8889 2.693412 0.504225 163.9713 277.5609 12.3321 20250607 12.0 4.0 403P/Catalina MPEC 2021-J28 -0404P 2023 10 31.6874 4.132457 0.124185 168.9818 260.0414 9.8042 20250607 10.0 4.0 404P/Bressi MPC184420 -0405P 2027 10 29.5759 1.116462 0.690199 3.3095 112.1934 9.3791 20250607 17.5 4.0 405P/Lemmon MPEC 2021-L04 -0406P 2027 06 24.8821 1.642885 0.541027 11.5603 352.3872 1.2098 20250607 17.0 4.0 406P/Gibbs MPEC 2021-F20 -0407P 2026 07 25.6178 2.180538 0.375802 93.1181 80.2440 4.8756 20250607 14.0 4.0 407P/PANSTARRS-Fuls MPEC 2022-YN2 -0408P 2022 10 6.0525 3.471990 0.268408 226.6931 189.4513 19.3516 20250607 11.0 4.0 408P/Novichonok-Gerke MPC184420 -0409P 2021 01 28.6707 1.748064 0.710239 15.0413 143.6402 17.1487 20250607 14.0 4.0 409P/LONEOS-Hill MPEC 2022-ED3 -0410P 2021 06 24.7597 3.248927 0.511720 313.2759 139.9321 9.3881 20250607 12.5 4.0 410P/NEAT-LINEAR MPEC 2022-M21 -0411P 2021 01 25.7171 2.430419 0.581806 46.5713 77.6513 12.3887 20250607 13.5 4.0 411P/Christensen MPC184420 -0412P 2026 05 30.6388 1.620937 0.479056 155.8592 0.8422 8.9295 20250607 17.0 4.0 412P/WISE MPEC 2021-F20 -0413P 2028 10 3.3046 2.174952 0.417792 186.7365 38.9485 15.9599 20250607 14.0 4.0 413P/Larson MPC184420 -0414P 2025 09 26.3288 0.524164 0.812267 210.7105 257.8154 23.4073 20250607 19.0 4.0 414P/STEREO MPEC 2024-JU4 -0415P 2029 06 13.6921 3.304886 0.195532 345.8839 160.2578 31.8097 20250607 12.0 4.0 415P/Tenagra MPEC 2022-J42 -0416P 2029 02 23.8581 2.181589 0.455479 134.4535 355.7315 3.3635 20250607 15.5 4.0 416P/Scotti MPC184420 -0417P 2027 05 12.7447 1.490433 0.554714 126.4646 112.0339 9.9002 20250607 16.5 4.0 417P/NEOWISE MPEC 2021-W31 -0418P 2021 10 16.3639 1.710917 0.663870 307.3346 277.6185 5.7809 20250607 13.0 4.0 418P/LINEAR MPEC 2022-TA0 -0419P 2028 06 15.3740 2.567002 0.273637 187.8498 40.4101 2.7951 20250607 12.5 4.0 419P/PANSTARRS MPEC 2023-UR6 -0420P 2022 05 18.1699 2.767435 0.495113 156.4067 173.5362 14.5003 20250607 11.5 4.0 420P/Hill MPEC 2024-L77 -0421P 2021 01 23.6117 1.652444 0.674384 259.8586 55.3316 10.0758 20250607 14.0 4.0 421P/McNaught MPEC 2021-W31 -0422P 2022 01 10.7554 3.101343 0.505701 304.7600 36.0130 39.5804 20250607 11.0 4.0 422P/Christensen MPEC 2024-N80 -0423P 2021 09 26.5503 5.423079 0.122787 80.9199 33.3020 8.3426 20250607 8.0 4.0 423P/Lemmon MPEC 2023-FK0 -0424P 2021 10 30.8860 1.368866 0.690373 312.5567 51.2117 8.6815 20250607 17.0 4.0 424P/LaSagra MPEC 2022-CN4 -0425P 2021 09 20.9687 2.898155 0.543718 200.9908 210.0867 16.4138 20250607 12.0 4.0 425P/Kowalski MPEC 2024-C04 -0426P 2023 09 10.3346 2.672800 0.161039 118.3922 280.3970 17.7841 20250607 13.5 4.0 426P/PANSTARRS MPEC 2024-N80 -0428P 2027 11 17.9743 1.680748 0.518205 36.8957 299.3112 8.5029 20250607 15.0 4.0 428P/Gibbs MPEC 2023-J29 -0429P 2028 09 16.2989 1.810451 0.490852 75.7352 322.0144 7.5142 20250607 15.5 4.0 429P/LINEAR-Hill MPEC 2024-EF7 -0430P 2027 05 22.4892 1.550764 0.500274 94.4519 54.6469 4.4756 20250607 16.5 4.0 430P/Scotti MPEC 2022-L66 -0431P 2028 08 8.6553 1.817259 0.477351 200.0018 202.8384 22.3803 20250607 14.0 4.0 431P/Scotti MPEC 2025-A40 -0432P 2026 12 15.4250 2.306582 0.240841 105.2718 239.1306 10.0678 20250607 17.0 4.0 432P/PANSTARRS MPEC 2021-U31 -0434P 2021 10 27.1034 3.001368 0.274320 128.4444 288.9135 6.3363 20250607 13.0 4.0 434P/Tenagra MPEC 2024-D33 -0435P 2026 10 26.6486 2.062085 0.317562 244.2095 98.5244 18.8745 20250607 17.0 4.0 435P/PANSTARRS MPEC 2021-W31 -0436P 2021 12 7.8069 1.964666 0.669069 282.7618 87.1567 20.1993 20250607 14.5 4.0 436P/Garradd MPEC 2022-X67 -0437P 2022 08 20.2500 3.403586 0.255057 207.0596 245.8406 3.6890 20250607 13.0 4.0 437P/Lemmon-PANSTARRS MPEC 2023-B57 -0438P 2027 10 25.1481 2.257082 0.414142 58.9868 260.1089 8.2807 20250607 14.5 4.0 438P/Christensen MPEC 2025-A40 -0439P 2028 03 5.6720 1.853811 0.469102 342.1057 56.4377 7.1120 20250607 13.5 4.0 439P/LINEAR MPEC 2022-C56 -0440P 2022 03 30.3738 2.051684 0.760853 183.3005 328.8055 12.3506 20250607 15.5 4.0 440P/Kobayashi MPEC 2024-N80 -0441P 2025 09 9.3538 3.327874 0.194656 178.8630 143.5912 2.5748 20250607 13.5 4.0 441P/PANSTARRS MPEC 2022-X67 -0442P 2022 08 17.6837 2.316124 0.532565 310.6429 31.9518 6.0574 20250607 13.5 4.0 442P/McNaught MPEC 2024-N80 -0443P 2022 10 9.4567 2.957540 0.282955 145.0756 108.9339 19.8879 20250607 13.5 4.0 443P/PANSTARRS-Christensen MPEC 2024-TD8 -0444P 2022 06 30.7432 1.535214 0.557888 172.8648 88.1825 22.7308 20250607 17.0 4.0 444P/WISE-PANSTARRS MPEC 2023-VM5 -0445P 2022 08 16.2241 2.370492 0.414144 213.2128 126.5903 1.0888 20250607 15.0 4.0 445P/Lemmon-PANSTARRS MPEC 2024-BE0 -0446P 2022 05 28.7239 1.610829 0.646757 344.6258 336.3393 16.6278 20250607 16.5 4.0 446P/McNaught MPEC 2024-NE4 -0447P 2022 08 16.4281 4.628525 0.177299 97.5241 302.6370 7.4411 20250607 12.0 4.0 447P/Sheppard-Tholen MPEC 2022-YB4 -0448P 2022 09 6.1621 2.115735 0.418171 218.8004 161.7545 12.1451 20250607 16.0 4.0 448P/PANSTARRS MPEC 2024-PC5 -0449P 2027 09 25.1082 1.872734 0.479774 176.7649 242.5221 15.4702 20250607 16.0 4.0 449P/Leonard MPEC 2024-DC6 -0450P 2027 01 31.7283 5.444217 0.314290 23.4293 124.2896 10.6732 20250607 6.5 4.0 450P/LONEOS MPC184420 -0451P 2022 11 27.9550 2.798890 0.559224 186.7904 300.8688 26.4846 20250607 15.5 4.0 451P/Christensen MPEC 2023-HD1 -0452P 2023 04 25.9668 4.177820 0.428542 37.0947 123.6660 6.4219 20250607 9.0 4.0 452P/Sheppard-Jewitt MPEC 2024-NE4 -0453P 2023 03 3.3550 2.279095 0.583139 70.8972 42.8926 27.0601 20250607 14.0 4.0 453P/WISE-Lemmon MPEC 2023-RF3 -0454P 2022 07 26.6557 2.689231 0.361437 20.1924 54.5858 19.8096 20250607 14.0 4.0 454P/PANSTARRS MPEC 2023-CD7 -0455P 2023 02 24.9412 2.193295 0.304454 237.5346 146.1806 14.1349 20250607 17.0 4.0 455P/PANSTARRS MPEC 2022-Y14 -0456P 2025 04 14.9564 2.802242 0.115960 233.0098 243.1455 16.9653 20250607 13.5 4.0 456P/PANSTARRS MPC182892 -0457P 2024 08 20.0796 2.331997 0.118396 104.3201 175.9634 5.2257 20250607 15.5 4.0 457P/Lemmon-PANSTARRS MPEC 2025-A40 -0458P 2022 10 30.7660 2.634879 0.317253 104.9312 1.5622 13.6223 20250607 17.3 4.0 458P/Jahn MPEC 2023-HD1 -0459P 2023 02 21.6654 1.367930 0.577854 205.2246 256.9876 7.1737 20250607 15.5 4.0 459P/Catalina MPEC 2024-N80 -0460P 2026 09 21.6515 1.016499 0.664214 351.9354 180.5167 18.8999 20250607 21.0 4.0 460P/PANSTARRS MPEC 2023-G14 -0461P 2027 05 3.0315 1.353373 0.569586 174.8314 194.3774 18.3993 20250607 18.5 4.0 461P/WISE MPEC 2024-GJ3 -0462P 2022 08 1.2015 2.050171 0.578436 4.2305 322.6698 7.0450 20250607 17.0 4.0 462P/LONEOS-PANSTARRS MPEC 2024-BE0 -0463P 2023 03 29.8400 0.517854 0.825881 216.3408 283.2178 29.2958 20250607 18.0 4.0 463P/NEOWISE MPEC 2024-GJ3 -0464P 2023 02 27.3301 3.369861 0.280566 267.5305 309.5781 21.6732 20250607 10.5 4.0 464P/PANSTARRS MPEC 2024-Q20 -0465P 2023 05 8.9757 2.324382 0.613176 140.9873 217.9596 25.8619 20250607 12.5 4.0 465P/Hill MPEC 2024-NE4 -0466P 2023 05 9.6263 2.114663 0.477057 197.9146 118.1754 12.7718 20250607 14.0 4.0 466P/PANSTARRS MPEC 2024-JU4 -0467P 2022 11 26.8408 5.508694 0.054523 267.4972 43.2631 2.4793 20250607 9.0 4.0 467P/LINEAR-Grauer MPEC 2025-A40 -0468P 2023 11 21.1147 3.950373 0.445001 322.5779 356.1257 50.4516 20250607 11.5 4.0 468P/SidingSpring MPEC 2024-O39 -0469P 2025 12 8.4128 3.005002 0.307990 43.4952 178.9674 20.1724 20250607 13.5 4.0 469P/PANSTARRS MPEC 2025-A40 -0470P 2023 12 16.7708 2.725781 0.389395 151.6954 246.1700 8.8441 20250607 15.5 4.0 470P/PANSTARRS MPC182892 -0471P 2023 12 19.8514 2.119913 0.627724 94.7957 283.3120 4.7969 20250607 12.0 4.0 471P/LINEAR-Lemmon MPC182892 -0472P 2024 07 14.1988 3.387549 0.564693 218.8441 205.8531 10.8240 20250607 10.5 4.0 472P/NEAT-LINEAR MPC184421 -0473P 2024 02 26.2380 1.406342 0.823599 42.9362 22.1898 56.8975 20250607 13.5 4.0 473P/NEAT MPEC 2024-MB8 -0474P 2023 07 15.6722 2.541733 0.188069 11.2619 26.7494 1.0970 20250607 15.5 4.0 474P/Hogan MPEC 2024-B74 -0475P 2024 06 1.6505 4.077413 0.442781 40.4077 147.3609 14.5237 20250607 11.0 4.0 475P/Spacewatch-LINEAR MPEC 2024-O39 -0476P 2024 10 16.4833 3.123411 0.345905 46.7335 57.0503 19.0052 20250607 12.5 4.0 476P/PANSTARRS MPC184421 -0477P 2023 12 26.5325 1.748659 0.417524 305.8802 59.1468 8.9138 20250607 14.5 4.0 477P/PANSTARRS MPEC 2024-GJ3 -0478P 2024 05 2.1573 2.393939 0.343740 13.2403 127.2635 12.5246 20250607 13.5 4.0 478P/ATLAS MPEC 2024-L77 -0479P 2024 05 5.2575 1.243250 0.778900 263.5073 295.8323 15.3996 20250607 15.0 4.0 479P/Elenin MPEC 2024-PC5 -0480P 2023 04 23.7229 3.474913 0.246330 214.4089 229.9814 13.7167 20250607 12.0 4.0 480P/PANSTARRS MPC182893 -0481P 2023 07 9.2780 3.073532 0.343472 356.7966 93.5504 6.0826 20250607 13.5 4.0 481P/Lemmon-PANSTARRS MPEC 2025-A40 -0482P 2023 06 2.1591 1.907084 0.492366 339.7223 126.0783 24.4868 20250607 13.5 4.0 482P/PANSTARRS MPEC 2024-JU4 -0483P a 2027 11 10.4245 2.484149 0.222448 49.1038 199.3062 14.1911 20250607 13.5 4.0 483P-A/PANSTARRS MPEC 2024-R10 -0483P b 2027 11 10.1869 2.484279 0.222389 49.0939 199.3055 14.1919 20250607 17.0 4.0 483P-B/PANSTARRS MPEC 2024-R10 -0484P 2028 03 10.6394 2.130530 0.432916 240.7957 265.3823 14.4743 20250607 16.0 4.0 484P/Spacewatch MPEC 2024-DD5 -0485P 2023 08 25.1954 3.992729 0.417180 196.0955 261.6447 10.0161 20250607 13.0 4.0 485P/Sheppard-Tholen MPEC 2024-JU4 -0486P 2025 04 3.8370 2.308935 0.363558 93.9449 219.0237 2.2095 20250607 14.5 4.0 486P/Leonard MPEC 2024-R10 -0487P 2024 10 20.5965 1.814750 0.648474 0.8441 49.2040 39.3660 20250607 13.5 4.0 487P/SidingSpring MPC184421 -0488P 2024 05 19.4535 1.678954 0.551052 1.6776 323.9647 11.3711 20250607 16.5 4.0 488P/NEAT-PANSTARRS MPEC 2024-UA9 -0489P 2025 12 4.3390 1.561146 0.647117 109.4300 20.6100 4.0264 20250607 15.5 4.0 489P/Denning MPEC 2024-Q14 -0490P 2024 09 28.1811 1.068979 0.647189 332.5397 307.6016 12.2663 20250607 21.0 4.0 490P/ATLAS MPEC 2024-YC7 -0491P 2024 09 6.0283 3.716464 0.258697 298.8843 311.6845 9.3662 20250607 9.5 4.0 491P/Spacewatch-PANSTARRS MPC184421 -0492P 2024 07 20.4507 1.781968 0.690633 40.9840 11.3056 11.4010 20250607 15.0 4.0 492P/LINEAR MPC182893 -0493P 2026 01 14.1041 3.823261 0.466466 83.1979 1.1071 24.1121 20250607 12.0 2.0 493P/LONEOS MPC182893 -0494P 2024 05 30.9949 2.440446 0.356845 48.8777 245.0430 7.7900 20250607 16.0 4.0 494P/PANSTARRS MPEC 2024-RQ6 -0495P 2025 10 22.3931 3.459917 0.272457 141.3381 291.6181 26.3547 20250607 11.5 4.0 495P/Christensen MPEC 2025-A40 -0496P 2025 03 10.2759 1.621033 0.734226 42.2450 63.5864 14.8144 20250607 14.0 4.0 496P/Hill MPC184421 -0497P 2025 02 15.3227 2.075092 0.630482 32.4047 40.3741 10.4368 20250607 17.5 4.0 497P/Spacewatch-PANSTARRS MPC184421 -0498P 2024 12 18.9126 1.964327 0.572313 179.0802 279.2309 14.4828 20250607 14.7 4.0 498P/LINEAR MPC184421 -0499P 2025 03 4.3922 0.931053 0.691456 2.5567 139.3090 24.5822 20250607 18.5 4.0 499P/Catalina MPC184421 -0500P 2025 03 31.9462 2.131767 0.375872 46.6889 111.5293 2.3015 20250607 16.0 4.0 500P/PANSTARRS MPC184421 -0501P 2024 04 14.3029 0.671892 0.698442 53.6944 139.7797 10.0468 20250607 21.5 4.0 501P/Rankin MPC182882 -0502P 2025 08 5.0979 4.229494 0.471199 37.7433 264.4846 11.3996 20250607 8.5 4.0 502P/NEAT MPC184421 -0503P 2025 11 5.5701 1.897318 0.481306 17.9528 268.5823 10.5748 20250607 15.0 4.0 503P/PANSTARRS MPC184422 -0001I 2017 09 9.4886 0.255240 1.199252 241.6845 24.5997 122.6778 20170904 23.0 2.0 1I/`Oumuamua MPC107687 -0002I 2019 12 8.5548 2.006548 3.356633 209.1251 308.1480 44.0527 20191223 11.0 4.0 2I/Borisov MPEC 2023-L37 From 4de737a72a78d5fe0d7bac7ffef38b67cd753c99 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 22 Jun 2025 01:16:57 +0100 Subject: [PATCH 032/253] Remove PiFinder/python/tetra3 that was mistakenly added. --- python/tetra3 | 1 - 1 file changed, 1 deletion(-) delete mode 120000 python/tetra3 diff --git a/python/tetra3 b/python/tetra3 deleted file mode 120000 index 0cb73b816..000000000 --- a/python/tetra3 +++ /dev/null @@ -1 +0,0 @@ -/home/pifinder/PiFinder/python/PiFinder/tetra3/tetra3 \ No newline at end of file From 7f61c7ef4201bfab38da96135af7bf29d53196f9 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 22 Jun 2025 15:57:31 +0100 Subject: [PATCH 033/253] Update README --- python/README_IMU.md | 1 - 1 file changed, 1 deletion(-) diff --git a/python/README_IMU.md b/python/README_IMU.md index 4348f12f9..f9cced13b 100644 --- a/python/README_IMU.md +++ b/python/README_IMU.md @@ -52,7 +52,6 @@ Ensure that you're in new virtual environment and install the Python packages us cd PiFinder/python pip install -r requirements.txt pip install -r requirements_dev.txt -pip install -r requirements_imu.txt ``` The last line installs the additional packages required (just `numpy-quaternion`). PiFinder can be From 0ad8b444bae6f0449507c5295567084c2de12569 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Sun, 22 Jun 2025 17:09:48 +0200 Subject: [PATCH 034/253] Initialize imu["quat"] and imu["avg_quat"] to None rather than np.quaternion(0, 0, 0, 0) because it's used in statements like if imu["quat"]... --- python/PiFinder/imu_pi.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/python/PiFinder/imu_pi.py b/python/PiFinder/imu_pi.py index e17069990..58478db34 100644 --- a/python/PiFinder/imu_pi.py +++ b/python/PiFinder/imu_pi.py @@ -66,7 +66,7 @@ def __init__(self): self.quat_history = [(0, 0, 0, 0)] * QUEUE_LEN self._flip_count = 0 self.calibration = 0 - self.avg_quat = np.quaternion(0, 0, 0, 0) # Init to invalid quaternion + self.avg_quat = None # Data type: np.quaternion(w, x, y, z) self.__moving = False self.last_sample_time = time.time() @@ -174,7 +174,7 @@ def imu_monitor(shared_state, console_queue, log_queue): "move_start": None, "move_end": None, #"pos": [0, 0, 0], # Corresponds to [Az, related_to_roll, Alt] --> **TO REMOVE LATER - "quat": np.quaternion(0, 0, 0, 0), # Scalar-first quaternion (w, x, y, z) - Init to invalid quaternion + "quat": None, # Scalar-first np.quaternion(w, x, y, z) - Init to invalid quaternion #"start_pos": [0, 0, 0], "status": 0, } From 921d2da2ebd8fe83b08cdbc8526c89c0724fd839 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Tue, 24 Jun 2025 21:41:52 +0200 Subject: [PATCH 035/253] Move to pointing_model/README.md --- python/{README_IMU.md => PiFinder/pointing_model/README.md} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename python/{README_IMU.md => PiFinder/pointing_model/README.md} (100%) diff --git a/python/README_IMU.md b/python/PiFinder/pointing_model/README.md similarity index 100% rename from python/README_IMU.md rename to python/PiFinder/pointing_model/README.md From 8177b6b132de65f19cf0019d3f28c141ae2656b1 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Tue, 24 Jun 2025 21:57:09 +0200 Subject: [PATCH 036/253] Update README with theory --- python/PiFinder/pointing_model/README.md | 214 +++++++++++++++++++++-- 1 file changed, 203 insertions(+), 11 deletions(-) diff --git a/python/PiFinder/pointing_model/README.md b/python/PiFinder/pointing_model/README.md index f9cced13b..5f07ef0f3 100644 --- a/python/PiFinder/pointing_model/README.md +++ b/python/PiFinder/pointing_model/README.md @@ -67,24 +67,216 @@ For testing, running the following command will dump the raw IMU measurements to python PiFinder/imu_print_measurements.py ``` -# Approach: Improved IMU support for quaternions for Altaz +# Theory -During normal operation, we want to find the pointing of the scope, expressed using $q_{hor2scope}$, which is the quaternion that rotates the scope axis in the horizontal frame from the *home* pointing to the current pointing. +## Quaternion rotation -$$q_{hor2scope} = q_{hor2imu} \; q_{drift} \; q_{imu2scope}$$ +A quaternion is defined by -The IMU outputs its orientation $q_{hor2imu}$ but this drifts over time by $q_{drift}$. $q_{imu2scope}$ rotates the IMU frame to the scope frame and is assumed to be fixed and determined during alignment of the PiFinder: +$$\mathbf{q} = \cos(\theta/2) + (u_x \mathbf{i} + u_y \mathbf{j} + u_z +\mathbf{k}) \sin(\theta / 2)$$ -$$q_{imu2scope} = q_{hor2imu}^{-1} \; q_{hor2scope}$$ +This can be interpreted as a rotation around the axis $\mathbf{u}$ by an angle +$\theta$ in the clockwise direction when looking along $\mathbf{u}$ from the +origin. Alternatively, using the right-hand corkscrew rule, the right thumb +points along the axis and fingers in the direction of positive rotation. -During alignment, plate solving gives the pointing of the scope which can be used to estimate $q_{hor2scope}$ assuming a perfect altaz mount. For unit quaternions, we can also use the conjugate $q^*$ instead of $q^{-1}$, which is slightly faster to compute. +We can express a quaternion as -When plate solved scope pointings are available during normal operation, we can estimate the drift, $q_{drift}$; +$$\mathbf{q} = (w, x, y, z)$$ -$$q_{drift} = q_{hor2imu}^{-1} \; q_{hor2scope} \; q_{imu2scope}^{-1}$$ +where $w$ is the scalar part and $(x, y, z)$ is the vector part. We will use +the *scalar-first* convention used by Numpy Quaternion. -where $q_{hor2scope}$ can be estimated from plate solving (again, assuming a perfect altaz mount) and the IMU gives $q_{hor2imu}$. +A vector can be rotated by the quaternion $\mathbf{q}$ by defining the vector +as a pure quaternion $\mathbf{p}$ (where the scalar part is zero) as follows: -## Equatorial mounts +$\mathbf{p^\prime} = \mathbf{qpq}^{-1}$ -It's possible that this can also work with equatorial mounts. Clearly, it won't be correct to use $q_{hor2scope}$ for the scope pointing because this is for altaz mounts and EQ mounts also rate the scope around its axis. It's possible that $q_{drift}$ will compensate for this but it won't be the most efficient way. \ No newline at end of file + +### Numpy quaternion + +In Numpy Quaternion, we can create a quaternion using + +```python +q = np.quaternion(w, x, y, z) +``` + +Quaternion multiplications are simply `q1 * q2`. + +The inverse (or conjugate) is given by `q.conj()`. + + +### Intrinsic and extrinsic rotation + +Intrinsic rotation of $q_0$ followed by $q_1$ + +$$q_{new} = q_0 q_1$$ + +For an extrinsic rotation of $q_0$ followed by $q_1$, left multiply + +$$q_{new} = q_1 q_0$$ + + +## Coordinate frames + +### Home positions + +For an altaz mount, we define the *home position* as az=0°, alt=0°. i.e. the +scope points due North and is horizontal. The $z_{mnt}$ axis of the mount frame +corresponds to the axis of the scope in the *home* position in the ideal case. + +### Coordinate frame definitions + +We define the following reference frames: + +#### Horizontal coordinate system +* Centred around the observer. We will use the convention: +* $x$ points South, $y$ to East and $z$ to the zenith. + +#### Mount frame (altaz) +* $y$ is defined as the axis of the azimuthal gimbal rotation. $z$ is the cross + product between the altitude and azimuthal gimbal axes and $x = y \times z$. +* For a perfect mount where $y$ points to the zenith and the gimbal axes are + orthogonal, $x$ is the altitude gimbal axis when in the *home position*. +* A perfect system in the *home position*, $x$ points West and $z$ points due + North and horizontal. +* Non-orthogonality between the axes are allowed by for now, we will assume the + orthogonal case for simplicity. + +#### Gimbal frame +* The mount frame rotated around the mount's azimuthal gimbal axes by + $\theta_{az}$ followed by a rotation around the mount's altitude axis by + $\theta_{alt}$. + +#### Scope frame (altaz) +* +z is boresight, +y is the vertical direction of the scope and +x is the + horizontal direction to the left when looking along the boresight. +* In the ideal case, the Scope frame is assumed to be the same as the Gimbal + frame. In reality, there may be errors due to mounting or gravity. + +#### Camera frame +* The camera frame describes the pointing of the PiFinder's camera. There will + be an offset between the camera and the scope. +* $+z$ is the boresight of the camera, $+y$ and $+x$ are respectively the + vertical and horizontal (to the left) directions of the camera. + +## Telescope coordinate transformations + +**TO EDIT...** + +We will use quaternions to rotate between the coordinate frames. For example, +the quaternion `q_horiz2mnt` rotates the Horizontal frame to the Mount frame. +The quaternions can be multiplied to apply successive intrinsic rotation from +the Horizontal frame to the Camera; + +```python +q_horiz2camera = q_horiz2mnt * q_mnt2gimb * q_gimb2scope * q_scope2camera +``` + +`q_mnt2gimb` depends on the gimbal angles, which is what we can control to move +the scope. + +## Coordinate frame transformation for altaz mounts + +During normal operation, we want to find the pointing of the scope, expressed +using $q_{hor2scope}$, which is the quaternion that rotates the scope axis in +the horizontal frame from the *home* position to the current pointing. + +### Plate solving + +Plate solving returns the pointing of the PiFinder camera in RA/Dec coordinates +which can be converted to the quaternion rotation $q_{hor2cam}$. Plate solving +also returns the roll but this is less accurate. For this reason, we will will +initially assume a perfect altaz mount and infer the roll from the geometry of +a perfect altaz mount at the given RA/Dec coordinates. + +The offset $q_{cam2scope}$ between the PiFinder camera frame and the scope +frame is determined during alignment of the PiFinder with the scope. Assuming +that this offset is constant, we can infer the pointing of the scope at time +step $k$: + +$$q_{hor2scope}(k) = q_{hor2cam}(k) \; q_{cam2scope}$$ + +We will use the PiFinder's camera frame as the reference because plate solving +is done relative to the camera frame. + +### Alignment + +As already mentioned, the alignment of the PiFinder determines $q_{cam2scope}$ +and we assume that this is fixed. + +During alignment, plate solving gives the RA/Dec of the the camera frame +pointing which can be used to estimate $q_{hor2cam}$ assuming a perfect altaz +mount. The roll measurement by the camera could be used to determine the +rotation of the camera frame around its $z_{cam}$ axis if the roll measurement +is accurate enough. Otherwise the roll will need to be inferred assuming that +the PiFinder is mounted upright. + +At the same time, the user selects the target seen by the scope, which gives +the RA/Dec of the scope pointing. We can use this to get a fix on +$q_{hor2scope}$ (assuming a perfect altaz mount); + +$$q_{hor2scope}(k) = q_{hor2cam}(k) \; q_{cam2scope}$$ + +Rearranging this gives, + +$$q_{cam2scope} = q_{hor2cam}^{-1}(k) \; q_{hor2scope}(k)$$ + +Note that for unit quaternions, we can also use the conjugate $q^*$ instead of +$q^{-1}$, which is slightly faster to compute. + +Some scopes and focusers can be rotated around its axis which also rotates the +PiFinder with it. This would currently require a re-alignment. + +### Dead-reckoning + +Between plate solving, the IMU extrapolates the scope orientation by dead +reckoning. Suppose that at the $k$ th time step, plate solves finds the camera +pointing, $q_{hor2cam}(k)$. It can be related to the IMU measurement by, + +$$q_{hor2cam}(k) = q_{hor2x}(k) \; q_{x2imu}(k) \; q_{imu2cam}$$ + +The IMU outputs its orientation $q_{x2imu}$ relative to a frame $X$ which is +similar to the horizontal frame but drifts over time; in particular, it will +drift rotating around the $z_{hor}$ axis because the IMU with just +accelerometer/gyro fusion has no means to determine the bearing. $q_{imu2cam}$ +rotates the IMU frame to the scope frame. It depends on the PiFinder type and +is assumed to be fixed and can be estimated during alignment. + +The drift $q_{hor2x}$ is unknown but it drifts slowly enough that we can assume +that it will be constant between successive plate solves. + +$$q_{hor2x}(k) = q_{hor2cam}(k) \; q_{imu2cam}^{-1} \; q_{x2imu}^{-1}(k)$$ + +In subsequent time steps, the drift, $q_{hor2x}(k)$, estimated in the last +plate solve can be used. At time step $k+l$ without plate solving, the the +camera pointing can be esimated by: + +$$\hat{q}_{hor2cam}(k+l) = q_{hor2x}(k) \; q_{x2imu}(k+l) \; q_{imu2cam}$$ + +Where $\hat{q}_{hor2cam}$ represents an estimate of the camera pointing using +dead-reckoning from the IMU. From this, we can make a dead-reckoning estimate +of the scope pointing; + +$$q_{hor2scope}(k + l) = \hat{q}_{hor2cam}(k + l) \; q_{cam2scope}$$ + + +### Notable features + +Because we use full 3D rotation and calibrate the IMU's unknown reference frame +every plate solve, we don't need to set the rotation between the camera and IMU +frame (in the old system, this was done by setting the PiFinder type). + +This approach will probably allow us to relax the requirement that the PiFinder +has to be upright. It should work even if it's mounted at an angle but this +hasn't been tested. + +## Approach for equatorial mounts + +It should be possible to take a similar approach for an equatorial mounts. + +One issue is that it's common to rotate EQ-mounteed scopes (particularly +Newtoninans) around its axis so that the eyepiece is at a comfortable position. +As mentioned in the alignment section, this would require a re-alignment. That +would need to be resolved in a future step. From 968e65f0fbf69cd721044c53eecdefb10f725ab1 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Wed, 25 Jun 2025 12:37:55 +0100 Subject: [PATCH 037/253] Add pointing_model.get_quat_angular_diff() --- .../PiFinder/pointing_model/pointing_model.py | 18 +++++++++++++++++- 1 file changed, 17 insertions(+), 1 deletion(-) diff --git a/python/PiFinder/pointing_model/pointing_model.py b/python/PiFinder/pointing_model/pointing_model.py index 7e47c5fe6..b8cdd77b1 100644 --- a/python/PiFinder/pointing_model/pointing_model.py +++ b/python/PiFinder/pointing_model/pointing_model.py @@ -50,4 +50,20 @@ def get_altaz_from_q_hor2scope(q_hor2scope): alt = np.pi / 2 - np.arccos(scope_axis.z) az = np.pi - np.arctan2(scope_axis.y, scope_axis.x) - return az, alt \ No newline at end of file + return az, alt + + +def get_quat_angular_diff(q1, q2): + """ + Calculates the relative rotation between quaternions `q1` and `q2`. + Accounts for the double-cover property of quaternions so that if q1 and q2 + are close, you get small angle d_theta rather than something around 2 * np.pi. + """ + dq = q1.conj() * q2 + d_theta = 2 * np.atan2(np.linalg.norm(dq.vec), dq.w) # atan2 is more robust than using acos + + # Account for double cover where q2 = -q1 gives d_theta = 2 * pi + if d_theta > np.pi: + d_theta = 2 * np.pi - d_theta + + return d_theta # In radians From 5ceb4649c5e3d1c92e1ad0d486a4641ad1428c88 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Wed, 25 Jun 2025 12:38:31 +0100 Subject: [PATCH 038/253] Use quaternion-based difference for deciding if the camera was still enough in camera_interface.py --- python/PiFinder/camera_interface.py | 15 ++++++++------- 1 file changed, 8 insertions(+), 7 deletions(-) diff --git a/python/PiFinder/camera_interface.py b/python/PiFinder/camera_interface.py index a0c5bd468..60da85bd0 100644 --- a/python/PiFinder/camera_interface.py +++ b/python/PiFinder/camera_interface.py @@ -14,6 +14,7 @@ import time from PIL import Image from PiFinder import state_utils, utils +from PiFinder.pointing_model import pointing_model from typing import Tuple import logging @@ -109,13 +110,13 @@ def get_image_loop( imu_end = shared_state.imu() # see if we moved during exposure - reading_diff = 0 + pointing_diff = 0 if imu_start and imu_end: - reading_diff = ( - abs(imu_start["pos"][0] - imu_end["pos"][0]) - + abs(imu_start["pos"][1] - imu_end["pos"][1]) - + abs(imu_start["pos"][2] - imu_end["pos"][2]) - ) + # Returns the pointing difference between successive IMU quaternions as + # an angle (radians). Note that this also accounts for rotation around the + # scope axis. + pointing_diff = pointing.get_quat_angular_diff( + imu_start["quat"], imu_end["quat"]) camera_image.paste(base_image) shared_state.set_last_image_metadata( @@ -123,7 +124,7 @@ def get_image_loop( "exposure_start": image_start_time, "exposure_end": image_end_time, "imu": imu_end, - "imu_delta": reading_diff, + "imu_delta": pointing_diff, # Angle in radians } ) From f7188796c40623c72936d4e4a0cef6dce69a08fd Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Wed, 25 Jun 2025 12:39:23 +0100 Subject: [PATCH 039/253] solver.py: Disable "imu_pos" --- python/PiFinder/solver.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/python/PiFinder/solver.py b/python/PiFinder/solver.py index 84129ef14..6b8976ca4 100644 --- a/python/PiFinder/solver.py +++ b/python/PiFinder/solver.py @@ -67,7 +67,7 @@ def solver( "RA": None, "Dec": None, "Roll": None, - "imu_pos": None, + #"imu_pos": None, "solve_time": None, "cam_solve_time": 0, } @@ -202,10 +202,10 @@ def solver( solved["RA"] = solved["RA_target"] solved["Dec"] = solved["Dec_target"] if last_image_metadata["imu"]: - solved["imu_pos"] = last_image_metadata["imu"]["pos"] + #solved["imu_pos"] = last_image_metadata["imu"]["pos"] solved["imu_quat"] = last_image_metadata["imu"]["quat"] else: - solved["imu_pos"] = None + #solved["imu_pos"] = None solved["imu_quat"] = None solved["solve_time"] = time.time() solved["cam_solve_time"] = solved["solve_time"] From d4f012f6ec7c985ae75e88e86a6347496daf4693 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Wed, 25 Jun 2025 12:50:51 +0100 Subject: [PATCH 040/253] camera_interface: Convert pointing_diff radians to degrees to be compatible with the threshold applied --- python/PiFinder/camera_interface.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/python/PiFinder/camera_interface.py b/python/PiFinder/camera_interface.py index 60da85bd0..1595d0e7f 100644 --- a/python/PiFinder/camera_interface.py +++ b/python/PiFinder/camera_interface.py @@ -110,11 +110,11 @@ def get_image_loop( imu_end = shared_state.imu() # see if we moved during exposure - pointing_diff = 0 + pointing_diff = 0.0 if imu_start and imu_end: # Returns the pointing difference between successive IMU quaternions as # an angle (radians). Note that this also accounts for rotation around the - # scope axis. + # scope axis. Returns an angle in radians. pointing_diff = pointing.get_quat_angular_diff( imu_start["quat"], imu_end["quat"]) @@ -124,7 +124,7 @@ def get_image_loop( "exposure_start": image_start_time, "exposure_end": image_end_time, "imu": imu_end, - "imu_delta": pointing_diff, # Angle in radians + "imu_delta": np.rad2deg(pointing_diff), } ) From d011b5b8a152fe142049f4a7a3ccb2ec1d900409 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Wed, 25 Jun 2025 13:06:09 +0100 Subject: [PATCH 041/253] Fix missing/incorrect import of pointing_model --- python/PiFinder/camera_interface.py | 6 ++++-- python/PiFinder/integrator.py | 2 +- 2 files changed, 5 insertions(+), 3 deletions(-) diff --git a/python/PiFinder/camera_interface.py b/python/PiFinder/camera_interface.py index 1595d0e7f..4c8c3f3e9 100644 --- a/python/PiFinder/camera_interface.py +++ b/python/PiFinder/camera_interface.py @@ -13,11 +13,13 @@ import queue import time from PIL import Image -from PiFinder import state_utils, utils -from PiFinder.pointing_model import pointing_model +import numpy as np from typing import Tuple import logging +from PiFinder import state_utils, utils +import PiFinder.pointing_model.pointing_model as pointing + logger = logging.getLogger("Camera.Interface") diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 8f030756b..3fcbab007 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -18,7 +18,7 @@ from PiFinder import state_utils import PiFinder.calc_utils as calc_utils from PiFinder.multiproclogging import MultiprocLogging -from PiFinder.pointing_model import pointing_model +import PiFinder.pointing_model.pointing_model as pointing #IMU_ALT = 2 #IMU_AZ = 0 From 3e9e0d2770e2956fb764043dec213859524db954 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Wed, 25 Jun 2025 13:06:58 +0100 Subject: [PATCH 042/253] pointing_model: Fix np.arctan2 in this version rather than np.atan2 --- python/PiFinder/pointing_model/pointing_model.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/python/PiFinder/pointing_model/pointing_model.py b/python/PiFinder/pointing_model/pointing_model.py index b8cdd77b1..740bca633 100644 --- a/python/PiFinder/pointing_model/pointing_model.py +++ b/python/PiFinder/pointing_model/pointing_model.py @@ -60,7 +60,7 @@ def get_quat_angular_diff(q1, q2): are close, you get small angle d_theta rather than something around 2 * np.pi. """ dq = q1.conj() * q2 - d_theta = 2 * np.atan2(np.linalg.norm(dq.vec), dq.w) # atan2 is more robust than using acos + d_theta = 2 * np.arctan2(np.linalg.norm(dq.vec), dq.w) # atan2 is more robust than using acos # Account for double cover where q2 = -q1 gives d_theta = 2 * pi if d_theta > np.pi: From b45056f4b9b45260485d7d6f95951e22dc42df72 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Wed, 25 Jun 2025 13:16:27 +0100 Subject: [PATCH 043/253] Define max_imu_ang_during_exposure in solver.py; a threshold for last_image_metadata["imu_delta"] --- python/PiFinder/solver.py | 3 ++- python/PiFinder/state.py | 2 +- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/python/PiFinder/solver.py b/python/PiFinder/solver.py index 6b8976ca4..c3309c53b 100644 --- a/python/PiFinder/solver.py +++ b/python/PiFinder/solver.py @@ -37,6 +37,7 @@ def solver( align_command_queue, align_result_queue, is_debug=False, + max_imu_ang_during_exposure=1.0, # Max allowed turn during exp [degrees] ): MultiprocLogging.configurer(log_queue) logger.debug("Starting Solver") @@ -128,7 +129,7 @@ def solver( logger.error(f"Lost connection to shared state manager: {e}") if ( last_image_metadata["exposure_end"] > (last_solve_time) - and last_image_metadata["imu_delta"] < 1 + and last_image_metadata["imu_delta"] < max_imu_ang_during_exposure ): img = camera_image.copy() img = img.convert(mode="L") diff --git a/python/PiFinder/state.py b/python/PiFinder/state.py index 535c8f02f..6dbbe7657 100644 --- a/python/PiFinder/state.py +++ b/python/PiFinder/state.py @@ -209,7 +209,7 @@ def __init__(self): "exposure_start": 0, "exposure_end": 0, "imu": None, - "imu_delta": 0, + "imu_delta": 0.0, # Angle between quaternion at start and end of exposure } self.__solution = None self.__sats = None From 877361e990dfb7eb8e168aa7657a073f858c9e71 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Wed, 25 Jun 2025 22:10:16 +0100 Subject: [PATCH 044/253] Temporarily disable printing IMU quaternions to status.py --- python/PiFinder/ui/status.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/python/PiFinder/ui/status.py b/python/PiFinder/ui/status.py index fa562be3b..0dde8bcab 100644 --- a/python/PiFinder/ui/status.py +++ b/python/PiFinder/ui/status.py @@ -264,7 +264,8 @@ def update_status_dict(self): mtext = "Static" self.status_dict["IMU"] = f"{mtext : >11}" + " " + str(imu["status"]) self.status_dict["IMU PS"] = ( - f"{imu['quat'][0] : >6.1f}/{imu['quat'][2] : >6.1f}" # TODO: Quick hack for now. This was changed from imu["pos"] and should be changed. + "imu NA" + #f"{imu['quat'][0] : >6.1f}/{imu['quat'][2] : >6.1f}" # TODO: Quick hack for now. This was changed from imu["pos"] and should be changed. ) location = self.shared_state.location() sats = self.shared_state.sats() From ebfa0232e97db59340320479e1da096a24792488 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Thu, 26 Jun 2025 18:40:10 +0100 Subject: [PATCH 045/253] Restored the old IMU code blocks --> Camera now works in Focus mode --- python/PiFinder/camera_interface.py | 17 +++++++++----- python/PiFinder/imu_pi.py | 35 ++++++++++++++++++++--------- python/PiFinder/integrator.py | 21 ++++++++++------- python/PiFinder/solver.py | 6 ++--- 4 files changed, 52 insertions(+), 27 deletions(-) diff --git a/python/PiFinder/camera_interface.py b/python/PiFinder/camera_interface.py index 4c8c3f3e9..db02287c6 100644 --- a/python/PiFinder/camera_interface.py +++ b/python/PiFinder/camera_interface.py @@ -114,11 +114,18 @@ def get_image_loop( # see if we moved during exposure pointing_diff = 0.0 if imu_start and imu_end: - # Returns the pointing difference between successive IMU quaternions as - # an angle (radians). Note that this also accounts for rotation around the - # scope axis. Returns an angle in radians. - pointing_diff = pointing.get_quat_angular_diff( - imu_start["quat"], imu_end["quat"]) + pointing_diff = ( + abs(imu_start["pos"][0] - imu_end["pos"][0]) + + abs(imu_start["pos"][1] - imu_end["pos"][1]) + + abs(imu_start["pos"][2] - imu_end["pos"][2]) + ) + # # Quaternion version + # if imu_start and imu_end: + # # Returns the pointing difference between successive IMU quaternions as + # # an angle (radians). Note that this also accounts for rotation around the + # # scope axis. Returns an angle in radians. + # pointing_diff = pointing.get_quat_angular_diff( + # imu_start["quat"], imu_end["quat"]) camera_image.paste(base_image) shared_state.set_last_image_metadata( diff --git a/python/PiFinder/imu_pi.py b/python/PiFinder/imu_pi.py index 58478db34..12683571d 100644 --- a/python/PiFinder/imu_pi.py +++ b/python/PiFinder/imu_pi.py @@ -12,7 +12,7 @@ import logging import numpy as np import quaternion # Numpy quaternion -#from scipy.spatial.transform import Rotation +from scipy.spatial.transform import Rotation from PiFinder import config @@ -30,7 +30,7 @@ def __init__(self): self.sensor.mode = adafruit_bno055.IMUPLUS_MODE # self.sensor.mode = adafruit_bno055.NDOF_MODE cfg = config.Config() - """ Disable rotating the IMU axes. Use its native form + #""" Disable rotating the IMU axes. Use its native form if ( cfg.get_option("screen_direction") == "flat" or cfg.get_option("screen_direction") == "straight" @@ -62,11 +62,11 @@ def __init__(self): adafruit_bno055.AXIS_REMAP_POSITIVE, adafruit_bno055.AXIS_REMAP_POSITIVE, ) - """ + #""" self.quat_history = [(0, 0, 0, 0)] * QUEUE_LEN self._flip_count = 0 self.calibration = 0 - self.avg_quat = None # Data type: np.quaternion(w, x, y, z) + self.avg_quat = (0, 0, 0, 0) # Data type: np.quaternion(w, x, y, z) self.__moving = False self.last_sample_time = time.time() @@ -79,6 +79,16 @@ def __init__(self): # to stop moving. self.__moving_threshold = (0.0005, 0.0003) + def quat_to_euler(self, quat): + if quat[0] + quat[1] + quat[2] + quat[3] == 0: + return 0, 0, 0 + rot = Rotation.from_quat(quat) + rot_euler = rot.as_euler("xyz", degrees=True) + # convert from -180/180 to 0/360 + rot_euler[0] += 180 + rot_euler[1] += 180 + rot_euler[2] += 180 + return rot_euler def moving(self): """ @@ -138,7 +148,7 @@ def update(self): # no flip self._flip_count = 0 - self.avg_quat = np.quaternion(quat[0], quat[1], quat[2], quat[3]) + self.avg_quat = quat #np.quaternion(quat[0], quat[1], quat[2], quat[3]) if len(self.quat_history) == QUEUE_LEN: self.quat_history = self.quat_history[1:] self.quat_history.append(quat) @@ -150,6 +160,9 @@ def update(self): if self.__reading_diff > self.__moving_threshold[0]: self.__moving = True + def get_euler(self): + return list(self.quat_to_euler(self.avg_quat)) + def __str__(self): return ( f"IMU Information:\n" @@ -173,9 +186,9 @@ def imu_monitor(shared_state, console_queue, log_queue): "moving": False, "move_start": None, "move_end": None, - #"pos": [0, 0, 0], # Corresponds to [Az, related_to_roll, Alt] --> **TO REMOVE LATER - "quat": None, # Scalar-first np.quaternion(w, x, y, z) - Init to invalid quaternion - #"start_pos": [0, 0, 0], + "pos": [0, 0, 0], # Corresponds to [Az, related_to_roll, Alt] --> **TO REMOVE LATER + "quat": [0, 0, 0, 0], # Scalar-first np.quaternion(w, x, y, z) - Init to invalid quaternion + "start_pos": [0, 0, 0], "status": 0, } @@ -186,9 +199,9 @@ def imu_monitor(shared_state, console_queue, log_queue): if not imu_data["moving"]: logger.debug("IMU: move start") imu_data["moving"] = True - #imu_data["start_pos"] = imu_data["pos"] + imu_data["start_pos"] = imu_data["pos"] imu_data["move_start"] = time.time() - #imu_data["pos"] = None # Remove this later. Was used to store Euler angles + imu_data["pos"] = imu.get_euler() # Remove this later. Was used to store Euler angles imu_data["quat"] = imu.avg_quat else: @@ -196,7 +209,7 @@ def imu_monitor(shared_state, console_queue, log_queue): # If we were moving and we now stopped logger.debug("IMU: move end") imu_data["moving"] = False - #imu_data["pos"] = None + imu_data["pos"] = imu.get_euler() imu_data["quat"] = imu.avg_quat imu_data["move_end"] = time.time() diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 3fcbab007..6d12a6d00 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -20,8 +20,8 @@ from PiFinder.multiproclogging import MultiprocLogging import PiFinder.pointing_model.pointing_model as pointing -#IMU_ALT = 2 -#IMU_AZ = 0 +IMU_ALT = 2 +IMU_AZ = 0 logger = logging.getLogger("IMU.Integrator") @@ -75,7 +75,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa "q_hor2x": None, }, "Roll_offset": 0, # May/may not be needed - for experimentation - #"imu_pos": None, + "imu_pos": None, "imu_quat": None, # IMU quaternion as numpy quaternion (scalar-first) - TODO: Move to "imu" "Alt": None, # Alt of scope "Az": None, @@ -85,7 +85,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa "constellation": None, } cfg = config.Config() - """ Disable dependence of IMU on PiFinder type + #""" Disable dependence of IMU on PiFinder type if ( cfg.get_option("screen_direction") == "left" or cfg.get_option("screen_direction") == "flat" @@ -95,7 +95,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa flip_alt_offset = True else: flip_alt_offset = False - """ + #""" # This holds the last image solve position info # so we can delta for IMU updates @@ -198,6 +198,10 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa if last_image_solve and last_image_solve["Alt"]: # If we have alt, then we have a position/time + # calc new alt/az - OLD method + lis_imu = last_image_solve["imu_pos"] + imu_pos = imu["pos"] + # calc new alt/az #lis_imu = last_image_solve["imu_pos"] lis_imu_quat = last_image_solve["imu_quat"] @@ -206,7 +210,8 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa q_x2imu = imu["quat"] #imu_pos = imu["pos"] - if imu_moved(lis_imu_quat, q_x2imu): + if imu_moved(lis_imu, imu_pos): + #if imu_moved(lis_imu_quat, q_x2imu): # Estimate camera pointing using IMU dead-reckoning q_hor2x = last_image_solve["imu"]["q_hor2x"] q_imu2cam = np.quaternion(1, 0, 0, 0) # Identity so this could be removed later (TODO) @@ -225,7 +230,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa #q_hor2scope = q_hor2cam * q_cam2scope - """ DISABLE - Use quaternions + #""" DISABLE - Use quaternions alt_offset = imu_pos[IMU_ALT] - lis_imu[IMU_ALT] if flip_alt_offset: alt_offset = ((alt_offset + 180) % 360 - 180) * -1 @@ -242,7 +247,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa solved["camera_center"]["Az"] = ( last_image_solve["camera_center"]["Az"] + az_offset ) % 360 - """ + #""" # N.B. Assumes that location hasn't changed since last solve # Turn this into RA/DEC diff --git a/python/PiFinder/solver.py b/python/PiFinder/solver.py index c3309c53b..4d9d78a67 100644 --- a/python/PiFinder/solver.py +++ b/python/PiFinder/solver.py @@ -68,7 +68,7 @@ def solver( "RA": None, "Dec": None, "Roll": None, - #"imu_pos": None, + "imu_pos": None, "solve_time": None, "cam_solve_time": 0, } @@ -203,10 +203,10 @@ def solver( solved["RA"] = solved["RA_target"] solved["Dec"] = solved["Dec_target"] if last_image_metadata["imu"]: - #solved["imu_pos"] = last_image_metadata["imu"]["pos"] + solved["imu_pos"] = last_image_metadata["imu"]["pos"] solved["imu_quat"] = last_image_metadata["imu"]["quat"] else: - #solved["imu_pos"] = None + solved["imu_pos"] = None solved["imu_quat"] = None solved["solve_time"] = time.time() solved["cam_solve_time"] = solved["solve_time"] From 54618e71447b698542b4a51bd29753b2dc8163b4 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Thu, 26 Jun 2025 20:16:15 +0100 Subject: [PATCH 046/253] camera_interface.py: Reverted to pointing_diff calculation using quaternion -- works --- python/PiFinder/camera_interface.py | 28 ++++++++++++++++------------ 1 file changed, 16 insertions(+), 12 deletions(-) diff --git a/python/PiFinder/camera_interface.py b/python/PiFinder/camera_interface.py index db02287c6..737742792 100644 --- a/python/PiFinder/camera_interface.py +++ b/python/PiFinder/camera_interface.py @@ -14,6 +14,7 @@ import time from PIL import Image import numpy as np +import quaternion # Numpy quaternion from typing import Tuple import logging @@ -113,19 +114,22 @@ def get_image_loop( # see if we moved during exposure pointing_diff = 0.0 - if imu_start and imu_end: - pointing_diff = ( - abs(imu_start["pos"][0] - imu_end["pos"][0]) - + abs(imu_start["pos"][1] - imu_end["pos"][1]) - + abs(imu_start["pos"][2] - imu_end["pos"][2]) - ) + + # TODO: REMOVE + #if imu_start and imu_end: + # pointing_diff = ( + # abs(imu_start["pos"][0] - imu_end["pos"][0]) + # + abs(imu_start["pos"][1] - imu_end["pos"][1]) + # + abs(imu_start["pos"][2] - imu_end["pos"][2]) + # ) + # # Quaternion version - # if imu_start and imu_end: - # # Returns the pointing difference between successive IMU quaternions as - # # an angle (radians). Note that this also accounts for rotation around the - # # scope axis. Returns an angle in radians. - # pointing_diff = pointing.get_quat_angular_diff( - # imu_start["quat"], imu_end["quat"]) + if imu_start and imu_end: + # Returns the pointing difference between successive IMU quaternions as + # an angle (radians). Note that this also accounts for rotation around the + # scope axis. Returns an angle in radians. + pointing_diff = pointing.get_quat_angular_diff( + quaternion.from_float_array(imu_start["quat"]), quaternion.from_float_array(imu_end["quat"])) camera_image.paste(base_image) shared_state.set_last_image_metadata( From 51cf7577e014922e215cfd16e2539311006eebdc Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Thu, 26 Jun 2025 22:29:00 +0100 Subject: [PATCH 047/253] Store quaternion measurements as np.quaternion type in state --> Camera works in focus mode --- python/PiFinder/camera_interface.py | 2 +- python/PiFinder/imu_pi.py | 22 ++++++++++++++-------- 2 files changed, 15 insertions(+), 9 deletions(-) diff --git a/python/PiFinder/camera_interface.py b/python/PiFinder/camera_interface.py index 737742792..a0fcfe3b1 100644 --- a/python/PiFinder/camera_interface.py +++ b/python/PiFinder/camera_interface.py @@ -129,7 +129,7 @@ def get_image_loop( # an angle (radians). Note that this also accounts for rotation around the # scope axis. Returns an angle in radians. pointing_diff = pointing.get_quat_angular_diff( - quaternion.from_float_array(imu_start["quat"]), quaternion.from_float_array(imu_end["quat"])) + imu_start["quat"], imu_end["quat"]) camera_image.paste(base_image) shared_state.set_last_image_metadata( diff --git a/python/PiFinder/imu_pi.py b/python/PiFinder/imu_pi.py index 12683571d..65069795f 100644 --- a/python/PiFinder/imu_pi.py +++ b/python/PiFinder/imu_pi.py @@ -19,7 +19,7 @@ logger = logging.getLogger("IMU.pi") QUEUE_LEN = 10 -MOVE_CHECK_LEN = 2 +MOVE_CHECK_LEN = 2 # TODO: Doesn't seem to be used? class Imu: @@ -66,7 +66,7 @@ def __init__(self): self.quat_history = [(0, 0, 0, 0)] * QUEUE_LEN self._flip_count = 0 self.calibration = 0 - self.avg_quat = (0, 0, 0, 0) # Data type: np.quaternion(w, x, y, z) + self.avg_quat = (0, 0, 0, 0) # Scalar-first quaternion: (w, x, y, z) self.__moving = False self.last_sample_time = time.time() @@ -132,6 +132,9 @@ def update(self): # Sometimes the quat output will 'flip' and change by 2.0+ # from one reading to another. This is clearly noise or an # artifact, so filter them out + # + # NOTE: This is probably due to the double-cover property of quaternions + # where +q and -q describe the same rotation? if self.__reading_diff > 1.5: self._flip_count += 1 if self._flip_count > 10: @@ -148,7 +151,9 @@ def update(self): # no flip self._flip_count = 0 - self.avg_quat = quat #np.quaternion(quat[0], quat[1], quat[2], quat[3]) + # avg_quat is the latest quaternion measurement, not the average + self.avg_quat = quat + # Write over the quat_hisotry queue FIFO: if len(self.quat_history) == QUEUE_LEN: self.quat_history = self.quat_history[1:] self.quat_history.append(quat) @@ -195,23 +200,24 @@ def imu_monitor(shared_state, console_queue, log_queue): while True: imu.update() imu_data["status"] = imu.calibration + + # TODO: move_start and move_end don't seem to be used? if imu.moving(): if not imu_data["moving"]: logger.debug("IMU: move start") imu_data["moving"] = True imu_data["start_pos"] = imu_data["pos"] imu_data["move_start"] = time.time() - imu_data["pos"] = imu.get_euler() # Remove this later. Was used to store Euler angles - imu_data["quat"] = imu.avg_quat - + imu_data["pos"] = imu.get_euler() # TODO: Remove this later. Was used to store Euler angles + imu_data["quat"] = quaternion.from_float_array(imu.avg_quat) # Scalar-first (w, x, y, z) else: if imu_data["moving"]: # If we were moving and we now stopped logger.debug("IMU: move end") imu_data["moving"] = False - imu_data["pos"] = imu.get_euler() - imu_data["quat"] = imu.avg_quat imu_data["move_end"] = time.time() + imu_data["pos"] = imu.get_euler() + imu_data["quat"] = quaternion.from_float_array(imu.avg_quat) # Scalar-first (w, x, y, z) if not imu_calibrated: if imu_data["status"] == 3: From c753be1835eab80d94bffabe83e052efdaa0188a Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Thu, 26 Jun 2025 23:03:10 +0100 Subject: [PATCH 048/253] Shared state: imu["quat"] stores numpy.quaternion --> Camera runs in focus mode --- python/PiFinder/imu_pi.py | 3 ++- python/PiFinder/integrator.py | 2 +- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/python/PiFinder/imu_pi.py b/python/PiFinder/imu_pi.py index 65069795f..1cb48ffa0 100644 --- a/python/PiFinder/imu_pi.py +++ b/python/PiFinder/imu_pi.py @@ -187,12 +187,13 @@ def imu_monitor(shared_state, console_queue, log_queue): MultiprocLogging.configurer(log_queue) imu = Imu() imu_calibrated = False + # TODO: Remove start_pos, move_start, move_end imu_data = { "moving": False, "move_start": None, "move_end": None, "pos": [0, 0, 0], # Corresponds to [Az, related_to_roll, Alt] --> **TO REMOVE LATER - "quat": [0, 0, 0, 0], # Scalar-first np.quaternion(w, x, y, z) - Init to invalid quaternion + "quat": np.quaternion(0, 0, 0, 0), # Scalar-first numpy quaternion(w, x, y, z) - Init to invalid quaternion "start_pos": [0, 0, 0], "status": 0, } diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 6d12a6d00..dd05cd116 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -207,8 +207,8 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa lis_imu_quat = last_image_solve["imu_quat"] # Get latest IMU meas: quaternion rot. of IMU rel. to some frame X + assert isinstance(imu["quat"] , quaternion.quaternion), "Expecting quaternion.quaternion type" # TODO: Remove later q_x2imu = imu["quat"] - #imu_pos = imu["pos"] if imu_moved(lis_imu, imu_pos): #if imu_moved(lis_imu_quat, q_x2imu): From 30112691cc5f08d3aa72a43adacf081546e9d8df Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Fri, 27 Jun 2025 21:50:30 +0100 Subject: [PATCH 049/253] integrator.py: Use quaternion ang. diff to switch to IMU tracking in the integrator loop --- python/PiFinder/integrator.py | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index dd05cd116..6468687a4 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -26,6 +26,7 @@ logger = logging.getLogger("IMU.Integrator") +# TODO: Remove this after migrating to quaternion def imu_moved(imu_a, imu_b): """ Compares two IMU states to determine if they are the 'same' @@ -96,6 +97,8 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa else: flip_alt_offset = False #""" + + imu_moved_ang_threshold = np.deg2rad(0.01) # Use IMU tracking if the angle moved is above this # This holds the last image solve position info # so we can delta for IMU updates @@ -203,15 +206,15 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa imu_pos = imu["pos"] # calc new alt/az - #lis_imu = last_image_solve["imu_pos"] lis_imu_quat = last_image_solve["imu_quat"] # Get latest IMU meas: quaternion rot. of IMU rel. to some frame X assert isinstance(imu["quat"] , quaternion.quaternion), "Expecting quaternion.quaternion type" # TODO: Remove later q_x2imu = imu["quat"] - if imu_moved(lis_imu, imu_pos): - #if imu_moved(lis_imu_quat, q_x2imu): + # When moving, switch to tracking using the IMU + #if imu_moved(lis_imu, imu_pos): + if get_quat_angular_diff((lis_imu_quat, q_x2imu)) > imu_moved_ang_threshold: # Estimate camera pointing using IMU dead-reckoning q_hor2x = last_image_solve["imu"]["q_hor2x"] q_imu2cam = np.quaternion(1, 0, 0, 0) # Identity so this could be removed later (TODO) From 12cb497772ccdfcbe514b1d5cd3570cdc94094ca Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Fri, 27 Jun 2025 21:57:25 +0100 Subject: [PATCH 050/253] integrator.py: Refactor --- python/PiFinder/integrator.py | 17 ++++++----------- 1 file changed, 6 insertions(+), 11 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 6468687a4..3d0ae0210 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -201,21 +201,13 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa if last_image_solve and last_image_solve["Alt"]: # If we have alt, then we have a position/time - # calc new alt/az - OLD method - lis_imu = last_image_solve["imu_pos"] - imu_pos = imu["pos"] - # calc new alt/az - lis_imu_quat = last_image_solve["imu_quat"] - - # Get latest IMU meas: quaternion rot. of IMU rel. to some frame X - assert isinstance(imu["quat"] , quaternion.quaternion), "Expecting quaternion.quaternion type" # TODO: Remove later - q_x2imu = imu["quat"] - # When moving, switch to tracking using the IMU #if imu_moved(lis_imu, imu_pos): - if get_quat_angular_diff((lis_imu_quat, q_x2imu)) > imu_moved_ang_threshold: + assert isinstance(imu["quat"] , quaternion.quaternion), "Expecting quaternion.quaternion type" # TODO: Remove later + if get_quat_angular_diff((last_image_solve["imu_quat"], imu["quat"])) > imu_moved_ang_threshold: # Estimate camera pointing using IMU dead-reckoning + q_x2imu = imu["quat"] # Latest IMU meas: quaternion rot. of IMU rel. to some frame X q_hor2x = last_image_solve["imu"]["q_hor2x"] q_imu2cam = np.quaternion(1, 0, 0, 0) # Identity so this could be removed later (TODO) q_hor2cam = q_hor2x * q_x2imu * q_imu2cam @@ -234,6 +226,9 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa #""" DISABLE - Use quaternions + # calc new alt/az - OLD method + lis_imu = last_image_solve["imu_pos"] + imu_pos = imu["pos"] alt_offset = imu_pos[IMU_ALT] - lis_imu[IMU_ALT] if flip_alt_offset: alt_offset = ((alt_offset + 180) % 360 - 180) * -1 From 95c0e82e52723badc995b2a607145757c9db2ca9 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Fri, 27 Jun 2025 22:04:44 +0100 Subject: [PATCH 051/253] integrator.py: Disable old calculation of Altaz --- python/PiFinder/integrator.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 3d0ae0210..4c2f12ac0 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -225,7 +225,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa #q_hor2scope = q_hor2cam * q_cam2scope - #""" DISABLE - Use quaternions + """ DISABLE - Use quaternions # calc new alt/az - OLD method lis_imu = last_image_solve["imu_pos"] imu_pos = imu["pos"] @@ -245,7 +245,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa solved["camera_center"]["Az"] = ( last_image_solve["camera_center"]["Az"] + az_offset ) % 360 - #""" + """ # N.B. Assumes that location hasn't changed since last solve # Turn this into RA/DEC From 91eab69158c50297955ed2d45f8bca7ee77fe35c Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Fri, 27 Jun 2025 22:05:02 +0100 Subject: [PATCH 052/253] Add comments --- python/PiFinder/camera_interface.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/python/PiFinder/camera_interface.py b/python/PiFinder/camera_interface.py index a0fcfe3b1..c9c973eea 100644 --- a/python/PiFinder/camera_interface.py +++ b/python/PiFinder/camera_interface.py @@ -137,7 +137,7 @@ def get_image_loop( "exposure_start": image_start_time, "exposure_end": image_end_time, "imu": imu_end, - "imu_delta": np.rad2deg(pointing_diff), + "imu_delta": np.rad2deg(pointing_diff), # TODO: Rename this } ) From b9572094a46767d6aa7b97a26691752de0cac72a Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Fri, 27 Jun 2025 23:57:03 +0100 Subject: [PATCH 053/253] Need to change dictionary solve in both integrator.py and solver.py --> Now plate solves but chart doesn't move when PiFinder moved --- python/PiFinder/integrator.py | 4 ++-- python/PiFinder/solver.py | 4 ++++ 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 4c2f12ac0..129a639f1 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -48,7 +48,7 @@ def imu_moved(imu_a, imu_b): return False -def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=False): +def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=True): # TODO: Change back is_debug=False MultiprocLogging.configurer(log_queue) try: if is_debug: @@ -198,7 +198,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa imu = shared_state.imu() if imu: dt = shared_state.datetime() - if last_image_solve and last_image_solve["Alt"]: + if last_image_solve and last_image_solve["Alt"] and last_image_solve["imu"]["q_hor2x"]: # If we have alt, then we have a position/time # calc new alt/az diff --git a/python/PiFinder/solver.py b/python/PiFinder/solver.py index 4d9d78a67..eeb2af304 100644 --- a/python/PiFinder/solver.py +++ b/python/PiFinder/solver.py @@ -47,6 +47,7 @@ def solver( last_solve_time = 0 align_ra = 0 align_dec = 0 + # TODO: This dictionary is duplicated in integrator.py. Need to rationalize? solved = { # RA, Dec, Roll solved at the center of the camera FoV # update by integrator @@ -64,6 +65,9 @@ def solver( "Dec": None, "Roll": None, }, + "imu": { + "q_hor2x": None, + }, # RA, Dec, Roll at the target pixel "RA": None, "Dec": None, From 5917e7947d8ed812cf7340a342ef672e770fff48 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 28 Jun 2025 00:30:26 +0100 Subject: [PATCH 054/253] Fix at scope: Missing name space pointing. --- python/PiFinder/integrator.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 129a639f1..f742bdb01 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -182,6 +182,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr cam2scope_offset_az = solved["Az"] - solved["camera_center"]["Az"] cam2scope_offset_alt = solved["Alt"] - solved["camera_center"]["Alt"] # TODO: Do something similar for EQ mounts here + logger.debug("Coordinates stored from plate solve.") last_image_solve = copy.deepcopy(solved) solved["solve_source"] = "CAM" @@ -205,7 +206,9 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr # When moving, switch to tracking using the IMU #if imu_moved(lis_imu, imu_pos): assert isinstance(imu["quat"] , quaternion.quaternion), "Expecting quaternion.quaternion type" # TODO: Remove later - if get_quat_angular_diff((last_image_solve["imu_quat"], imu["quat"])) > imu_moved_ang_threshold: + angle_moved = pointing.get_quat_angular_diff(last_image_solve["imu_quat"], imu["quat"]) + logger.debug("Track using IMU. Angle moved = {:}".format(np.rad2deg(angle_moved))) + if angle_moved > imu_moved_ang_threshold: # Estimate camera pointing using IMU dead-reckoning q_x2imu = imu["quat"] # Latest IMU meas: quaternion rot. of IMU rel. to some frame X q_hor2x = last_image_solve["imu"]["q_hor2x"] From a01bb0a77cb6b2d28d1ac821405fa2ec39fe4dc6 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 28 Jun 2025 00:30:43 +0100 Subject: [PATCH 055/253] Edit comment --- python/PiFinder/state.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/python/PiFinder/state.py b/python/PiFinder/state.py index 6dbbe7657..ea75ffba0 100644 --- a/python/PiFinder/state.py +++ b/python/PiFinder/state.py @@ -209,7 +209,7 @@ def __init__(self): "exposure_start": 0, "exposure_end": 0, "imu": None, - "imu_delta": 0.0, # Angle between quaternion at start and end of exposure + "imu_delta": 0.0, # Angle between quaternion at start and end of exposure [deg] } self.__solution = None self.__sats = None From 9b9ddf8f92dfd8e2eb31a9fe0cf015ebf76e0c99 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 28 Jun 2025 00:31:52 +0100 Subject: [PATCH 056/253] Fix at scope: Typo --- python/PiFinder/integrator.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index f742bdb01..fe04c1ade 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -214,7 +214,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr q_hor2x = last_image_solve["imu"]["q_hor2x"] q_imu2cam = np.quaternion(1, 0, 0, 0) # Identity so this could be removed later (TODO) q_hor2cam = q_hor2x * q_x2imu * q_imu2cam - q_hor2cam = q_hor2com.normalized() + q_hor2cam = q_hor2cam.normalized() # Store estimate: az_rad, alt_rad = pointing.get_altaz_from_q_hor2scope(q_hor2cam) solved["camera_center"]["Az"] = np.rad2deg(az_rad) From d04d17b25bb62c5b5a1fbe7550495fe4df1cf7c5 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 28 Jun 2025 00:42:24 +0100 Subject: [PATCH 057/253] Debug at scope: Increased threshold for using IMU tracking to 0.1 deg. Smoother. BUT IMU tracking is L/R and Up/Down reversed!? --- python/PiFinder/integrator.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index fe04c1ade..aced063a4 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -98,7 +98,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr flip_alt_offset = False #""" - imu_moved_ang_threshold = np.deg2rad(0.01) # Use IMU tracking if the angle moved is above this + imu_moved_ang_threshold = np.deg2rad(0.1) # Use IMU tracking if the angle moved is above this # This holds the last image solve position info # so we can delta for IMU updates From 8fd5ef1e8bbb1cb1706d453afbc09e721f9a8d79 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 28 Jun 2025 00:54:41 +0100 Subject: [PATCH 058/253] imu_pi.py: Disable BNO055 config to rotate the IMU data --- python/PiFinder/imu_pi.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/python/PiFinder/imu_pi.py b/python/PiFinder/imu_pi.py index 1cb48ffa0..0c5b8f752 100644 --- a/python/PiFinder/imu_pi.py +++ b/python/PiFinder/imu_pi.py @@ -30,7 +30,7 @@ def __init__(self): self.sensor.mode = adafruit_bno055.IMUPLUS_MODE # self.sensor.mode = adafruit_bno055.NDOF_MODE cfg = config.Config() - #""" Disable rotating the IMU axes. Use its native form + """ Disable rotating the IMU axes. Use its native form if ( cfg.get_option("screen_direction") == "flat" or cfg.get_option("screen_direction") == "straight" @@ -62,7 +62,7 @@ def __init__(self): adafruit_bno055.AXIS_REMAP_POSITIVE, adafruit_bno055.AXIS_REMAP_POSITIVE, ) - #""" + """ self.quat_history = [(0, 0, 0, 0)] * QUEUE_LEN self._flip_count = 0 self.calibration = 0 From f7e194bf52563df5e0536cedd2401e86f1c77322 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 28 Jun 2025 01:36:39 +0100 Subject: [PATCH 059/253] Disable using the old method to calculate Euler angles (imu["pos"]) --- python/PiFinder/imu_pi.py | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/python/PiFinder/imu_pi.py b/python/PiFinder/imu_pi.py index 0c5b8f752..4065ebbf5 100644 --- a/python/PiFinder/imu_pi.py +++ b/python/PiFinder/imu_pi.py @@ -209,7 +209,8 @@ def imu_monitor(shared_state, console_queue, log_queue): imu_data["moving"] = True imu_data["start_pos"] = imu_data["pos"] imu_data["move_start"] = time.time() - imu_data["pos"] = imu.get_euler() # TODO: Remove this later. Was used to store Euler angles + # DISABLE old method + #imu_data["pos"] = imu.get_euler() # TODO: Remove this later. Was used to store Euler angles imu_data["quat"] = quaternion.from_float_array(imu.avg_quat) # Scalar-first (w, x, y, z) else: if imu_data["moving"]: @@ -217,7 +218,8 @@ def imu_monitor(shared_state, console_queue, log_queue): logger.debug("IMU: move end") imu_data["moving"] = False imu_data["move_end"] = time.time() - imu_data["pos"] = imu.get_euler() + # DISABLE old method + #imu_data["pos"] = imu.get_euler() imu_data["quat"] = quaternion.from_float_array(imu.avg_quat) # Scalar-first (w, x, y, z) if not imu_calibrated: From 5b9441cca70b385f3cf3230bdd0823fe07683288 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 28 Jun 2025 01:37:04 +0100 Subject: [PATCH 060/253] Update comments --- python/PiFinder/integrator.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index aced063a4..c8b177aaf 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -210,7 +210,8 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr logger.debug("Track using IMU. Angle moved = {:}".format(np.rad2deg(angle_moved))) if angle_moved > imu_moved_ang_threshold: # Estimate camera pointing using IMU dead-reckoning - q_x2imu = imu["quat"] # Latest IMU meas: quaternion rot. of IMU rel. to some frame X + q_x2imu = imu["quat"] # Latest IMU meas: quaternion rot. of IMU rel. to some frame X + #q_x2imu = np.quaternion(q_x2imu.w, -q_x2imu.x, -q_x2imu.y, -q_x2imu.z) # HACK: Reverse the angle part of quaternion q_hor2x = last_image_solve["imu"]["q_hor2x"] q_imu2cam = np.quaternion(1, 0, 0, 0) # Identity so this could be removed later (TODO) q_hor2cam = q_hor2x * q_x2imu * q_imu2cam From 752d3b1c53bd6a77b541c49018f5809f67fc5dfe Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 28 Jun 2025 18:34:24 +0100 Subject: [PATCH 061/253] Remove debug logging that was added that was dumping too much to the log file. --- python/PiFinder/integrator.py | 23 ++++++++++++----------- 1 file changed, 12 insertions(+), 11 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index c8b177aaf..12a0a38ce 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -182,20 +182,19 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr cam2scope_offset_az = solved["Az"] - solved["camera_center"]["Az"] cam2scope_offset_alt = solved["Alt"] - solved["camera_center"]["Alt"] # TODO: Do something similar for EQ mounts here - logger.debug("Coordinates stored from plate solve.") last_image_solve = copy.deepcopy(solved) solved["solve_source"] = "CAM" - # Use IMU dead-reckoning from the last camera solve: - # 1) Check we have an alt/az solve, otherwise we can't use the IMU - # If Alt exists: - # 2) Calculate the difference in the IMU measurements since the - # last plage solve. IMU "pos" is stored as Alt/Az. - # 3) Add the relative Alt/Az difference from the IMU to the plate - # -solved Alt/Az to give a dead-reckoning estimate of the current - # position. elif solved["Alt"]: + # Use IMU dead-reckoning from the last camera solve: + # 1) Check we have an alt/az solve, otherwise we can't use the IMU + # If Alt exists: + # 2) Calculate the difference in the IMU measurements since the + # last plage solve. IMU "pos" is stored as Alt/Az. + # 3) Add the relative Alt/Az difference from the IMU to the plate + # -solved Alt/Az to give a dead-reckoning estimate of the current + # position. imu = shared_state.imu() if imu: dt = shared_state.datetime() @@ -207,9 +206,10 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr #if imu_moved(lis_imu, imu_pos): assert isinstance(imu["quat"] , quaternion.quaternion), "Expecting quaternion.quaternion type" # TODO: Remove later angle_moved = pointing.get_quat_angular_diff(last_image_solve["imu_quat"], imu["quat"]) - logger.debug("Track using IMU. Angle moved = {:}".format(np.rad2deg(angle_moved))) if angle_moved > imu_moved_ang_threshold: # Estimate camera pointing using IMU dead-reckoning + logger.debug("Track using IMU. Angle moved since last_image_solve = {:} (> threshold = {:})".format(np.rad2deg(angle_moved), np.rad2deg(imu_moved_ang_threshold))) + q_x2imu = imu["quat"] # Latest IMU meas: quaternion rot. of IMU rel. to some frame X #q_x2imu = np.quaternion(q_x2imu.w, -q_x2imu.x, -q_x2imu.y, -q_x2imu.z) # HACK: Reverse the angle part of quaternion q_hor2x = last_image_solve["imu"]["q_hor2x"] @@ -227,7 +227,8 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr # TODO: need to define q_cam2scope #q_hor2scope = q_hor2cam * q_cam2scope - + logger.debug(" IMU quat = ({:}, {:}, {:}, {:}".format(q_x2imu.w, q_x2imu.x, q_x2imu.y, q_x2imu.z)) + """ DISABLE - Use quaternions # calc new alt/az - OLD method From 4eb04d550c356e24252c0e8c88fedfa7296e696b Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 5 Jul 2025 09:24:59 +0100 Subject: [PATCH 062/253] Additional logging printing for debugging --- python/PiFinder/integrator.py | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 12a0a38ce..cce35d578 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -104,6 +104,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr # so we can delta for IMU updates last_image_solve = None last_solve_time = time.time() + prev_imu = None # TODO: For debugging - remove later while True: state_utils.sleep_for_framerate(shared_state) @@ -201,6 +202,11 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr if last_image_solve and last_image_solve["Alt"] and last_image_solve["imu"]["q_hor2x"]: # If we have alt, then we have a position/time + # TODO: For debugging -- remove later + if prev_imu is None or pointing.get_quat_angular_diff(prev_imu, imu["quat"]) > 1E-4: + print("Quat: ", imu["quat"]) + prev_imu = imu["quat"].copy() + # calc new alt/az # When moving, switch to tracking using the IMU #if imu_moved(lis_imu, imu_pos): From 9a10120bc215988039b7a3c9c5aa67319a547628 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 5 Jul 2025 21:01:18 +0100 Subject: [PATCH 063/253] Rename func --- astro_data/comets.txt | 1210 +++++++++++++++++ .../PiFinder/pointing_model/pointing_model.py | 19 +- 2 files changed, 1220 insertions(+), 9 deletions(-) create mode 100644 astro_data/comets.txt diff --git a/astro_data/comets.txt b/astro_data/comets.txt new file mode 100644 index 000000000..472fc4b8d --- /dev/null +++ b/astro_data/comets.txt @@ -0,0 +1,1210 @@ + PJ96R020 2026 06 15.6745 2.587038 0.314255 333.4893 40.0442 2.5990 20250704 11.5 4.0 P/1996 R2 (Lagerkvist) NK 1615 + PJ98V24S 2027 09 7.8602 3.419486 0.243572 244.8885 159.0392 5.0293 20250704 13.0 2.0 P/1998 VS24 (LINEAR) MPC 75703 + PJ99R28O 2025 10 30.3015 1.122846 0.672179 231.3531 137.8412 7.5671 20250704 20.0 2.0 P/1999 RO28 (LONEOS) NK 731 + PJ99XC0N 2025 12 21.5458 3.297933 0.211738 161.5850 285.2398 5.0299 20250704 13.5 2.0 P/1999 XN120 (Catalina) MPC 75704 + PK00R020 2025 12 2.2970 1.628205 0.530635 176.5816 160.2706 11.6788 20250704 18.0 4.0 P/2000 R2 (LINEAR) NK 744 + PK01H050 2030 10 22.4786 2.442418 0.599232 224.5839 328.6752 8.3721 20250704 12.0 4.0 P/2001 H5 (NEAT) MPC 43019 + PK02E57J 2018 06 20.3595 2.621228 0.593937 167.2801 330.2272 4.9892 20250704 12.5 4.0 P/2002 EJ57 (LINEAR) MPEC 2023-UR6 + CK02J040 2003 09 24.4189 3.679001 1.001480 231.0777 70.7672 46.2191 20250704 5.5 4.0 C/2002 J4 (NEAT) MPEC 2025-MC0 + CK02V94Q 2006 02 11.2313 6.754417 0.963841 99.8060 35.0947 70.6542 20250704 9.5 2.0 C/2002 VQ94 (LINEAR) MPC 75007 + CK03A020 2003 11 5.3536 11.358825 0.997992 346.4661 154.5014 8.0703 20250704 3.5 4.0 C/2003 A2 (Gleason) MPC184407 + PK03F020 2019 11 14.0800 3.017230 0.538690 192.9613 358.9258 11.6414 20250704 16.5 2.0 P/2003 F2 (NEAT) MPC 50354 + PK03T120 2024 07 3.7270 0.593913 0.770165 219.7935 174.5760 11.0232 20250704 17.0 4.0 P/2003 T12 (SOHO) MPC105235 + PK04FE0Y 2027 02 22.1271 4.011069 0.192763 254.2527 327.2620 2.1628 20250704 12.5 2.0 P/2004 FY140 (LINEAR) MPEC 2022-YN2 + PK04R030 2021 09 15.5693 3.539101 0.254511 37.2042 305.1204 12.8020 20250704 14.5 4.0 P/2004 R3 (LINEAR-NEAT) MPC 53304 + PK04V050 2027 08 6.1704 4.433645 0.448768 87.1922 47.7411 19.3369 20250704 8.0 4.0 P/2004 V5 (LINEAR-Hill) MPC 75705 + PK04V05b 2027 08 7.1429 4.433650 0.448786 87.1964 47.7415 19.3370 20250704 8.0 4.0 P/2004 V5-B (LINEAR-Hill) MPC 75705 + PK05E010 2023 09 28.1442 4.402630 0.377310 193.9260 335.4965 4.2606 20250704 10.0 4.0 P/2005 E1 (Tubbiolo) MPC 54164 + PK05J010 2025 07 11.7011 1.539552 0.569371 338.9130 268.7998 31.7406 20250704 16.5 4.0 P/2005 J1 (McNaught) MPC 79019 + PK05L010 2021 12 30.2903 2.918240 0.255502 160.6361 127.1294 8.7116 20250704 9.5 4.0 P/2005 L1 (McNaught) MPC 74246 + PK05S020 2029 01 26.0642 6.399606 0.198472 230.0075 161.3329 3.1386 20250704 7.5 4.0 P/2005 S2 (Skiff) MPC 75706 + PK05T030 2026 08 19.8367 6.253637 0.174306 7.0925 27.6222 6.2321 20250704 9.0 4.0 P/2005 T3 (Read) MPC 73461 + PK05T040 2034 05 27.7990 0.647952 0.930715 41.7934 25.8235 160.2495 20250704 15.0 4.0 P/2005 T4 (SWAN) MPC 73461 + PK05T050 2025 06 14.9495 3.253537 0.551752 304.7819 57.0618 21.3837 20250704 11.0 4.0 P/2005 T5 (Broughton) MPC 75706 + PK06H30R 2028 10 9.2759 1.219300 0.843610 117.5134 309.7571 31.9572 20250704 11.0 4.0 P/2006 HR30 (Siding Spring) MPC 75707 + PK07C020 2026 03 21.1614 3.692610 0.474461 180.1137 275.2338 8.6131 20250704 10.0 4.0 P/2007 C2 (Catalina) MPC 75707 + CK07D010 2007 06 14.2652 8.739058 0.992948 339.7559 171.0359 41.5138 20250704 3.5 4.0 C/2007 D1 (LINEAR) MPC 84315 + PK07K020 2027 01 26.4272 2.312960 0.686486 347.0842 188.4114 7.5937 20250704 14.0 4.0 P/2007 K2 (Gibbs) MPEC 2024-GJ3 + PK07Q020 2020 11 24.9451 1.875139 0.668762 162.8469 172.2269 10.1933 20250704 16.0 4.0 P/2007 Q2 (Gilmore) MPC 60925 + PK07S010 2022 10 6.4057 2.528204 0.337919 245.2750 141.3266 5.9631 20250704 13.0 4.0 P/2007 S1 (Zhao) MPC 73462 + CK07S020 2008 09 4.4604 5.534766 0.557012 210.1446 296.1307 16.9168 20250704 6.5 4.0 C/2007 S2 (Lemmon) MPEC 2024-GJ3 + PK07S24A 2022 12 1.6222 2.682679 0.568889 107.7937 233.2250 17.1074 20250704 12.6 4.0 P/2007 SA24 (Lemmon) MPC184407 + PK07T020 2023 11 17.4894 0.652992 0.785448 359.6672 3.3932 9.7479 20250704 18.5 4.0 P/2007 T2 (Kowalski) MPC 61994 + CK08E010 2008 08 22.7347 4.812373 0.552906 270.3654 188.9188 34.8643 20250704 7.0 4.0 C/2008 E1 (Catalina) MPEC 2024-GJ3 + PK08O030 2031 12 23.6945 2.494280 0.696141 341.2022 47.6073 32.3092 20250704 13.0 4.0 P/2008 O3 (Boattini) MPC 64114 + PK08Y030 2031 10 6.0837 4.434442 0.448247 238.1336 262.8384 38.7791 20250704 8.5 4.0 P/2008 Y3 (McNaught) MPC 75710 + PK09B010 2026 06 30.4359 2.448371 0.635934 129.0052 297.1088 22.2596 20250704 13.0 4.0 P/2009 B1 (Boattini) MPC 75710 + CK09G010 2009 04 17.2493 1.135426 0.997488 175.5050 120.8778 108.0258 20250704 9.0 4.0 C/2009 G1 (STEREO) MPC 66466 + PK09K37F 2026 01 17.7381 2.835021 0.310584 143.9695 111.9435 11.3882 20250704 14.9 4.0 P/2009 KF37 MPC184407 + PK09O030 2031 01 25.9363 2.439635 0.686123 154.4194 183.7171 16.2514 20250704 12.5 4.0 P/2009 O3 (Hill) MPC 75710 + PK09Q050 2029 12 18.2453 2.901313 0.609306 209.2050 160.2043 40.9534 20250704 10.0 4.0 P/2009 Q5 (McNaught) MPC 68902 + PK09T020 2031 06 11.3196 1.792267 0.767478 216.0080 216.3107 27.5983 20250704 14.0 4.0 P/2009 T2 (La Sagra) MPC112389 + PK09W51X 2026 04 15.0691 0.802392 0.739687 118.2946 31.5222 9.5980 20250704 19.0 2.0 P/2009 WX51 (Catalina) MPC105235 + PK09Y020 2026 12 1.7429 2.370647 0.637394 172.2450 262.0829 29.9730 20250704 13.0 4.0 P/2009 Y2 (Kowalski) MPC 74247 + CK10B010 2011 02 3.3115 2.951526 0.998812 211.6053 277.2239 102.2533 20250704 7.5 4.0 C/2010 B1 (Cardinal) MPEC 2025-MC0 + PK10C010 2028 09 21.6606 5.248020 0.263932 2.9081 141.5889 9.1157 20250704 9.5 4.0 P/2010 C1 (Scotti) MPC 75008 + PK10D020 2027 07 9.4935 3.682713 0.451691 120.0181 319.8767 57.1358 20250704 16.0 4.0 P/2010 D2 (WISE) MPC 75008 + PK10E020 2035 08 1.2950 2.409731 0.720935 8.2107 177.8278 15.4272 20250704 14.0 4.0 P/2010 E2 (Jarnac) MPC 75009 + PK10H020 2025 03 9.6697 3.075968 0.197768 128.0526 64.1889 14.2791 20250704 6.0 4.0 P/2010 H2 (Vales) MPC 72851 + PK10H030 2026 05 25.2347 0.043779 0.985576 26.0731 77.1812 23.1476 20250704 20.0 2.0 P/2010 H3 (SOHO) MPC 70361 + PK10H040 2027 05 21.6070 4.850226 0.267127 179.0801 44.7467 2.3178 20250704 10.5 4.0 P/2010 H4 (Scotti) MPEC 2024-GJ3 + PK10H050 2029 05 22.1622 6.057244 0.155371 174.9503 24.5049 14.0524 20250704 13.0 2.0 P/2010 H5 (Scotti) MPC 74637 + PK10J030 2037 07 18.9143 2.479074 0.724183 157.4156 106.5400 13.2261 20250704 11.0 4.0 P/2010 J3 (McMillan) MPC 98558 + PK10J81C 2034 05 29.3121 1.798294 0.778065 12.5078 30.8499 38.7660 20250704 9.0 4.0 P/2010 JC81 (WISE) MPC 84315 + PK10K43G 2023 08 26.6677 2.886398 0.482859 354.4253 325.6755 13.6508 20250704 12.7 4.0 P/2010 KG43 MPC184408 + AK10LD5N 2011 05 25.0831 1.747446 0.999956 181.5734 184.8573 64.4494 20250704 14.0 2.0 A/2010 LN135 MPEC 2024-H77 + PK10LF5H 2025 04 9.0281 2.224067 0.405990 308.5243 221.1200 8.8068 20250704 14.3 4.0 P/2010 LH155 MPEC 2025-MC0 + PK10T020 2024 02 23.3112 3.767622 0.325558 350.1592 57.8039 7.8584 20250704 11.5 4.0 P/2010 T2 (PANSTARRS) MPC 74248 + PK10U010 2026 09 9.9309 4.875199 0.248348 86.5411 280.8067 8.2273 20250704 9.5 4.0 P/2010 U1 (Boattini) MPC 82316 + CK10U030 2019 02 28.1178 8.439200 0.999720 88.0860 42.9925 55.5451 20250704 1.0 4.0 C/2010 U3 (Boattini) MPEC 2023-J95 + PK10U55H 2028 06 2.3024 2.893832 0.564699 225.3179 232.8238 8.0369 20250704 11.0 4.0 P/2010 UH55 (Spacewatch) MPC 79021 + PK11C020 2032 02 3.9780 5.399558 0.271185 160.2818 11.9611 10.8954 20250704 9.0 4.0 P/2011 C2 (Gibbs) MPC 84021 + PK11FE3R 2029 02 1.1823 3.767619 0.452601 349.6424 190.8466 15.9620 20250704 14.0 2.0 P/2011 FR143 (Lemmon) MPC 79866 + PK11J15B 2032 01 11.2291 5.057127 0.314803 110.6890 153.5860 19.1256 20250704 9.0 4.0 P/2011 JB15 (Spacewatch-Boattini) MPC 82317 + PK11N010 2027 12 30.9553 2.833482 0.545450 330.4970 77.6283 35.7858 20250704 11.5 4.0 P/2011 N1 (ASH) MPC 87913 + PK11P010 2030 12 21.6843 5.026749 0.326332 349.1731 4.2570 5.6517 20250704 9.0 4.0 P/2011 P1 (McNaught) MPEC 2022-ED3 + PK11S010 2014 08 24.5291 6.869150 0.200949 192.9581 218.8974 2.6884 20250704 8.0 4.0 P/2011 S1 (Gibbs) MPEC 2022-HC2 + PK11V010 2026 04 23.5445 1.742199 0.548368 269.6064 46.4915 7.3828 20250704 15.5 4.0 P/2011 V1 (Boattini) MPEC 2023-UR6 + PK11W010 2022 02 9.4668 3.326063 0.288462 283.0394 161.8061 3.7160 20250704 11.5 4.0 P/2011 W1 (PANSTARRS) MPC 82718 + PK11Y020 2027 10 2.2012 1.798732 0.711202 132.0737 309.3199 6.3921 20250704 15.0 4.0 P/2011 Y2 (Boattini) MPC 79342 + PK12B010 2030 03 8.4604 3.859022 0.410151 161.9110 36.2093 7.6053 20250704 9.0 4.0 P/2012 B1 (PANSTARRS) MPEC 2022-K19 + PK12C030 2011 10 6.7469 3.605925 0.630111 344.9542 135.3677 9.0920 13.0 4.0 P/2012 C3 (PANSTARRS) MPC 78590 + PK12F020 2029 03 19.1316 2.916185 0.540602 33.1595 226.9507 14.6979 20250704 12.0 4.0 P/2012 F2 (PANSTARRS) MPC 84931 + PK12G010 2029 03 27.9017 2.790620 0.329570 266.0156 283.2365 12.1681 20250704 15.0 4.0 P/2012 G1 (PANSTARRS) MPEC 2022-ED3 + PK12K030 2026 07 15.9055 2.100831 0.421691 172.1370 125.8052 13.1815 20250704 15.0 4.0 P/2012 K3 (Gibbs) MPC 80898 + CK12K51A 2011 11 6.2250 4.867013 0.990873 93.9951 344.8338 70.7262 20250704 8.7 4.0 C/2012 KA51 MPC184408 + PK12N00J 2037 02 1.2490 1.299790 0.846498 338.3853 315.6965 84.3166 20250704 14.5 4.0 P/2012 NJ (La Sagra) MPC 88326 + PK12O010 2025 11 1.1138 1.440115 0.593564 238.2783 91.9402 7.4280 20250704 17.5 4.0 P/2012 O1 (McNaught) MPC 81470 + PK12O020 2026 04 1.5161 1.701681 0.531237 183.4092 120.6611 24.4555 20250704 17.0 4.0 P/2012 O2 (McNaught) MPC 80899 + PK12T020 2027 01 21.1846 4.790599 0.162061 311.1940 73.8747 12.5699 20250704 10.0 4.0 P/2012 T2 (PANSTARRS) MPC 82320 + PK12T030 2027 08 9.9407 2.367570 0.615588 195.4624 114.3246 9.5537 20250704 15.0 4.0 P/2012 T3 (PANSTARRS) MPC 80900 + PK12U020 2031 12 5.8936 3.559587 0.500463 228.4494 185.2698 10.7580 20250704 12.5 4.0 P/2012 U2 (PANSTARRS) MPC 82720 + PK13A76L 2029 06 28.1054 2.044186 0.685521 27.1199 146.0951 144.9148 20250704 16.0 4.0 P/2013 AL76 (Catalina) MPC 82721 + PK13G010 2032 01 18.8759 3.384771 0.509970 51.3612 221.3153 5.4571 20250704 11.0 4.0 P/2013 G1 (Kowalski) MPC 91612 + PK13G040 2022 06 19.1635 2.617823 0.409419 214.5176 339.5876 5.9201 20250704 15.0 4.0 P/2013 G4 (PANSTARRS) MPC 84025 + PK13J020 2029 03 13.7692 2.144094 0.655828 37.8559 289.2886 15.5000 20250704 13.0 4.0 P/2013 J2 (McNaught) MPC 91613 + PK13N030 2034 04 9.8814 3.030163 0.590852 323.8770 17.5954 2.1670 20250704 13.0 4.0 P/2013 N3 (PANSTARRS) MPC 86229 + PK13N050 2031 04 2.5429 1.826074 0.731439 176.9590 187.1587 23.4106 20250704 17.0 4.0 P/2013 N5 (PANSTARRS) MPC 85834 + PK13P010 2013 02 15.2090 3.416295 0.602422 138.1214 160.7054 18.6861 20250704 12.0 4.0 P/2013 P1 (PANSTARRS) MPC 85834 + PK13R030 2024 03 20.8677 2.192545 0.277191 11.4886 341.7963 0.8655 20250704 14.0 4.0 P/2013 R3 (Catalina-PANSTARRS) MPEC 2022-V95 + PK13R03a 2024 03 20.4911 2.192562 0.277123 11.5661 341.7509 0.8646 20250704 9.0 4.0 P/2013 R3-A (Catalina-PANSTARRS) unp + PK13R03b 2024 03 20.8905 2.192597 0.277167 11.5019 341.8072 0.8658 20250704 9.0 4.0 P/2013 R3-B (Catalina-PANSTARRS) MPEC 2015-M77 + PK13T010 2027 10 12.9908 2.204181 0.623556 346.1728 10.0839 24.2686 20250704 16.5 4.0 P/2013 T1 (PANSTARRS) MPC 85835 + PK13T020 2026 06 11.3921 1.746196 0.500186 345.5644 0.8052 9.4467 20250704 16.0 4.0 P/2013 T2 (Schwartz) MPC 86643 + PK13W010 2027 03 15.9270 1.415369 0.593844 1.2472 117.8354 4.7000 20250704 17.5 4.0 P/2013 W1 (PANSTARRS) MPC 91613 + PK13Y46G 2023 01 20.4708 1.726138 0.470799 244.7258 46.6249 7.5142 20250704 10.0 4.0 P/2013 YG46 (Spacewatch) MPC101095 + PK14A020 2028 03 14.1665 2.091959 0.646693 356.2039 106.6561 24.5634 20250704 15.0 4.0 P/2014 A2 (Hill) MPC 89728 + PK14C010 2028 07 3.1355 2.649487 0.341965 188.2265 39.8248 3.2090 20250704 15.5 4.0 P/2014 C1 (TOTAS) MPEC 2024-F34 + CK14F030 2021 05 27.4757 5.731364 0.601668 5.1334 325.9781 6.5210 20250704 6.0 4.0 C/2014 F3 (Sheppard-Trujillo) MPEC 2022-WD2 + PK14L020 2030 05 26.3798 2.233642 0.646155 182.6888 149.3365 5.1903 20250704 12.0 4.0 P/2014 L2 (NEOWISE) MPC 98560 + PK14L030 2014 06 20.9231 1.873836 0.771036 178.6542 115.5305 6.2536 20250704 16.0 4.0 P/2014 L3 (Hill) MPC 90769 + PK14M040 2029 03 18.9963 2.368624 0.595989 148.1279 263.1999 3.3472 20250704 15.0 4.0 P/2014 M4 (PANSTARRS) MPC 91614 + PK14O030 2035 02 25.7246 4.685939 0.382417 204.6507 87.6244 7.7890 20250704 10.5 4.0 P/2014 O3 (PANSTARRS) MPC 98560 + CK14Od2G 2022 01 4.9929 9.984642 0.185334 255.3420 145.8259 9.0324 20250704 6.0 4.0 C/2014 OG392 (PANSTARRS) MPC182878 + PK14U040 2027 09 13.8851 1.883631 0.463706 347.8408 11.9262 6.4220 20250704 18.0 4.0 P/2014 U4 (PANSTARRS) MPC 91616 + CK14UR1N 2031 01 16.3106 10.960439 1.004248 326.0768 189.9629 95.4446 20250704 2.5 3.2 C/2014 UN271 (Bernardinelli-Bernstein) MPEC 2025-MC0 + PK14V010 2027 11 27.5861 2.557771 0.533392 177.6468 166.1798 22.4990 20250704 14.0 4.0 P/2014 V1 (PANSTARRS) MPC 95211 + PK14W040 2032 11 23.9288 4.242812 0.355140 67.7508 33.3026 15.2833 20250704 11.0 4.0 P/2014 W4 (PANSTARRS) MPC105542 + PK14X010 2030 06 15.0090 1.791673 0.710924 33.9558 61.5428 26.0481 20250704 15.0 4.0 P/2014 X1 (Elenin) MPC 94281 + PK15A030 2015 02 23.4562 1.165660 0.850870 249.6656 277.4875 172.5515 20250704 20.0 4.0 P/2015 A3 (PANSTARRS) MPC 92275 + PK15B010 2015 09 6.5437 5.997301 0.366940 188.6655 352.8487 18.0890 20250704 8.5 4.0 P/2015 B1 (PANSTARRS) MPC 99270 + PK15B040 2015 02 9.3427 3.719384 0.562652 227.0984 266.1377 1.7676 20250704 11.0 4.0 P/2015 B4 (Lemmon-PANSTARRS) MPC109141 + PK15C010 2032 02 1.6100 2.824579 0.568428 178.0607 348.7420 13.8813 20250704 12.5 4.0 P/2015 C1 (TOTAS-Gibbs) MPC101096 + PK15D050 2014 04 10.7322 4.544292 0.491924 39.6293 74.0869 20.5511 20250704 9.0 4.0 P/2015 D5 (Kowalski) MPC109141 + PK15D060 2034 07 1.2392 4.536751 0.362717 125.9079 45.3766 20.3058 20250704 10.5 4.0 P/2015 D6 (Lemmon-PANSTARRS) MPEC 2024-R10 + PK15K050 2032 11 2.6672 3.016799 0.551612 106.0921 134.3121 39.9251 20250704 13.5 4.0 P/2015 K5 (PANSTARRS) MPC 95213 + PK15M020 2035 03 16.5792 5.966221 0.177672 225.7217 86.6990 3.9678 20250704 8.5 4.0 P/2015 M2 (PANSTARRS) MPC107684 + PK15P040 2030 12 11.6187 2.510179 0.584997 280.7429 104.6750 8.7223 20250704 14.0 4.0 P/2015 P4 (PANSTARRS) MPC 99819 + PK15PM9D 2034 12 14.9724 4.864893 0.325037 352.6763 342.7492 2.0200 20250704 11.5 2.0 P/2015 PD229 (Cameron-ISON) MPEC 2022-K19 + PK15Q020 2015 09 13.3654 1.820127 0.752296 244.6420 228.5249 146.5493 20250704 15.5 4.0 P/2015 Q2 (Pimentel) MPC 96867 + PK15R010 2029 10 7.6909 2.160652 0.632855 300.5079 48.3923 22.6808 20250704 14.0 4.0 P/2015 R1 (PANSTARRS) MPC 98562 + PK15R020 2024 12 15.7157 2.454984 0.451973 149.8752 168.6021 15.4827 20250704 14.5 4.0 P/2015 R2 (PANSTARRS) MPC 95734 + PK15T19O 2025 11 23.5388 2.911378 0.359609 89.3432 321.6614 6.5055 20250704 14.0 4.0 P/2015 TO19 (Lemmon-PANSTARRS) MPC102953 + PK15TK0P 2016 11 3.5781 3.359973 0.537360 82.6033 6.9023 8.7782 20250704 11.0 4.0 P/2015 TP200 (LINEAR) MPC110080 + PK15W020 2015 10 8.5676 2.660895 0.635185 117.7196 294.0689 11.6209 20250704 13.0 4.0 P/2015 W2 (Catalina) MPC101098 + PK15X030 2026 10 23.6464 2.799425 0.439829 306.9776 77.2548 24.4221 20250704 15.0 4.0 P/2015 X3 (PANSTARRS) MPEC 2023-J29 + PK15X060 2025 05 11.3314 2.273686 0.174154 329.6969 106.9295 4.5659 20250704 16.0 4.0 P/2015 X6 (PANSTARRS) MPC115881 + PK16A030 2017 04 26.7130 4.821603 0.387126 340.8018 187.1275 8.5217 20250704 10.0 4.0 P/2016 A3 (PANSTARRS) MPEC 2022-OB6 + PK16A070 2027 05 27.7398 2.182866 0.569635 352.8313 220.5194 16.2498 20250704 16.0 4.0 P/2016 A7 (PANSTARRS) MPC102098 + PK16G010 2025 05 16.1412 2.041076 0.210016 111.0871 204.0100 10.9700 20250704 14.0 4.0 P/2016 G1 (PANSTARRS) MPEC 2021-P47 + CK16J020 2016 04 12.6533 1.496297 1.000355 318.2561 186.2634 130.3767 20250704 17.0 4.0 C/2016 J2 (Denneau) MPEC 2024-C04 + PK16P010 2027 03 6.0686 2.283411 0.287243 271.0683 319.0083 24.4528 20250704 15.0 4.0 P/2016 P1 (PANSTARRS) MPC102099 + PK16P050 2023 05 22.0551 4.430852 0.057309 33.8505 185.3752 7.0380 20250704 13.2 4.0 P/2016 P5 (COIAS) MPC184408 + CK16Q020 2021 05 11.5880 7.079904 1.002346 84.5271 322.3497 109.3247 20250704 6.0 4.0 C/2016 Q2 (PANSTARRS) MPEC 2024-H50 + PK16R040 2028 11 19.5093 2.803989 0.474705 174.0972 168.2658 10.8634 20250704 12.5 4.0 P/2016 R4 (Gibbs) MPEC 2022-K19 + PK16S010 2017 03 20.6542 2.379675 0.712113 273.1569 227.6406 94.7315 20250704 12.0 4.0 P/2016 S1 (PANSTARRS) MPC105543 + PK16W48M 2017 02 27.6996 1.763865 0.784197 36.1797 59.9444 117.6165 20250704 15.0 4.0 P/2016 WM48 (Lemmon) MPC106345 + CK16X010 2019 04 30.8464 7.560867 0.997282 224.6167 256.3013 26.4693 20250704 6.0 4.0 C/2016 X1 (Lemmon) MPEC 2021-P47 + CK17B030 2019 01 30.0654 3.933033 0.998795 284.7580 2.2490 54.2256 20250704 6.0 4.0 C/2017 B3 (LINEAR) MPEC 2022-OB6 + PK17B040 2017 01 5.8178 2.800894 0.364952 11.0197 121.4578 20.0584 14.5 4.0 P/2017 B4 (PANSTARRS) MPC103847 + PK17D010 2027 01 30.9620 2.710809 0.437819 8.0875 82.1915 20.7713 20250704 14.0 4.0 P/2017 D1 (Fuls) MPEC 2022-OB6 + PK17D040 2016 09 10.9271 2.785583 0.630653 212.1344 264.9133 10.5614 20250704 13.0 4.0 P/2017 D4 (PANSTARRS) MPEC 2022-OB6 + PK17F36L 2025 08 8.6591 2.830970 0.032757 90.2137 313.4509 15.6870 20250704 14.7 4.0 P/2017 FL36 (PANSTARRS) MPC184408 + PK17G010 2016 04 21.3013 2.510961 0.650879 225.2568 247.1364 5.1551 20250704 13.5 4.0 P/2017 G1 (PANSTARRS) MPEC 2024-C04 + PK17G020 2017 06 10.4816 2.820744 0.648953 105.2066 79.8952 47.9682 20250704 13.0 4.0 P/2017 G2 (PANSTARRS) MPC108595 + CK17K020 2022 12 18.5344 1.799875 0.998948 236.1716 88.2219 87.6429 20250704 1.5 4.0 C/2017 K2 (PANSTARRS) MPC184408 + PK17K030 2030 07 30.9363 2.351663 0.579109 253.2862 354.1784 4.2723 20250704 14.5 4.0 P/2017 K3 (Gasparovic) MPEC 2021-N06 + CK17K050 2020 03 25.4539 7.677126 1.002898 171.9347 102.4583 82.2794 20250704 5.0 4.0 C/2017 K5 (PANSTARRS) MPEC 2021-P47 + CK17M040 2019 01 17.6183 3.235718 1.000164 167.4074 66.0109 105.6277 20250704 6.0 4.0 C/2017 M4 (ATLAS) MPEC 2022-OB6 + PK17P010 2018 06 18.8549 5.473605 0.308962 122.7684 221.4692 7.6880 20250704 10.0 4.0 P/2017 P1 (PANSTARRS) MPC114599 + PK17S080 2027 05 4.5075 1.691800 0.391136 254.9230 191.5071 29.8401 20250704 16.0 4.0 P/2017 S8 (PANSTARRS) MPEC 2022-OB6 + CK17T020 2020 05 6.0897 1.603682 0.999000 92.7777 64.4351 57.2833 20250704 5.0 4.0 C/2017 T2 (PANSTARRS) MPEC 2024-A43 + PK17T13W 2018 06 23.7848 2.065285 0.710648 120.0220 322.1191 44.8841 20250704 15.0 2.0 P/2017 TW13 (Lemmon) MPC115882 + PK17U030 2030 03 15.8502 4.423343 0.100854 296.4660 165.0559 15.9225 20250704 11.0 4.0 P/2017 U3 (PANSTARRS) MPEC 2022-K19 + CK17U070 2019 09 16.2391 6.418830 1.002723 326.4149 276.3210 142.6395 20250704 8.3 2.0 C/2017 U7 (PANSTARRS) MPEC 2023-A50 + PK17W030 2018 02 26.7198 3.853815 0.507077 327.7731 210.0647 18.1889 20250704 10.5 4.0 P/2017 W3 (Gibbs) MPC114601 + CK17Y020 2020 11 4.8999 4.621078 1.001045 147.8031 66.0290 128.4477 20250704 15.0 4.0 C/2017 Y2 (PANSTARRS) MPEC 2024-DC6 + PK17Y030 2018 02 6.3655 1.276706 0.869645 67.3210 154.0257 27.6318 20250704 16.5 4.0 P/2017 Y3 (Leonard) MPC111770 + CK18A030 2019 01 8.6385 3.293761 0.990477 86.5181 194.3603 139.6109 20250704 8.5 4.0 C/2018 A3 (ATLAS) MPEC 2021-P47 + PK18A050 2031 01 31.3389 2.674316 0.524502 359.5561 87.7836 23.6241 20250704 15.0 4.0 P/2018 A5 (PANSTARRS) MPC109147 + CK18A060 2019 07 10.2894 3.016619 0.798840 264.2645 340.4607 77.1628 20250704 9.0 4.0 C/2018 A6 (Gibbs) MPEC 2024-JU4 + PK18C010 2031 07 31.0441 2.640101 0.532676 235.8127 270.1885 5.1011 20250704 13.5 4.0 P/2018 C1 (Lemmon-Read) MPC114601 + CK18D04O 2019 08 17.1215 2.421970 0.905132 176.4266 251.3960 160.4450 20250704 11.0 4.0 C/2018 DO4 (Lemmon) MPEC 2022-M88 + CK18F010 2018 12 10.1211 2.990928 0.986199 71.4188 177.3236 46.1777 20250704 11.5 4.0 C/2018 F1 (Grauer) MPEC 2021-R75 + CK18F040 2019 11 30.8210 3.448655 0.998003 263.1942 26.5400 78.1407 20250704 11.0 6.0 C/2018 F4 (PANSTARRS) MPEC 2023-A50 + CK18F04a 2019 11 30.8091 3.448523 0.997950 263.1910 26.5402 78.1409 20250704 11.0 6.0 C/2018 F4-A MPEC 2021-Y10 + CK18F04b 2019 11 30.7459 3.448339 0.998039 263.1768 26.5397 78.1418 20250704 11.0 6.0 C/2018 F4-B MPEC 2023-D41 + PK18H020 2027 03 18.2524 2.029226 0.539827 119.1705 67.9862 7.4163 20250704 16.6 2.0 P/2018 H2 (PANSTARRS) MPC114602 + CK18K03J 2019 09 8.6662 3.617288 0.994751 217.5306 91.6955 136.6200 20250704 12.2 2.0 C/2018 KJ3 (Lemmon) MPEC 2021-R75 + CK18L020 2018 11 29.4188 1.721709 0.992680 56.3436 242.9908 67.2192 20250704 10.0 4.0 C/2018 L2 (ATLAS) MPEC 2021-P47 + PK18L040 2029 07 28.4695 1.690964 0.658312 140.5009 145.2199 26.5956 20250704 17.5 4.0 P/2018 L4 (PANSTARRS) MPC114603 + CK18N020 2019 11 12.0904 3.135748 1.002029 25.3263 24.5290 77.4927 20250704 6.0 4.0 C/2018 N2 (ASASSN) MPEC 2022-YN2 + PK18P040 2018 11 6.8374 3.689579 0.448990 8.5165 353.1591 23.0772 20250704 12.0 4.0 P/2018 P4 (PANSTARRS) MPC114603 + CK18P050 2019 02 25.5182 4.603980 0.641529 132.0324 216.2721 7.2465 20250704 11.0 4.0 C/2018 P5 (PANSTARRS) MPEC 2021-P47 + CK18R030 2019 06 7.9891 1.284591 0.999287 112.8119 324.3538 69.6862 20250704 9.5 4.0 C/2018 R3 (Lemmon) MPC118841 + CK18R050 2019 01 10.7853 3.637759 0.841698 178.2719 171.2728 103.6802 20250704 11.5 4.0 C/2018 R5 (Lemmon) MPC114603 + CK18S020 2018 11 5.2573 5.491788 0.617817 290.9543 85.1075 64.1106 20250704 7.5 4.0 C/2018 S2 (TESS) MPEC 2022-QC6 + CK18U010 2021 11 2.1021 4.985700 1.000084 180.3481 75.5136 108.3258 20250704 5.0 4.0 C/2018 U1 (Lemmon) MPC184408 + CK18V010 2018 12 4.1910 0.390572 1.000463 89.5853 129.6200 144.2041 20250704 12.0 4.0 C/2018 V1 (Machholz-Fujikawa-Iwamoto) MPC114604 + CK18V020 2018 11 26.4584 2.492141 0.901315 319.2950 357.2290 159.1610 20250704 15.0 4.0 C/2018 V2 (ATLAS) MPC115884 + PK18V02N 2026 08 15.7446 2.119352 0.478142 138.9254 226.4377 18.2567 20250704 15.0 4.0 P/2018 VN2 (Leonard) MPEC 2025-A40 + AK18V030 2019 09 10.4842 1.329570 0.989542 3.5727 308.8233 164.9119 20250704 15.7 2.0 A/2018 V3 MPEC 2025-A40 + CK18V040 2019 03 2.4092 3.204276 0.985200 0.1041 78.2470 69.0425 20250704 12.5 4.0 C/2018 V4 (Africano) MPEC 2022-M21 + PK18V050 2018 10 6.1962 4.708732 0.475752 260.8991 171.2903 10.5771 20250704 12.5 4.0 P/2018 V5 (Trujillo-Sheppard) MPEC 2021-P47 + CK18W010 2019 05 13.9747 1.351258 0.937853 251.1649 233.6294 83.3933 20250704 15.5 2.0 C/2018 W1 (Catalina) MPEC 2021-P47 + CK18W020 2019 09 5.7416 1.465370 1.000947 158.2402 181.9877 116.5332 20250704 9.5 4.0 C/2018 W2 (Africano) MPEC 2021-P47 + AK18W030 2021 04 13.1668 4.281592 0.993880 313.8598 251.6873 104.8377 20250704 10.7 2.0 A/2018 W3 MPEC 2023-M14 + CK18X020 2019 07 9.8921 2.110888 0.985030 162.0125 340.6296 23.1088 20250704 12.0 4.0 C/2018 X2 (Fitzsimmons) MPC119996 + CK18X030 2019 01 1.6579 2.694913 0.782898 359.8709 78.7970 43.4256 20250704 14.5 4.0 C/2018 X3 (PANSTARRS) MPC114604 + CK18Y010 2019 02 3.3150 1.293693 0.989762 357.8677 147.3324 160.4846 20250704 11.5 4.0 C/2018 Y1 (Iwamoto) MPEC 2024-A43 + PK18Y020 2019 01 4.6903 3.877806 0.480017 162.3940 297.1156 11.6956 20250704 11.5 4.0 P/2018 Y2 (Africano) MPC114605 + PK19A010 2030 05 6.9278 2.196694 0.570316 150.7890 312.2099 13.7724 20250704 16.0 4.0 P/2019 A1 (PANSTARRS) MPC114605 + PK19A020 2018 11 24.3796 3.521630 0.383296 323.9616 139.3657 14.8739 20250704 10.5 4.0 P/2019 A2 (ATLAS) MPEC 2021-P47 + PK19A030 2024 03 2.7296 2.304051 0.267596 325.6444 31.2573 15.3549 20250704 16.0 4.0 P/2019 A3 (PANSTARRS) MPEC 2022-M21 + PK19A040 2027 05 26.8653 2.385905 0.087429 343.2446 119.3536 13.3059 20250704 15.0 4.0 P/2019 A4 (PANSTARRS) MPEC 2022-L66 + CK19A050 2019 06 7.0715 6.312808 0.706469 355.8306 146.5112 67.5515 20250704 9.5 4.0 C/2019 A5 (PANSTARRS) MPEC 2021-P47 + PK19A060 2031 01 25.6369 1.926550 0.640355 156.2525 280.1733 33.2987 20250704 16.0 4.0 P/2019 A6 (Lemmon-PANSTARRS) MPC114605 + CK19A090 2019 07 27.2835 1.426383 0.963721 237.8776 278.4713 84.4005 20250704 15.0 4.0 C/2019 A9 (PANSTARRS) MPC118842 + CK19B010 2019 03 18.2485 1.603967 0.988528 174.8299 290.2318 123.4940 20250704 16.0 4.0 C/2019 B1 (Africano) MPEC 2022-L66 + PK19B020 2027 02 24.2855 2.523560 0.357694 0.5825 175.6464 16.9504 20250704 14.5 4.0 P/2019 B2 (Groeller) MPC115885 + CK19B030 2021 01 19.5604 6.830083 0.998099 263.9991 358.4017 66.6061 20250704 5.5 4.0 C/2019 B3 (PANSTARRS) MPEC 2024-JU4 + CK19C010 2020 05 4.5994 6.567159 0.990495 319.0178 212.3679 36.0373 20250704 10.0 4.0 C/2019 C1 (ATLAS) MPEC 2021-P47 + CK19D010 2019 05 8.7352 1.592204 0.988322 70.7138 231.6685 34.0126 20250704 13.0 4.0 C/2019 D1 (Flewelling) MPEC 2022-O08 + CK19E030 2023 11 15.6415 10.313297 0.998106 280.7196 347.1944 84.3157 20250704 2.5 4.0 C/2019 E3 (ATLAS) MPEC 2025-MC0 + CK19F010 2021 06 21.1232 3.608322 1.000265 251.3013 38.6642 54.2541 20250704 5.5 4.0 C/2019 F1 (ATLAS-Africano) MPEC 2024-GJ3 + CK19F020 2019 09 7.7956 2.238729 0.864779 11.6092 175.3448 19.3361 20250704 12.0 4.0 C/2019 F2 (ATLAS) MPEC 2025-A40 + CK19G020 2019 12 6.4381 2.306186 0.994256 82.7893 208.2395 159.2544 20250704 15.0 4.0 C/2019 G2 (PANSTARRS) MPEC 2024-E01 + AK19G030 2018 12 3.6143 2.836336 0.834254 161.7245 49.8915 156.8091 20250704 17.1 2.0 A/2019 G3 MPEC 2022-VC5 + PK19G21G 2019 05 9.6257 3.946177 0.471643 208.5912 340.5657 6.0827 20250704 12.0 4.0 P/2019 GG21 (PANSTARRS) MPC114607 + CK19H010 2019 04 26.8205 1.839807 0.991912 19.2390 269.3122 104.3568 20250704 15.5 4.0 C/2019 H1 (NEOWISE) MPEC 2022-M21 + CK19J010 2019 04 5.8702 2.481492 0.962652 167.5646 98.2364 24.5222 20250704 12.0 4.0 C/2019 J1 (Lemmon) MPEC 2023-A50 + CK19J020 2019 07 21.1670 1.714037 0.989293 98.5458 25.4593 105.2110 20250704 13.0 4.0 C/2019 J2 (Palomar) MPEC 2021-R75 + CK19J030 2019 08 1.8901 2.361450 0.999871 16.4883 270.6557 131.2935 20250704 13.5 4.0 C/2019 J3 (ATLAS) MPC117071 + CK19J06U 2019 06 2.8962 2.031357 0.999851 94.7649 21.6836 148.2981 20250704 14.5 4.0 C/2019 JU6 (ATLAS) MPEC 2022-M21 + CK19K010 2020 02 10.8398 2.021602 0.999302 265.7831 73.3121 87.0187 20250704 10.0 4.0 C/2019 K1 (ATLAS) MPEC 2022-O08 + CK19K040 2019 06 15.3003 2.275876 0.998607 140.0231 180.3025 105.2873 20250704 12.5 4.0 C/2019 K4 (Ye) MPC119997 + CK19K050 2019 06 21.2566 2.055285 0.987781 175.1414 177.2804 15.2915 20250704 13.0 4.0 C/2019 K5 (Young) MPEC 2021-P47 + CK19K060 2020 05 18.5124 3.917298 0.995749 187.4284 42.9778 132.3901 20250704 11.5 4.0 C/2019 K6 (PANSTARRS) MPEC 2021-P47 + CK19K070 2020 06 17.0927 4.474084 1.000309 27.3544 308.0371 103.4765 20250704 6.0 4.0 C/2019 K7 (Smith) MPEC 2024-GJ3 + CK19K080 2019 07 20.1212 3.198693 0.998071 85.3731 290.9886 93.0474 20250704 11.5 4.0 C/2019 K8 (ATLAS) MPEC 2021-R75 + CK19L010 2019 08 7.0104 2.905335 0.704062 50.0086 254.4271 9.9737 20250704 13.5 4.0 C/2019 L1 (PANSTARRS) MPEC 2023-A50 + CK19L020 2019 04 3.8918 1.620715 0.935551 18.8471 12.5830 152.1463 20250704 16.0 4.0 C/2019 L2 (NEOWISE) MPC115886 + PK19L02D 2020 01 29.9897 4.488398 0.131411 116.4230 178.6902 11.6137 20250704 8.5 4.0 P/2019 LD2 (ATLAS) MPEC 2024-GJ3 + CK19L030 2022 01 10.1262 3.558779 1.003160 171.7521 290.7167 48.3459 20250704 4.5 4.0 C/2019 L3 (ATLAS) MPEC 2025-MC0 + PK19L04M 2019 06 20.0705 2.359775 0.586175 68.2091 72.8883 36.4160 20250704 9.5 4.0 P/2019 LM4 (Palomar) MPEC 2024-YC7 + CK19L07B 2019 03 27.6115 2.494844 0.928785 336.7784 4.0055 164.2786 20250704 17.0 4.0 C/2019 LB7 (Kleyna) MPC118095 + CK19M030 2018 12 31.4469 2.424672 0.999517 87.9350 155.0519 99.6519 20250704 12.2 4.0 C/2019 M3 (ATLAS) MPC118095 + CK19M040 2019 09 9.5803 9.191042 1.000370 260.3409 52.6421 65.6913 20250704 5.0 4.0 C/2019 M4 (TESS) MPEC 2023-JA2 + CK19N010 2020 11 30.5158 1.703084 0.998241 193.3440 13.5123 82.5319 20250704 7.5 4.0 C/2019 N1 (ATLAS) MPEC 2023-C45 + AK19N020 2019 08 22.4331 1.940091 0.998286 347.0670 276.2241 89.3209 20250704 12.5 2.0 A/2019 N2 MPEC 2023-CD8 + CK19N03J 2020 10 22.2422 4.362925 1.001431 246.8718 142.4924 99.3351 20250704 9.0 4.0 C/2019 NJ3 (Lemmon) MPEC 2022-A21 + CK19O020 2023 04 6.0719 9.680939 0.835215 129.5753 48.2630 93.2995 20250704 5.0 4.0 C/2019 O2 (PANSTARRS) MPEC 2025-MC0 + CK19O030 2021 03 8.4073 8.820735 1.002710 60.1002 300.4764 89.7961 20250704 3.5 4.0 C/2019 O3 (Palomar) MPC182878 + AK19O040 2020 02 11.1350 3.642310 0.890387 61.8239 354.9263 115.0040 20250704 15.5 2.0 A/2019 O4 MPEC 2021-P47 + CK19Q010 2020 07 22.1922 5.002731 1.002396 56.2548 42.4671 155.7212 20250704 8.5 4.0 C/2019 Q1 (Lemmon) MPEC 2024-EF7 + AK19Q020 2019 07 23.6649 1.260802 0.978554 176.5095 188.1250 158.9713 20250704 18.0 2.0 A/2019 Q2 MPC117072 + PK19S020 2029 06 21.3612 3.775711 0.204678 216.9312 93.1803 10.4637 20250704 13.5 4.0 P/2019 S2 (PANSTARRS) MPC117072 + PK19S030 2025 12 19.1677 1.807087 0.470749 213.0959 150.1407 8.6940 20250704 18.3 4.0 P/2019 S3 (PANSTARRS) MPEC 2022-CN4 + CK19S040 2020 04 9.3893 3.439097 0.986183 71.3706 63.1558 92.0955 20250704 11.0 4.0 C/2019 S4 (Lemmon) MPEC 2021-S45 + AK19T010 2021 01 14.9389 4.274749 0.889697 90.9821 6.9299 120.8206 20250704 13.0 2.0 A/2019 T1 MPEC 2023-N01 + CK19T020 2021 04 22.5147 2.643334 0.999228 239.3867 155.6546 111.3718 20250704 9.0 4.0 C/2019 T2 (Lemmon) MPEC 2023-R20 + CK19T030 2021 03 4.7246 5.953492 0.998707 112.4886 139.5435 121.8745 20250704 6.8 4.0 C/2019 T3 (ATLAS) MPEC 2023-UR6 + CK19T040 2022 06 8.6638 4.237537 0.995186 351.1087 199.9017 53.6246 20250704 5.0 4.0 C/2019 T4 (ATLAS) MPC182878 + PK19T050 2019 08 3.4432 1.523256 0.809776 189.6242 247.6127 33.4929 20250704 15.0 4.0 P/2019 T5 (ATLAS) MPEC 2021-P47 + PK19T060 2019 11 8.8876 2.054917 0.622457 329.0590 71.2477 18.6986 20250704 15.5 4.0 P/2019 T6 (PANSTARRS) MPEC 2021-P47 + PK19U040 2026 04 28.5243 1.844755 0.475747 181.0825 200.0015 11.6954 20250704 19.0 4.0 P/2019 U4 (PANSTARRS) MPC118096 + CK19U050 2023 03 29.4452 3.624255 1.000180 181.4498 2.6127 113.5125 20250704 4.5 4.0 C/2019 U5 (PANSTARRS) MPEC 2025-MC0 + CK19U060 2020 06 18.3188 0.906504 0.997015 329.4302 235.7500 60.9864 20250704 10.0 4.0 C/2019 U6 (Lemmon) MPEC 2022-H04 + CK19V010 2020 07 17.5719 3.092875 0.998825 51.1932 83.1481 61.9482 20250704 11.0 4.0 C/2019 V1 (Borisov) MPEC 2022-N37 + PK19V020 2020 10 17.2446 5.007460 0.331876 335.6331 189.1377 11.8069 20250704 10.0 4.0 P/2019 V2 (Groeller) MPEC 2022-L66 + PK19W010 2029 01 22.3031 3.333198 0.267194 18.8898 35.3616 23.4666 20250704 12.9 4.0 P/2019 W1 (PANSTARRS) MPEC 2023-A50 + PK19X010 2019 07 24.7030 4.301967 0.303829 36.9897 43.6770 10.2457 20250704 10.4 4.0 P/2019 X1 (Pruyne) MPEC 2021-P47 + PK19X020 2026 11 15.2889 1.815318 0.500474 213.5159 250.8309 15.8946 20250704 18.0 4.0 P/2019 X2 (Pan-STARRS) MPEC 2020-C98 + CK19Y010 2020 03 17.1972 0.826391 0.990629 57.9153 31.4771 73.2790 20250704 13.7 4.0 C/2019 Y1 (ATLAS) MPC119999 + CK19Y040 2020 05 29.6537 0.257236 0.999222 177.4097 120.7913 44.9348 20250704 11.8 6.0 C/2019 Y4 (ATLAS) MPEC 2024-A43 + CK19Y04a 2020 05 29.7075 0.255391 1.001364 177.2419 121.1590 45.3695 20250704 11.6 6.0 C/2019 Y4-A (ATLAS) MPEC 2020-L06 + CK19Y04b 2020 05 29.6623 0.256924 0.999811 177.3688 120.8545 45.0161 20250704 12.1 6.0 C/2019 Y4-B (ATLAS) MPEC 2025-CE3 + CK19Y04c 2020 05 29.6613 0.256463 1.002092 177.2746 120.8863 45.1533 20250704 12.7 6.0 C/2019 Y4-C (ATLAS) MPEC 2020-L06 + CK19Y04d 2020 05 29.7471 0.255786 0.996199 177.4177 121.2479 45.2063 20250704 12.5 6.0 C/2019 Y4-D (ATLAS) MPEC 2020-L06 + CK19Y050 2019 08 16.5695 4.933889 0.992819 303.6649 51.7668 82.7743 20250704 11.0 4.0 C/2019 Y5 (PANSTARRS) MPEC 2023-A50 + AK20A010 2019 11 30.2101 1.671654 0.934353 302.4016 119.0638 149.0316 20250704 18.0 2.0 A/2020 A1 MPEC 2023-A50 + CK20A020 2020 01 7.1186 0.975249 0.998989 68.0144 286.1891 120.5054 20250704 13.5 4.0 C/2020 A2 (Iwamoto) MPEC 2022-YN2 + CK20A030 2019 06 26.8752 5.753183 0.998860 268.2359 120.7985 146.6210 20250704 8.0 4.0 C/2020 A3 (ATLAS) MPEC 2023-A50 + PK20A040 2019 11 24.4624 2.834334 0.654470 144.9043 312.2812 25.0027 20250704 15.0 4.0 P/2020 A4 (PANSTARRS-Lemmon) MPEC 2022-P91 + AK20B010 2019 12 27.6508 1.739218 0.966608 154.8788 309.8032 18.5405 20250704 21.0 2.0 A/2020 B1 MPEC 2020-N08 + CK20B020 2020 01 27.2915 2.756049 0.959407 143.6281 354.1778 55.7550 20250704 10.0 4.0 C/2020 B2 (Lemmon) MPEC 2020-HN5 + CK20B030 2019 10 20.7757 3.327419 0.996833 324.9303 185.7465 20.7068 20250704 13.0 4.0 C/2020 B3 (Rankin) MPEC 2022-N37 + PK20B040 2021 11 19.3153 6.435367 0.192890 342.0503 185.9489 11.6031 20250704 10.5 4.0 P/2020 B4 (Sheppard) MPEC 2023-KD6 + CK20F020 2022 07 12.5203 8.813532 1.002600 48.2374 250.3008 163.5897 20250704 4.5 4.0 C/2020 F2 (ATLAS) MPC184409 + CK20F030 2020 07 4.9327 0.293493 0.999270 37.3485 61.0770 129.1144 20250704 7.5 5.2 C/2020 F3 (NEOWISE) MPEC 2021-O56 + CK20F050 2021 03 16.1872 4.326158 0.973664 310.6172 350.5414 52.2322 20250704 6.5 3.2 C/2020 F5 (MASTER) MPEC 2024-UQ8 + CK20F060 2020 04 10.3420 3.498170 0.989778 344.3346 207.8408 174.5842 20250704 14.5 2.8 C/2020 F6 (PANSTARRS) MPEC 2020-L06 + CK20F070 2021 11 13.8690 5.334920 0.990654 227.9832 321.8223 93.9823 20250704 7.0 4.0 C/2020 F7 (Lemmon) MPEC 2024-A43 + CK20F080 2020 05 25.8322 0.432700 1.000066 68.1111 259.8028 110.5565 20250704 10.0 4.0 C/2020 F8 (SWAN) MPEC 2023-J29 + PK20G010 2027 01 24.2733 0.501977 0.860814 207.6480 240.0986 18.5072 20250704 17.0 4.0 P/2020 G1 (Pimentel) MPEC 2020-L06 + CK20H020 2020 04 26.8894 0.828497 0.995322 26.5850 277.6716 124.7791 20250704 14.0 3.2 C/2020 H2 (Pruyne) MPEC 2022-YB4 + CK20H030 2020 06 5.7161 2.300288 1.000000 30.4456 270.6227 62.5292 13.5 4.0 C/2020 H3 (Wierzchos) MPEC 2020-HM1 + CK20H040 2020 08 29.2295 0.927483 0.980616 117.5769 307.4563 84.4946 20250704 15.0 3.2 C/2020 H4 (Leonard) MPEC 2020-L06 + CK20H050 2020 12 9.9606 9.335100 0.998435 326.2656 210.6147 70.2290 20250704 5.0 4.0 C/2020 H5 (Robinson) MPC184409 + CK20H060 2021 09 29.5794 4.696878 0.997639 20.1931 213.6921 79.9888 20250704 8.0 3.2 C/2020 H6 (ATLAS) MPEC 2024-JU4 + CK20H070 2020 06 2.9509 4.419545 0.996854 82.6780 323.5194 135.9235 11.0 4.0 C/2020 H7 (Lemmon) MPEC 2020-KB7 + CK20H080 2020 06 4.7913 4.663399 0.992103 128.8196 68.4385 99.7029 20250704 10.5 4.0 C/2020 H8 (PANSTARRS) MPEC 2021-N06 + AK20H090 2019 12 21.7839 2.562001 0.992501 312.6202 213.1196 137.8737 20250704 18.0 2.0 A/2020 H9 MPEC 2022-ED3 + CK20H110 2020 09 12.5557 7.621011 0.999752 91.3662 303.0571 151.3735 20250704 8.5 4.0 C/2020 H11 (PANSTARRS-Lemmon) MPEC 2023-HN7 + CK20J010 2021 04 18.0382 3.345139 0.999664 341.5800 226.5860 142.3072 20250704 8.5 3.2 C/2020 J1 (SONEAR) MPEC 2023-KD6 + CK20K010 2023 05 8.7544 3.074038 0.998740 213.9707 94.3664 89.6713 20250704 5.5 4.0 C/2020 K1 (PANSTARRS) MPC184409 + CK20K020 2020 08 4.4309 8.880287 1.000975 67.3102 288.4337 90.9888 20250704 10.8 4.0 C/2020 K2 (PANSTARRS) MPEC 2021-N06 + CK20K030 2020 06 1.0031 1.583069 1.000000 64.4924 28.3546 129.0152 14.5 4.0 C/2020 K3 (Leonard) MPEC 2020-KF9 + CK20K040 2020 03 4.9823 1.744028 0.927105 308.7843 264.2744 125.5850 20250704 16.5 4.0 C/2020 K4 (PANSTARRS) MPEC 2020-L06 + CK20K050 2021 06 4.2523 1.540685 1.000806 249.6415 86.1417 67.0686 20250704 11.0 4.0 C/2020 K5 (PANSTARRS) MPEC 2021-R75 + CK20K060 2021 09 14.7385 5.866114 1.002131 44.2782 291.5993 103.6306 20250704 8.0 4.0 C/2020 K6 (Rankin) MPEC 2023-N01 + CK20K070 2019 10 25.2971 6.388359 0.932501 358.0812 286.1322 32.0443 20250704 8.0 4.0 C/2020 K7 (PANSTARRS) MPEC 2023-A50 + CK20K080 2020 09 15.7041 0.471517 1.000318 260.1612 181.3013 31.3813 20250704 15.0 3.2 C/2020 K8 (Catalina-ATLAS) MPEC 2021-P47 + PK20K090 2029 09 29.3369 2.860423 0.320135 197.0903 166.3110 23.1904 20250704 12.5 4.0 P/2020 K9 (Lemmon-PANSTARRS) MPEC 2021-BE3 + PK20M010 2019 12 23.2268 2.796580 0.473521 72.4927 142.6150 8.5345 20250704 14.5 4.0 P/2020 M1 (PANSTARRS) MPEC 2023-C45 + CK20M030 2020 10 25.7447 1.275150 0.953299 328.6688 71.1765 23.4703 20250704 14.5 4.0 C/2020 M3 (ATLAS) MPEC 2022-H30 + AK20M040 2020 11 22.7831 5.940836 0.999750 104.4804 348.6144 160.1025 20250704 14.5 2.0 A/2020 M4 MPEC 2023-N01 + PK20M04K 2027 04 18.8851 6.130198 0.015095 93.5850 0.6643 6.7814 20250704 8.0 4.0 P/2020 MK4 (PANSTARRS) MPEC 2024-NE4 + CK20M050 2021 08 19.7509 2.999892 1.000120 126.2454 352.0194 93.1737 20250704 9.0 4.0 C/2020 M5 (ATLAS) MPEC 2023-FK0 + CK20N010 2021 03 13.1422 1.317603 1.000863 186.8357 279.8569 29.7659 20250704 12.5 4.0 C/2020 N1 (PANSTARRS) MPEC 2022-GA9 + CK20N020 2020 08 24.3134 1.783895 0.982399 331.2024 257.1794 161.0387 20250704 16.0 3.2 C/2020 N2 (ATLAS) MPEC 2021-P47 + CK20O020 2021 08 27.2803 4.856592 0.999607 10.1743 256.7913 71.7623 20250704 8.0 3.2 C/2020 O2 (Amaral) MPEC 2024-JU4 + PK20O030 2021 01 24.9718 4.170330 0.102414 81.1988 266.8180 8.4445 20250704 12.0 4.0 P/2020 O3 (PANSTARRS) MPEC 2023-C45 + CK20P010 2020 10 21.2082 0.341800 1.000437 8.9328 53.4879 45.1117 20250704 14.0 3.2 C/2020 P1 (NEOWISE) MPEC 2021-BE3 + CK20P030 2021 04 22.9255 6.816067 1.003695 82.3495 19.4842 61.8554 20250704 6.0 4.0 C/2020 P3 (ATLAS) MPEC 2024-JU4 + CK20P06V 2021 09 25.8054 2.291077 0.945003 71.2814 329.1285 128.1544 20250704 10.0 4.0 C/2020 PV6 (PANSTARRS) MPEC 2022-PB4 + CK20Q010 2020 08 15.3118 1.319387 0.978840 10.0289 52.4120 142.9230 20250704 14.0 4.0 C/2020 Q1 (Borisov) MPEC 2022-L66 + CK20Q020 2020 01 24.8104 5.419477 0.488831 118.2064 179.8272 3.3358 20250704 12.0 3.2 C/2020 Q2 (PANSTARRS) MPEC 2023-CD7 + CK20R020 2022 02 25.3556 4.699299 0.989082 211.8843 195.1268 53.2156 20250704 9.0 4.0 C/2020 R2 (PANSTARRS) MPEC 2024-F34 + CK20R040 2021 03 2.2096 1.020673 0.989503 46.5134 323.2334 164.4038 20250704 13.5 4.0 C/2020 R4 (ATLAS) MPEC 2022-K19 + PK20R050 2020 05 27.4464 3.429771 0.313126 82.7543 272.9384 11.4395 20250704 9.5 6.0 P/2020 R5 (PANSTARRS) MPEC 2023-C45 + CK20R060 2019 09 6.8288 3.139433 0.989213 271.9979 12.2354 82.8913 20250704 11.0 4.0 C/2020 R6 (Rankin) MPEC 2021-Y10 + CK20R070 2022 09 16.0347 2.951825 0.999647 347.7610 268.3097 114.9031 20250704 7.0 3.2 C/2020 R7 (ATLAS) MPEC 2024-PC5 + PK20S010 2021 01 16.9119 2.959814 0.506859 255.1634 129.4907 13.7148 20250704 14.0 4.0 P/2020 S1 (PANSTARRS) MPEC 2021-BE3 + CK20S020 2020 12 22.0380 1.763836 0.827933 202.4247 197.7094 22.3749 20250704 17.0 4.0 C/2020 S2 (PANSTARRS) MPEC 2022-ST7 + CK20S030 2020 12 11.3747 0.392596 0.997222 350.0484 222.5184 20.0662 20250704 13.5 3.2 C/2020 S3 (Erasmus) MPEC 2024-JU4 + CK20S040 2023 02 9.5797 3.370440 1.002743 21.0598 117.6825 20.5701 20250704 8.5 3.2 C/2020 S4 (PANSTARRS) MPEC 2024-N80 + PK20S050 2028 10 11.3241 2.689414 0.337333 53.2758 316.0205 12.3402 20250704 14.5 4.0 P/2020 S5 (PANSTARRS) MPEC 2021-BE3 + PK20S070 2020 11 17.5411 2.974214 0.409502 40.6632 328.0828 16.0702 20250704 14.5 4.0 P/2020 S7 (PANSTARRS) MPEC 2021-BE3 + CK20S080 2021 04 10.3604 2.355653 0.990150 160.1292 24.0082 108.5435 20250704 12.5 4.0 C/2020 S8 (Lemmon) MPEC 2021-P47 + CK20T020 2021 07 10.5646 2.052449 0.992378 150.3455 83.0341 27.8396 20250704 11.0 3.2 C/2020 T2 (Palomar) MPEC 2022-TD3 + PK20T030 2027 08 27.4539 1.433027 0.592436 357.0804 73.9918 7.2985 20250704 18.0 3.2 P/2020 T3 (PANSTARRS) MPEC 2021-N06 + CK20T040 2021 07 6.0946 2.187607 1.000649 79.5700 50.6069 83.8279 20250704 13.0 3.2 C/2020 T4 (PANSTARRS) MPEC 2021-N06 + CK20T050 2020 10 7.7313 1.897925 0.996874 90.3842 237.8435 66.5575 20250704 16.0 4.0 C/2020 T5 (Lemmon) MPEC 2021-BE3 + PK20U020 2028 05 1.4747 1.846108 0.511336 84.7713 342.8164 6.4197 20250704 18.0 4.0 P/2020 U2 (PANSTARRS) MPEC 2021-N06 + CK20U030 2021 02 6.0002 2.285696 0.966220 124.5156 282.6001 30.1388 20250704 15.0 4.0 C/2020 U3 (Rankin) MPEC 2021-W31 + CK20U040 2022 04 10.0126 5.361889 1.001223 70.1748 120.4059 167.0033 20250704 7.0 4.0 C/2020 U4 (PANSTARRS) MPEC 2024-TD8 + CK20U050 2022 04 28.3828 3.756830 0.999662 75.4662 107.3132 97.3120 20250704 8.0 4.0 C/2020 U5 (PANSTARRS) MPEC 2024-GJ3 + CK20V020 2023 05 8.5256 2.229299 1.001058 162.4581 212.3997 131.6122 20250704 4.9 4.0 C/2020 V2 (ZTF) MPEC 2025-MC0 + PK20V030 2021 02 15.6639 6.239704 0.257885 249.8046 198.2690 23.0210 20250704 8.3 4.0 P/2020 V3 (PANSTARRS) MPEC 2023-D72 + PK20V040 2021 07 20.7006 5.154005 0.451595 257.2525 203.4888 14.2369 20250704 9.0 4.0 P/2020 V4 (Rankin) MPEC 2024-F34 + PK20W010 2020 04 10.3401 5.307780 0.265465 265.3943 124.3860 10.7772 20250704 10.0 4.0 P/2020 W1 (Rankin) MPEC 2021-BE3 + CK20W050 2020 11 30.9310 3.370888 1.002161 24.6067 75.4673 88.6154 20250704 15.0 4.0 C/2020 W5 (Lemmon) MPEC 2021-BE3 + PK20W05J 2021 06 30.5605 4.980074 0.172131 338.0873 177.7635 22.2881 20250704 8.5 4.0 P/2020 WJ5 (Lemmon) MPEC 2024-PC5 + PK20X010 2030 03 18.8489 2.883239 0.364395 323.5276 55.9877 31.6916 20250704 13.0 4.0 P/2020 X1 (ATLAS) MPEC 2024-F34 + CK20X020 2020 11 17.1899 3.832357 0.768324 347.5704 105.3559 18.1866 20250704 10.6 4.0 C/2020 X2 (ATLAS) MPEC 2024-A43 + CK20X040 2020 11 15.4324 5.224026 0.871284 140.2915 161.9550 80.6583 20250704 9.0 4.0 C/2020 X4 (Leonard) MPEC 2021-S45 + CK20Y020 2022 06 17.7716 3.146244 0.997528 266.4145 26.5393 101.2129 20250704 6.5 4.0 C/2020 Y2 (ATLAS) MPEC 2024-YC7 + CK20Y030 2020 12 3.2276 1.990305 0.985526 341.8505 191.3447 83.1438 20250704 13.5 4.0 C/2020 Y3 (ATLAS) MPEC 2021-R75 + CK21A010 2022 01 3.8142 0.615358 1.000244 225.1364 255.9111 132.7537 20250704 8.5 4.0 C/2021 A1 (Leonard) MPEC 2025-A40 + CK21A020 2021 01 21.8720 1.416278 0.993828 338.7999 125.0618 107.0546 20250704 13.5 4.0 C/2021 A2 (NEOWISE) MPEC 2025-A40 + CK21A040 2021 03 19.5786 1.150357 0.972951 204.7541 307.0895 111.6476 20250704 16.0 4.0 C/2021 A4 (NEOWISE) MPEC 2022-ED3 + PK21A050 2026 03 11.2834 2.620511 0.139793 61.5372 328.8096 18.1895 20250704 15.0 4.0 P/2021 A5 (PANSTARRS) MPEC 2021-BE3 + CK21A060 2021 05 3.0775 7.924774 0.999352 351.6259 164.0250 75.5636 20250704 7.0 4.0 C/2021 A6 (PANSTARRS) MPEC 2024-P23 + CK21A070 2021 07 15.1593 1.965197 0.998959 356.0011 154.4016 78.2184 20250704 10.0 4.0 C/2021 A7 (NEOWISE) MPEC 2022-M88 + CK21A090 2023 12 3.9992 7.763845 1.000054 211.6379 314.8536 158.0181 20250704 6.0 4.0 C/2021 A9 (PANSTARRS) MPC182879 + CK21A100 2021 03 14.7158 1.266804 0.985879 82.6460 188.8412 151.9954 20250704 19.0 4.0 C/2021 A10 (NEOWISE) MPEC 2021-N06 + CK21B020 2021 05 4.8499 2.515015 0.993848 335.1197 120.4382 38.0870 20250704 14.0 4.0 C/2021 B2 (PANSTARRS) MPEC 2022-L66 + CK21B030 2021 03 9.2836 2.168354 0.936640 293.6046 67.2827 119.4777 20250704 13.5 4.0 C/2021 B3 (NEOWISE) MPEC 2021-N06 + CK21C010 2020 12 5.7192 3.472904 0.998096 336.0583 186.8266 143.0431 20250704 11.5 4.0 C/2021 C1 (Rankin) MPEC 2023-KD6 + PK21C020 2021 02 24.6427 4.883747 0.488383 78.7235 66.4553 21.9382 20250704 12.0 4.0 P/2021 C2 (PANSTARRS) MPEC 2021-U31 + CK21C030 2021 02 11.0920 2.274153 0.962361 356.9752 181.8517 122.2084 20250704 14.0 4.0 C/2021 C3 (Catalina) MPEC 2024-M41 + CK21C040 2021 01 16.1602 4.493409 0.998805 320.0246 194.2280 132.8314 20250704 9.0 4.0 C/2021 C4 (ATLAS) MPEC 2022-M88 + CK21C050 2023 02 10.9800 3.240329 0.998099 270.8890 323.6736 50.8029 20250704 9.0 4.0 C/2021 C5 (PANSTARRS) MPEC 2024-N80 + CK21C060 2021 11 11.8895 3.284711 0.998782 203.8606 332.3259 164.6092 20250704 12.0 4.0 C/2021 C6 (Lemmon) MPEC 2022-YB4 + CK21D010 2021 02 27.3342 0.908198 0.991099 72.4617 311.1614 31.3554 20250704 13.0 4.0 C/2021 D1 (SWAN) MPEC 2022-F14 + CK21D020 2022 02 3.6408 2.949603 1.001428 125.0680 305.6277 83.7716 20250704 9.0 4.0 C/2021 D2 (ZTF) MPEC 2023-J29 + AK21E020 2020 12 8.9249 2.283019 0.988595 342.2188 190.7499 167.4938 20250704 15.0 2.0 A/2021 E2 MPEC 2022-UY9 + CK21E030 2022 06 11.1215 1.777504 0.999839 228.7998 104.4839 112.5248 20250704 8.5 4.0 C/2021 E3 (ZTF) MPEC 2024-GJ3 + AK21E040 2022 04 24.8287 4.679884 0.990720 48.2831 171.1410 116.3819 20250704 13.5 2.0 A/2021 E4 MPEC 2024-N80 + CK21F010 2022 04 6.7366 0.999262 0.995978 146.9463 203.5500 107.2905 20250704 13.5 4.0 C/2021 F1 (Lemmon-PANSTARRS) MPEC 2022-QD9 + CK21G010 2021 07 20.3378 3.427911 0.951757 107.4352 270.6976 131.5468 20250704 14.0 4.0 C/2021 G1 (Leonard) MPEC 2021-J72 + CK21G020 2024 09 9.1356 4.982275 1.000733 343.2665 221.0945 48.4667 20250704 5.5 4.0 C/2021 G2 (ATLAS) MPEC 2025-MC0 + CK21G030 2021 10 17.8544 5.182610 0.999412 10.5984 147.3452 102.8729 20250704 10.5 4.0 C/2021 G3 (PANSTARRS) MPEC 2022-X67 + PK21H00S 2021 08 4.7430 0.799039 0.809451 46.1180 262.3573 12.1542 20250704 22.0 4.0 P/2021 HS (PANSTARRS) MPEC 2021-Y10 + CK21J010 2021 02 19.4250 1.733825 0.933812 147.1970 88.4324 92.7076 20250704 15.5 4.0 C/2021 J1 (Maury-Attard) MPEC 2022-C56 + CK21J020 2021 09 20.7566 4.701501 0.957931 171.8828 23.3089 156.2116 20250704 12.0 4.0 C/2021 J2 (PANSTARRS) MPEC 2023-XP6 + PK21J030 2019 06 30.3281 4.894588 0.449410 125.6278 110.9981 14.5149 20250704 7.0 4.0 P/2021 J3 (ATLAS) MPEC 2024-F34 + CK21K010 2021 05 2.3406 2.502187 0.801480 184.2229 140.9240 16.2711 20250704 11.0 4.0 C/2021 K1 (ATLAS) MPEC 2022-O08 + CK21K020 2021 09 9.2384 5.463622 1.000445 343.2761 282.3377 100.8713 20250704 8.0 4.0 C/2021 K2 (MASTER) MPEC 2022-O01 + CK21K030 2022 02 3.6382 5.227551 1.004184 182.0124 114.6085 134.7805 20250704 10.0 4.0 C/2021 K3 (Catalina) MPEC 2022-L66 + PK21L020 2021 07 22.8083 1.939405 0.520831 51.4302 266.6527 21.0644 20250704 17.0 4.0 P/2021 L2 (Leonard) MPEC 2021-W31 + CK21L030 2022 02 14.9960 8.460324 1.004544 91.6514 345.0173 78.5377 20250704 6.0 4.0 C/2021 L3 (Borisov) MPEC 2024-H50 + PK21N010 2026 07 27.8469 0.966268 0.675728 21.2255 301.1350 11.4856 20250704 19.0 4.0 P/2021 N1 (ZTF) MPEC 2022-TA0 + PK21N020 2021 11 14.1542 3.805969 0.452131 177.6306 221.7434 13.0601 20250704 9.5 4.0 P/2021 N2 (Fuls) MPEC 2024-GJ3 + CK21N030 2020 08 16.8832 5.711942 0.959308 304.5965 337.5267 26.7638 20250704 8.5 4.0 C/2021 N3 (PANSTARRS) MPEC 2022-YB4 + CK21O010 2021 08 14.7769 0.782739 0.999844 74.4291 41.5402 27.5698 20250704 10.5 4.0 C/2021 O1 (Nishimura) MPEC 2022-A21 + CK21O030 2022 04 21.2907 0.285089 1.000052 300.0216 188.7830 56.8286 20250704 10.5 4.0 C/2021 O3 (PANSTARRS) MPEC 2022-L66 + CK21P010 2022 06 2.5650 4.379761 0.998370 40.5261 359.7121 51.6199 20250704 11.0 4.0 C/2021 P1 (PANSTARRS) MPEC 2024-F34 + CK21P020 2023 01 23.0774 5.067924 0.999623 76.7154 32.0950 150.0547 20250704 9.0 4.0 C/2021 P2 (PANSTARRS) MPEC 2025-MC0 + PK21P030 2021 05 28.2935 2.919152 0.338380 334.0053 358.2478 27.1605 20250704 14.0 4.0 P/2021 P3 (PANSTARRS) MPEC 2024-GJ3 + CK21P040 2022 07 30.4288 1.078600 0.996358 175.8085 348.0064 56.3760 20250704 9.5 4.0 C/2021 P4 (ATLAS) MPEC 2023-A50 + PK21P20E 2028 09 4.4526 1.236194 0.669982 210.4321 99.6248 20.0000 20250704 17.0 4.0 P/2021 PE20 (ATLAS) MPEC 2023-E68 + CK21Q030 2022 01 26.0565 5.208913 0.930604 114.1463 307.9090 77.7158 20250704 8.0 4.0 C/2021 Q3 (ATLAS) MPEC 2023-FK0 + CK21Q040 2023 06 11.0370 7.565011 1.001614 147.0530 183.3298 71.5337 20250704 6.0 4.0 C/2021 Q4 (Fuls) MPEC 2025-A40 + PK21Q050 2027 08 17.0033 1.234035 0.624562 180.9579 239.7553 10.7382 20250704 15.0 4.0 P/2021 Q5 (ATLAS) MPEC 2022-C56 + CK21Q060 2024 03 25.2336 8.707744 1.002838 141.0647 133.5742 161.8260 20250704 6.0 4.0 C/2021 Q6 (PANSTARRS) MPEC 2024-UA9 + CK21Q45M 2022 08 13.6780 2.778247 0.993214 72.9232 354.5961 22.7983 20250704 11.0 4.0 C/2021 QM45 (PANSTARRS) MPEC 2023-FK0 + PK21R010 2021 12 8.5041 4.884597 0.408060 220.0353 143.1025 5.5335 20250704 11.0 4.0 P/2021 R1 (PANSTARRS) MPEC 2022-X67 + CK21R020 2021 12 28.4772 7.316486 0.999346 32.5533 16.3386 134.4820 20250704 7.5 4.0 C/2021 R2 (PANSTARRS) MPEC 2022-X67 + PK21R030 2028 09 17.5750 2.519301 0.331596 2.5866 304.1946 19.9420 20250704 16.0 4.0 P/2021 R3 (PANSTARRS) MPEC 2021-W31 + PK21R040 2021 10 13.3912 2.334057 0.585257 56.7782 321.2812 21.0114 20250704 16.0 4.0 P/2021 R4 (Wierzchos) MPEC 2021-W31 + PK21R050 2022 01 12.3702 3.330204 0.305927 167.6071 219.9623 7.8538 20250704 12.0 4.0 P/2021 R5 (Rankin) MPEC 2024-JU4 + PK21R060 2021 10 31.9129 2.559544 0.593021 220.8822 176.1615 34.8907 20250704 14.5 4.0 P/2021 R6 (Groeller) MPEC 2021-W31 + CK21R070 2021 04 17.3513 5.654716 0.994371 140.4006 170.2027 158.8754 20250704 10.5 4.0 C/2021 R7 (PANSTARRS) MPEC 2022-X67 + PK21R080 2027 01 5.7909 2.136721 0.292540 190.8186 167.0654 2.2027 20250704 18.5 4.0 P/2021 R8 (Sheppard) MPEC 2021-Y10 + CK21S010 2022 03 2.0151 6.125248 1.002903 148.3107 299.8557 52.0377 20250704 7.0 4.0 C/2021 S1 (ATLAS) MPEC 2023-J29 + CK21S030 2024 02 14.6701 1.319744 1.000004 6.8362 215.6070 58.5399 20250704 5.5 4.0 C/2021 S3 (PANSTARRS) MPEC 2025-MC0 + CK21S040 2024 01 3.8416 6.691901 0.957113 73.0460 5.4509 17.4797 20250704 6.5 4.0 C/2021 S4 (Tsuchinshan) MPC184409 + CK21T010 2021 10 14.8778 3.060315 0.998933 51.5822 56.8481 140.3518 20250704 12.5 4.0 C/2021 T1 (Lemmon) MPEC 2022-OB6 + CK21T020 2022 06 8.3358 1.244080 1.000536 263.5264 223.2067 117.5113 20250704 12.0 4.0 C/2021 T2 (Fuls) MPEC 2023-A50 + CK21T040 2023 07 31.5120 1.481465 0.999689 329.7695 257.8896 160.7784 20250704 7.5 4.0 C/2021 T4 (Lemmon) MPC184409 + PK21T81R 2022 04 3.6268 1.464781 0.833043 272.0088 220.1746 36.8139 20250704 15.6 4.0 P/2021 TR81 (Lemmon) MPC184409 + PK21U010 2021 09 30.7382 2.454061 0.712639 145.2383 246.7949 30.5513 20250704 14.5 4.0 P/2021 U1 (Wierzchos) MPEC 2022-ED3 + PK21U030 2021 10 24.8612 1.891208 0.549396 335.3262 75.0942 69.9614 20250704 15.5 4.0 P/2021 U3 (Attard-Maury) MPEC 2022-L66 + CK21U040 2021 12 22.5746 1.787222 0.960719 237.3225 241.8054 152.8822 20250704 17.0 4.0 C/2021 U4 (Leonard) MPEC 2021-W31 + CK21U050 2022 01 26.9976 2.359095 0.989400 321.4625 182.6754 39.0400 20250704 13.0 4.0 C/2021 U5 (Catalina) MPEC 2022-WQ9 + CK21V010 2022 04 30.6121 3.019281 0.995799 195.2172 207.6992 71.4349 20250704 13.0 4.0 C/2021 V1 (Rankin) MPEC 2022-CN4 + PK21V020 2023 01 21.9962 3.497406 0.615277 259.9068 232.2763 12.6927 20250704 10.0 4.0 P/2021 V2 (Fuls) MPEC 2024-JU4 + CK21X010 2023 05 27.2901 3.234628 1.000615 334.6179 10.6165 140.1073 20250704 7.0 4.0 C/2021 X1 (Maury-Attard) MPEC 2024-TD8 + CK21X020 2022 07 8.3851 2.998044 1.001534 193.3872 228.8427 137.1535 20250704 13.0 4.0 C/2021 X2 (Bok) MPEC 2024-E08 + CK21Y010 2023 04 30.9362 2.032478 1.001594 245.8496 244.7667 77.1869 20250704 7.0 4.0 C/2021 Y1 (ATLAS) MPEC 2024-GJ3 + CK22A010 2022 01 31.1418 1.256163 0.996625 201.2838 285.4928 116.5732 20250704 18.0 4.0 C/2022 A1 (Sarneczky) MPEC 2022-YN2 + CK22A020 2023 02 18.1847 1.735350 1.000065 88.3668 171.6052 108.1702 20250704 9.5 4.0 C/2022 A2 (PANSTARRS) MPEC 2024-P23 + CK22A030 2023 09 28.9640 3.704424 0.995876 234.8720 325.4572 88.3503 20250704 8.0 4.0 C/2022 A3 (Lemmon-ATLAS) MPEC 2024-UQ8 + PK22B010 2022 02 26.0285 1.894386 0.653633 148.9388 325.3811 10.9946 20250704 16.5 4.0 P/2022 B1 (Wierzchos) MPEC 2022-K19 + AK22B030 2022 01 16.7065 3.704409 0.994159 150.7201 286.1758 132.0507 20250704 16.5 2.0 A/2022 B3 MPEC 2022-YB4 + CK22B040 2022 01 30.4540 1.375920 0.996618 153.0252 340.5139 20.0576 20250704 21.0 4.0 C/2022 B4 (Bok) MPEC 2022-GA9 + PK22B09V 2029 12 6.0632 3.346234 0.233531 16.3089 337.3083 11.9237 20250704 9.5 4.0 P/2022 BV9 (Lemmon) MPEC 2023-J29 + PK22C010 2021 11 5.5203 3.985170 0.449139 9.4620 113.0992 4.7631 20250704 12.0 4.0 P/2022 C1 (PANSTARRS) MPEC 2023-J29 + PK22C020 2022 08 5.9112 3.366458 0.442000 89.1359 135.2627 9.9847 20250704 12.5 4.0 P/2022 C2 (PANSTARRS) MPEC 2023-VM5 + PK22C030 2022 06 30.2029 4.370405 0.545499 93.8037 139.0408 12.8249 20250704 11.5 4.0 P/2022 C3 (PANSTARRS) MPEC 2023-UR6 + PK22D010 2021 08 28.8099 3.347438 0.548001 88.6639 47.9473 44.0661 20250704 12.5 4.0 P/2022 D1 (PANSTARRS) MPEC 2022-K19 + CK22D020 2022 03 28.0566 1.552663 0.996108 177.8559 312.3593 22.6810 20250704 17.0 4.0 C/2022 D2 (Kowalski) MPEC 2022-K19 + PK22E010 2022 06 9.2835 2.944589 0.220573 114.8949 113.3413 19.0070 20250704 13.5 4.0 P/2022 E1 (Christensen) MPEC 2022-L66 + CK22E020 2024 09 14.1421 3.666511 1.000359 41.7494 125.3976 137.1410 20250704 5.0 4.0 C/2022 E2 (ATLAS) MPEC 2025-MC0 + CK22E030 2023 01 12.5097 1.114248 0.999994 145.8287 302.5074 109.1755 20250704 7.5 4.0 C/2022 E3 (ZTF) MPEC 2024-GJ3 + CK22F010 2022 08 5.9450 5.977908 0.999565 278.3546 350.6349 58.0023 20250704 7.0 4.0 C/2022 F1 (ATLAS) MPEC 2024-PC5 + CK22F020 2022 03 22.3396 1.589422 0.933119 200.5909 58.7818 97.3178 20250704 14.5 4.0 C/2022 F2 (NEOWISE) MPEC 2022-QD9 + CK22H010 2024 01 18.6502 7.689149 0.990981 246.2925 6.3259 49.8602 20250704 6.0 4.0 C/2022 H1 (PANSTARRS) MPEC 2025-MC0 + CK22J010 2022 02 19.3501 1.599969 0.966310 305.6089 280.8034 105.9596 20250704 14.9 4.0 C/2022 J1 (Maury-Attard) MPEC 2022-VC5 + CK22J020 2022 10 26.6965 1.828383 0.979687 133.1518 252.6860 149.1418 20250704 9.0 4.0 C/2022 J2 (Bok) MPEC 2023-M14 + CK22J05K 2023 04 28.9386 2.695676 0.938550 247.3848 59.6520 16.8246 20250704 11.0 4.0 C/2022 JK5 (PANSTARRS) MPEC 2024-YC7 + CK22K010 2021 12 16.5892 3.985805 1.000825 142.5435 136.3604 41.9745 20250704 11.0 4.0 C/2022 K1 (Leonard) MPEC 2022-ST7 + CK22L010 2022 09 27.7105 1.591077 0.996242 59.8023 300.0318 123.4388 20250704 15.8 4.0 C/2022 L1 (Catalina) MPEC 2023-CD7 + CK22L020 2024 03 12.1945 2.693409 1.000833 199.9256 39.2453 129.3124 20250704 6.5 4.0 C/2022 L2 (ATLAS) MPC184409 + PK22L030 2022 10 29.8422 2.424040 0.627436 10.4139 29.8241 21.5373 20250704 16.5 4.0 P/2022 L3 (ATLAS) MPEC 2024-DC6 + CK22L040 2021 12 9.0776 3.008548 0.989321 125.2487 66.0608 141.2435 20250704 14.0 4.0 C/2022 L4 (PANSTARRS) MPEC 2022-N37 + CK22N010 2022 09 9.7444 1.479131 0.959586 40.9945 301.8787 164.7267 20250704 16.9 4.0 C/2022 N1 (Attard-Maury) MPEC 2024-GJ3 + CK22N020 2025 07 31.8046 3.825367 1.003323 75.3989 319.7398 5.5029 20250704 6.0 4.0 C/2022 N2 (PANSTARRS) MPEC 2025-MC0 + CK22O010 2022 02 15.3679 7.434939 1.001276 268.9416 49.9109 71.0515 20250704 6.0 4.0 C/2022 O1 (ATLAS) MPEC 2024-A43 + PK22O020 2023 01 6.7180 1.759469 0.720948 48.6680 330.4913 9.4184 20250704 16.2 4.0 P/2022 O2 (PANSTARRS) MPEC 2023-HD1 + CK22P010 2022 11 28.7085 1.592236 0.913784 249.8733 205.0682 154.5866 20250704 13.0 4.0 C/2022 P1 (NEOWISE) MPEC 2023-N01 + PK22P020 2022 07 11.0347 1.985417 0.557990 137.7754 291.1733 12.4410 20250704 12.5 4.0 P/2022 P2 (ZTF) MPEC 2023-XP6 + CK22P030 2022 07 27.5278 2.566469 0.990270 0.2220 72.2192 59.5161 20250704 9.0 4.0 C/2022 P3 (ZTF) MPEC 2023-HD1 + CK22Q020 2023 01 31.7249 1.641602 0.949925 44.0300 352.9619 151.4579 20250704 13.0 4.0 C/2022 Q2 (ATLAS) MPEC 2023-R20 + CK22Q78E 2025 09 11.6886 5.475887 1.002731 0.5925 119.8879 36.6198 20250704 5.0 4.0 C/2022 QE78 (ATLAS) MPC184410 + PK22R010 2023 10 4.2045 3.565164 0.500915 221.7755 175.6611 7.3786 20250704 11.5 4.0 P/2022 R1 (PANSTARRS) MPEC 2024-M41 + CK22R020 2022 10 25.5632 0.630183 0.998567 78.3206 60.3914 52.8923 20250704 17.0 4.0 C/2022 R2 (ATLAS) MPEC 2022-Y15 + CK22R030 2023 03 5.9260 5.132158 1.001528 72.9347 8.2596 43.0714 20250704 9.0 4.0 C/2022 R3 (Leonard) MPC184410 + PK22R040 2022 07 9.8620 1.959824 0.489444 197.4956 176.6351 21.0089 20250704 16.5 4.0 P/2022 R4 (PANSTARRS) MPEC 2022-X67 + PK22R050 2027 10 12.0640 2.472150 0.194724 240.5381 115.0427 15.2923 20250704 16.0 4.0 P/2022 R5 (PANSTARRS) MPEC 2022-WQ9 + CK22R060 2025 08 26.2396 6.565529 1.005046 319.9189 150.7851 57.0196 20250704 5.0 4.0 C/2022 R6 (PANSTARRS) MPEC 2025-MC0 + PK22S010 2022 08 19.0045 3.155652 0.507605 262.8470 136.0898 34.5668 20250704 15.1 4.0 P/2022 S1 (PANSTARRS) MPEC 2023-HD1 + CK22S030 2023 01 21.6194 0.838803 1.000382 267.9876 157.2489 78.4810 20250704 17.0 4.0 C/2022 S3 (PANSTARRS) MPEC 2022-VC5 + CK22S040 2024 07 18.7856 2.761849 0.998034 268.5624 220.1786 101.2149 20250704 8.0 4.0 C/2022 S4 (Lemmon) MPEC 2025-MC0 + CK22S050 2022 11 27.7907 2.177875 0.893860 232.7987 214.8653 136.5106 20250704 16.3 4.0 C/2022 S5 (PANSTARRS) MPEC 2023-HD1 + CK22T010 2024 02 17.4425 3.444267 1.000378 324.2927 236.9153 22.5420 20250704 9.0 4.0 C/2022 T1 (Lemmon) MPEC 2024-O39 + CK22U010 2024 03 26.1000 4.202267 1.000241 78.6136 72.5280 128.1479 20250704 8.5 4.0 C/2022 U1 (Leonard) MPEC 2025-MC0 + CK22U020 2023 01 14.2728 1.329705 0.986477 148.0124 304.4029 48.2500 20250704 16.0 4.0 C/2022 U2 (ATLAS) MPEC 2023-VM5 + CK22U030 2024 07 28.6603 4.826863 1.000109 189.1335 272.7881 33.6617 20250704 7.5 4.0 C/2022 U3 (Bok) MPC182880 + CK22U040 2023 08 3.6443 2.897266 0.998997 88.9847 132.9163 52.0532 20250704 10.5 4.0 C/2022 U4 (Bok) MPEC 2023-W26 + CK22V020 2023 11 1.8509 2.064243 0.943667 168.9549 332.8539 98.9023 20250704 12.0 4.0 C/2022 V2 (Lemmon) MPEC 2024-H50 + PK22W010 2022 09 16.1266 3.372906 0.516466 17.9321 38.8300 13.4639 20250704 12.5 4.0 P/2022 W1 (Rankin) MPEC 2023-CD7 + CK22W020 2023 03 8.7352 3.124942 0.990880 123.3162 320.4358 63.5016 20250704 11.5 4.0 C/2022 W2 (ATLAS) MPEC 2024-EF7 + CK22W030 2023 06 22.8265 1.396841 0.994974 116.5117 132.3045 103.5819 20250704 13.0 4.0 C/2022 W3 (Leonard) MPEC 2024-C04 + CK22Y010 2022 11 27.6883 2.960617 0.765318 174.8843 285.8762 18.8559 20250704 9.0 4.0 C/2022 Y1 (Hogan) MPEC 2023-M14 + CK22Y020 2023 03 22.4395 2.542229 0.871155 105.4842 216.3761 165.8929 20250704 13.5 4.0 C/2022 Y2 (Lemmon) MPEC 2023-TM6 + CK23A010 2023 03 18.5831 1.836136 0.991701 159.2648 318.2648 94.7417 20250704 14.5 4.0 C/2023 A1 (Leonard) MPEC 2024-GJ3 + CK23A020 2023 01 20.3637 0.944940 0.997672 142.4921 94.5091 94.7061 20250704 13.5 4.0 C/2023 A2 (SWAN) MPEC 2023-J95 + CK23A030 2024 09 27.7435 0.391520 1.000125 308.5099 21.5757 139.1111 20250704 6.5 3.2 C/2023 A3 (Tsuchinshan-ATLAS) MPEC 2025-MC0 + PK23B010 2023 05 3.9468 6.140676 0.130968 81.7191 78.5602 14.5883 20250704 5.5 4.0 P/2023 B1 (PANSTARRS) MPEC 2024-F34 + CK23B020 2023 03 10.6140 1.740561 0.997084 317.3632 218.0888 40.7667 20250704 14.5 4.0 C/2023 B2 (ATLAS) MPEC 2023-XP6 + PK23B030 2020 09 5.8992 3.993706 0.122346 240.3829 153.9850 9.1565 20250704 10.5 4.0 P/2023 B3 (PANSTARRS) MPEC 2023-F81 + CK23C020 2024 11 16.7815 2.368525 0.999018 357.4459 301.0046 48.3218 20250704 7.0 4.0 C/2023 C2 (ATLAS) MPEC 2025-MC0 + CK23E010 2023 06 30.8505 1.027485 0.946621 105.9480 164.5198 38.2815 20250704 15.5 4.0 C/2023 E1 (ATLAS) MPEC 2024-D33 + CK23F010 2023 06 28.0793 1.710270 0.993014 216.7324 25.3070 131.6949 20250704 16.0 4.0 C/2023 F1 (PANSTARRS) MPEC 2023-N01 + CK23F030 2025 02 2.6219 5.190795 1.003373 265.5327 109.4658 145.9635 20250704 6.0 4.0 C/2023 F3 (ATLAS) MPEC 2025-MC0 + CK23H010 2024 11 28.6296 4.447566 0.994127 333.7505 292.6468 21.7829 20250704 8.5 4.0 C/2023 H1 (PANSTARRS) MPEC 2025-MC0 + CK23H020 2023 10 29.1587 0.895309 0.996384 150.6892 217.0742 113.7470 20250704 14.0 4.0 C/2023 H2 (Lemmon) MPEC 2024-GJ3 + CK23H030 2024 02 18.2418 5.231467 0.615815 193.2570 55.0918 2.4885 20250704 10.0 4.0 C/2023 H3 (PANSTARRS) MPEC 2025-MC0 + AK23H040 2023 08 8.6810 2.124150 0.985014 65.0171 230.8265 76.5682 20250704 18.0 2.0 A/2023 H4 MPEC 2023-SQ0 + CK23H050 2025 06 30.2873 4.312581 1.000459 60.1010 159.4783 97.8553 20250704 7.0 4.0 C/2023 H5 (Lemmon) MPEC 2025-MC0 + PK23J16N 2024 12 30.8345 2.299815 0.146984 353.2257 11.8706 3.7020 20250704 14.0 4.0 P/2023 JN16 (Lemmon) MPEC 2024-UA9 + CK23K010 2023 09 7.5638 2.038743 0.996702 337.4181 223.6981 137.9976 20250704 13.0 4.0 C/2023 K1 (ATLAS) MPEC 2024-GJ3 + PK23M010 2023 12 14.3144 2.826759 0.586793 79.7001 216.8599 12.2889 20250704 13.5 4.0 P/2023 M1 (PANSTARRS) MPEC 2023-N01 + PK23M020 2023 07 27.6464 3.516484 0.369977 243.5049 83.2510 19.7267 20250704 12.5 4.0 P/2023 M2 (PANSTARRS) MPEC 2024-TD8 + PK23M040 2022 04 13.5970 3.927093 0.278931 320.5126 296.2831 7.5919 20250704 7.5 4.0 P/2023 M4 (ATLAS) MPEC 2024-TP3 + CK23P010 2023 09 17.6162 0.224383 0.996021 116.2496 66.8303 132.4780 20250704 10.0 4.0 C/2023 P1 (Nishimura) MPEC 2024-MB8 + CK23Q010 2024 12 1.1250 2.575812 1.004959 84.4184 7.1238 36.6450 20250704 10.0 4.0 C/2023 Q1 (PANSTARRS) MPEC 2025-MC0 + CK23Q020 2024 06 23.9401 3.209063 0.990664 171.6897 92.6798 104.0619 20250704 11.5 4.0 C/2023 Q2 (PANSTARRS) MPEC 2024-N80 + CK23R010 2026 04 13.4748 3.569846 1.002235 144.2726 62.5627 149.3169 20250704 6.0 4.0 C/2023 R1 (PANSTARRS) MPEC 2025-MC0 + CK23R020 2024 08 12.1612 0.905076 1.000285 337.3140 188.8979 30.6895 20250704 10.5 4.0 C/2023 R2 (PANSTARRS) MPEC 2024-L77 + AK23R030 2023 12 18.1786 1.358744 0.998114 86.9456 347.3401 12.0804 20250704 20.0 2.0 A/2023 R3 MPEC 2023-UR6 + CK23R03N 2023 01 20.5247 5.180711 0.490550 130.6148 207.0639 10.3514 20250704 7.5 4.0 C/2023 RN3 (ATLAS) MPEC 2024-YC7 + CK23R61S 2028 12 1.2479 7.997890 0.327853 119.4134 347.0210 19.9448 20250704 6.8 4.0 C/2023 RS61 MPC184411 + PK23S010 2025 02 24.1785 2.619723 0.318462 180.3069 317.2904 9.1578 20250704 11.5 4.0 P/2023 S1 (PANSTARRS) MPEC 2025-MC0 + CK23S020 2023 10 15.3170 1.061662 0.993569 78.9549 229.4610 19.6554 20250704 15.0 4.0 C/2023 S2 (ATLAS) MPEC 2023-XP6 + CK23S030 2024 01 19.6494 0.829273 0.970824 281.5307 233.8227 140.4932 20250704 16.0 4.0 C/2023 S3 (Lemmon) MPEC 2024-P23 + PK23T010 2024 05 22.8586 2.817654 0.333217 202.8646 249.5763 6.6123 20250704 14.0 4.0 P/2023 T1 (PANSTARRS) MPEC 2024-BE0 + CK23T020 2023 12 22.7441 1.996315 0.991083 111.2166 317.5267 48.5907 20250704 14.5 4.0 C/2023 T2 (Borisov) MPEC 2024-GJ3 + CK23T030 2025 01 25.3560 3.548321 0.995876 302.8478 246.0019 27.2214 20250704 8.5 4.0 C/2023 T3 (Fuls) MPEC 2025-MC0 + CK23T22D 2024 09 16.3033 2.356669 0.951261 32.5416 5.5646 170.4898 20250704 12.5 4.0 C/2023 TD22 (Lemmon) MPEC 2025-MC0 + CK23U010 2024 10 12.9333 4.973112 0.998107 255.6457 305.8038 108.1460 20250704 8.0 4.0 C/2023 U1 (Fuls) MPEC 2025-MC0 + CK23V010 2025 07 13.0449 5.092583 1.000395 103.3153 15.0427 102.0137 20250704 8.5 4.0 C/2023 V1 (Lemmon) MPEC 2025-MC0 + PK23V020 2024 02 3.6618 3.104158 0.570036 330.5171 95.4744 9.8884 20250704 13.5 4.0 P/2023 V2 (PANSTARRS) MPC184411 + CK23V030 2023 08 3.5835 4.489587 0.650531 291.8380 91.2919 40.6995 20250704 11.5 4.0 C/2023 V3 (PANSTARRS) MPEC 2024-A43 + CK23V040 2024 05 30.3932 1.121906 1.001166 50.8702 66.3270 67.1252 20250704 12.0 4.0 C/2023 V4 (Camarasa-Duszanowicz) MPEC 2025-MC0 + CK23V050 2023 12 13.9085 0.846315 1.009427 56.9688 31.5150 73.5490 20250704 21.5 4.0 C/2023 V5 (Leonard) MPEC 2024-GJ3 + PK23V060 2022 12 1.3660 4.365112 0.175486 192.4431 189.6363 3.9726 20250704 11.5 4.0 P/2023 V6 (PANSTARRS) MPEC 2025-A40 + CK23X010 2023 10 17.9681 0.951114 0.993894 321.4685 136.9915 110.5886 20250704 13.5 3.2 C/2023 X1 (Leonard) MPEC 2024-GJ3 + CK23X020 2025 12 28.1995 5.088735 1.000073 64.7680 66.3029 76.9821 20250704 8.5 3.2 C/2023 X2 (Lemmon) MPEC 2025-MC0 + PK23X030 2024 04 22.1535 3.030764 0.286183 40.8695 62.0138 4.4833 20250704 15.5 4.0 P/2023 X3 (PANSTARRS) MPEC 2024-A43 + CK23X040 2024 05 25.0625 3.658450 0.631282 100.5921 28.7696 11.5934 20250704 12.0 4.0 C/2023 X4 (Hogan) MPC184411 + CK23X070 2025 05 15.2371 4.820348 1.002433 354.4027 119.1981 69.0941 20250704 9.0 4.0 C/2023 X7 (PANSTARRS) MPEC 2024-DA2 + PK23Y010 2023 11 29.9262 2.080083 0.445368 51.4791 78.8561 6.3839 20250704 17.0 4.0 P/2023 Y1 (Gibbs) MPEC 2024-JU4 + PK23Y020 2023 08 10.1120 2.277360 0.392271 16.9037 79.2290 6.9926 20250704 15.5 4.0 P/2023 Y2 (Gibbs) MPEC 2025-A40 + CK24A010 2025 06 13.6656 3.875289 1.002553 353.3035 112.1350 94.4697 20250704 7.0 4.0 C/2024 A1 (ATLAS) MPEC 2025-MC0 + CK24A020 2024 04 28.8033 1.879384 0.941753 295.4930 78.1650 119.1143 20250704 12.5 4.0 C/2024 A2 (ATLAS) MPC182881 + CK24B010 2024 10 7.7209 1.633809 1.001023 66.2176 79.1882 70.9030 20250704 13.0 4.0 C/2024 B1 (Lemmon) MPEC 2025-MC0 + CK24B020 2023 10 5.8262 4.078133 0.997856 130.3353 294.3861 99.8696 20250704 11.5 4.0 C/2024 B2 (Lemmon) MPEC 2025-A40 + CK24C010 2024 08 31.0676 4.412875 0.582998 94.4894 83.8096 14.2269 20250704 11.5 4.0 C/2024 C1 (PANSTARRS) MPEC 2025-MC0 + CK24C020 2025 03 11.2541 8.991384 0.445937 87.5747 66.4458 27.2844 20250704 6.0 4.0 C/2024 C2 (PANSTARRS) MPEC 2024-JU4 + CK24C030 2023 11 8.7619 6.713039 0.424669 159.6907 359.7058 22.4546 20250704 9.0 4.0 C/2024 C3 (PANSTARRS) MPC184412 + CK24C040 2024 01 30.1902 1.470494 0.982375 321.4982 220.6709 79.2830 20250704 14.5 4.0 C/2024 C4 (ATLAS) MPEC 2024-Q20 + CK24D010 2027 12 3.3970 6.693173 0.999291 125.7772 179.6614 132.4498 20250704 7.3 4.0 C/2024 D1 (Lemmon) MPEC 2025-MC0 + CK24E010 2026 01 20.7643 0.565989 1.000067 243.6328 108.0805 75.2391 20250704 7.0 4.0 C/2024 E1 (Wierzchos) MPEC 2025-MC0 + CK24E020 2023 10 25.1763 7.695087 0.850589 358.1382 135.6542 155.6499 20250704 8.0 4.0 C/2024 E2 (Bok) MPEC 2024-JU4 + PK24F010 2023 10 25.7817 1.859839 0.459985 229.5773 251.5413 7.0052 20250704 16.0 4.0 P/2024 F1 (PANSTARRS) MPEC 2024-JU4 + CK24F020 2024 07 29.0422 3.967819 0.601121 112.9006 138.9396 13.7429 20250704 11.0 4.0 C/2024 F2 (PANSTARRS) MPEC 2025-MC0 + PK24F09G 2024 05 20.4047 1.596489 0.509924 245.9339 253.0426 1.7312 20250704 14.0 4.0 P/2024 FG9 (Nanshan-Hahn) MPEC 2024-UA9 + CK24G010 2024 10 21.0726 3.930118 0.967836 128.2238 30.6053 95.3934 20250704 10.0 4.0 C/2024 G1 (Wierzchos) MPC184412 + CK24G020 2025 06 13.5384 5.348241 0.992697 328.7381 171.3969 122.1252 20250704 7.0 4.0 C/2024 G2 (ATLAS) MPEC 2025-MC0 + CK24G030 2025 01 13.4266 0.093553 1.000006 108.1277 220.3456 116.8475 20250704 9.0 4.0 C/2024 G3 (ATLAS) MPC184412 + CK24G040 2026 03 21.6128 4.900424 0.998456 131.4207 152.9814 33.0265 20250704 8.0 4.0 C/2024 G4 (PANSTARRS) MPEC 2025-MC0 + CK24G050 2024 09 7.0565 2.953047 0.994840 209.5801 316.3924 50.3869 20250704 13.0 4.0 C/2024 G5 (Leonard) MPEC 2024-JC6 + CK24G060 2026 02 20.7441 6.429787 1.002164 23.4393 250.9519 120.4554 20250704 5.5 4.0 C/2024 G6 (ATLAS) MPEC 2025-MC0 + CK24G070 2025 02 10.1037 6.027654 1.001913 289.6567 191.9632 131.5151 20250704 7.0 4.0 C/2024 G7 (ATLAS) MPC184412 + AK24G080 2024 06 15.5823 1.172469 0.991717 249.1571 11.2486 97.4139 20250704 20.0 2.0 A/2024 G8 MPEC 2024-Q05 + PK24J010 2023 11 11.3130 2.636629 0.307731 200.3655 321.9380 13.1592 20250704 14.5 4.0 P/2024 J1 (PANSTARRS) MPEC 2024-JU4 + CK24J020 2025 03 19.7848 1.810903 0.987699 143.1611 189.0592 79.2970 20250704 11.5 4.0 C/2024 J2 (Wierzchos) MPC182882 + CK24J030 2026 11 25.3330 3.865184 1.000726 74.0887 285.9612 75.6402 20250704 5.0 4.0 C/2024 J3 (ATLAS) MPEC 2025-MC0 + CK24J040 2025 04 26.0055 5.695121 0.999102 127.8587 19.3065 117.5295 20250704 8.0 4.0 C/2024 J4 (Lemmon) MPEC 2025-MC0 + PK24K010 2024 05 8.9354 3.455449 0.495175 351.9259 251.6891 1.7862 20250704 13.5 4.0 P/2024 K1 (PANSTARRS) MPEC 2024-LB4 + CK24L010 2025 04 23.1477 5.348103 0.533542 171.7950 45.1395 99.1652 20250704 10.0 4.0 C/2024 L1 (PANSTARRS) MPEC 2025-MC0 + CK24L020 2025 06 12.7885 8.326290 0.982376 345.6169 266.2859 139.4875 20250704 7.5 3.2 C/2024 L2 (PANSTARRS) MPEC 2024-P23 + CK24L030 2023 11 24.1478 6.857936 1.003832 59.0764 294.9953 111.5922 20250704 9.5 4.0 C/2024 L3 (PANSTARRS) MPEC 2024-RQ6 + CK24L050 2025 03 10.3956 3.432420 1.037115 290.5155 139.1774 166.5729 20250704 9.0 4.0 C/2024 L5 (ATLAS) MPEC 2025-MC0 + CK24M010 2024 11 19.9944 1.703227 0.942836 345.5840 76.2144 73.7095 20250704 12.0 4.0 C/2024 M1 (ATLAS) MPC184413 + CK24N010 2025 10 18.8662 4.398220 1.001168 91.2538 323.0214 88.7814 20250704 10.5 4.0 C/2024 N1 (PANSTARRS) MPEC 2025-MC0 + CK24N030 2025 04 11.4476 5.014579 1.001405 86.8863 82.6088 88.7289 20250704 8.0 4.0 C/2024 N3 (Sarneczky) MPEC 2025-MC0 + CK24N040 2025 01 10.2090 5.397813 1.004378 116.7081 339.6568 49.7747 20250704 7.5 4.0 C/2024 N4 (Sarneczky) MPEC 2025-MC0 + CK24O010 2023 01 28.5176 6.606783 1.000621 349.8875 303.3417 59.0792 20250704 8.5 4.0 C/2024 O1 (PANSTARRS) MPEC 2024-PC5 + PK24O020 2024 04 20.1507 3.697695 0.499084 310.7853 6.8056 28.9768 20250704 12.0 4.0 P/2024 O2 (PANSTARRS) MPEC 2024-UA9 + PK24O02C 2024 10 9.3143 0.592885 0.774180 258.5383 136.6166 7.6712 20250704 20.5 4.0 P/2024 OC2 (PANSTARRS) MPEC 2025-A40 + CK24P07N 2024 12 6.4342 1.524571 0.977341 74.2736 358.5842 101.2093 20250704 15.2 4.0 C/2024 PN7 (PANSTARRS) MPEC 2025-MC0 + PK24Q010 2024 06 14.6500 1.637859 0.534868 284.5326 23.1101 5.0117 20250704 17.0 4.0 P/2024 Q1 (PANSTARRS) MPEC 2024-UQ8 + CK24Q030 2025 03 5.2193 2.091560 1.001489 70.1277 337.2874 121.3780 20250704 15.0 4.0 C/2024 Q3 (PANSTARRS) MPEC 2025-MC0 + CK24Q040 2024 11 12.1859 5.419116 0.992006 133.0515 324.2723 3.3150 20250704 10.0 4.0 C/2024 Q4 (PANSTARRS) MPC182882 + PK24R010 2024 06 15.8715 1.751282 0.493126 230.6951 84.9830 12.7356 20250704 18.0 4.0 P/2024 R1 (PANSTARRS) MPEC 2024-TP3 + PK24R020 2024 10 1.7093 2.302955 0.268704 203.9302 193.0085 15.1157 20250704 15.5 4.0 P/2024 R2 (PANSTARRS) MPC182883 + PK24R030 2024 05 8.4426 2.345775 0.267288 309.3203 33.2378 14.7167 20250704 15.0 4.0 P/2024 R3 (PANSTARRS) MPEC 2024-YC7 + CK24R040 2027 10 26.6555 4.409159 1.002594 108.9929 345.9351 95.3627 20250704 6.5 4.0 C/2024 R4 (PANSTARRS) MPEC 2025-MC0 + CK24S010 2024 10 28.4785 0.007984 0.999908 69.5348 347.6063 142.0308 20250704 15.5 4.0 C/2024 S1 (ATLAS) MPC182883 + PK24S020 2024 09 16.2890 2.047610 0.593576 49.1659 8.3377 7.5258 20250704 15.0 4.0 P/2024 S2 (Rankin) MPEC 2025-A40 + PK24T010 2024 09 30.3866 2.287002 0.653432 164.8639 279.7108 17.6202 20250704 14.5 4.0 P/2024 T1 (Rankin) MPC182883 + PK24T020 2024 12 8.3276 1.972300 0.680413 343.8265 113.0614 12.9290 20250704 16.0 4.0 P/2024 T2 (Rankin) MPC184413 + CK24T030 2025 03 15.2477 3.716150 0.957210 336.8858 74.8336 53.4719 20250704 11.5 4.0 C/2024 T3 (PANSTARRS) MPC182883 + CK24T050 2027 05 6.1779 3.841459 1.002275 352.4375 100.6799 52.3868 20250704 5.5 4.0 C/2024 T5 (ATLAS) MPEC 2025-MC0 + CK24U010 2024 06 30.4371 4.836220 0.990032 188.0816 270.2639 128.7552 20250704 10.0 4.0 C/2024 U1 (PANSTARRS) MPC182883 + AK24U020 2026 01 14.4478 8.180816 1.003452 29.7740 56.0700 120.6714 20250704 12.1 2.0 A/2024 U2 MPC182883 + CK24V010 2025 04 4.1128 2.318471 0.990033 168.6684 328.1947 54.6259 20250704 14.8 4.0 C/2024 V1 (Borisov) MPEC 2025-MC0 + CK24V020 2024 11 3.8247 1.243082 0.968366 13.7239 102.2017 95.9719 20250704 19.0 4.0 C/2024 V2 (Sarneczky) MPEC 2024-YC7 + CK24W010 2025 03 19.1058 2.560730 0.942939 256.7394 310.7272 83.2005 20250704 15.0 4.0 C/2024 W1 (PANSTARRS) MPC182883 + AK24W020 2025 02 27.4162 3.720673 1.002574 168.0033 241.9381 116.6152 20250704 15.6 2.0 A/2024 W2 MPC182883 + CK24X010 2025 08 3.4799 3.816668 0.596739 124.3601 351.9961 6.4640 20250704 11.3 4.0 C/2024 X1 (Fazekas) MPC182884 + CK24X020 2025 07 7.8837 3.676298 0.927286 315.7822 122.5229 109.2212 20250704 9.6 4.0 C/2024 X2 (ATLAS) MPEC 2025-MC0 + PK24X030 2024 09 5.7835 2.614247 0.626188 352.9470 113.3647 2.9723 20250704 14.6 4.0 P/2024 X3 (PANSTARRS) MPEC 2025-MC0 + CK24X040 2025 09 1.9108 3.604754 0.641780 153.2910 258.9434 34.6689 20250704 12.6 4.0 C/2024 X4 (PANSTARRS) MPEC 2025-A40 + CK24Y010 2024 11 26.8817 0.822209 0.986815 238.1411 112.5424 64.7686 20250704 17.6 4.0 C/2024 Y1 (Masek) MPC182884 + AK25A010 2027 03 12.3570 5.341782 1.004226 68.0760 101.3305 33.4400 20250704 11.8 2.0 A/2025 A1 MPC182884 + PK25A020 2024 10 5.6454 3.446392 0.322091 278.0450 189.3191 20.7342 20250704 13.2 4.0 P/2025 A2 (PANSTARRS) MPC184414 + CK25A030 2026 03 15.0573 5.792284 0.431759 222.3086 322.4332 9.9766 20250704 9.0 4.0 C/2025 A3 (Tsuchinshan) MPC184414 + CK25A040 2025 01 13.1655 3.824237 0.653988 102.7978 69.9136 32.0254 20250704 12.4 4.0 C/2025 A4 (PANSTARRS) MPEC 2025-MC0 + CK25A060 2025 11 8.5393 0.529987 0.995712 132.9604 108.0968 143.6638 20250704 13.2 4.0 C/2025 A6 (Lemmon) MPC184414 + AK25A070 2025 03 28.1140 2.883453 0.999361 195.5695 348.8453 133.6505 20250704 14.0 2.0 A/2025 A7 MPC184414 + CK25B010 2025 06 26.7709 3.530889 1.000796 23.5263 102.8413 39.6804 20250704 12.0 4.0 C/2025 B1 (PANSTARRS) MPC182885 + CK25B020 2026 09 10.0158 8.244800 1.000116 78.7304 84.8733 91.7517 20250704 6.2 4.0 C/2025 B2 (Borisov) MPC184414 + PK25C010 2025 02 6.5736 2.746063 0.345489 186.8033 9.1025 7.5170 20250704 10.8 4.0 P/2025 C1 (ATLAS) MPEC 2025-MC0 + CK25D010 2028 05 20.1813 14.118679 1.002964 185.8961 312.8990 84.4633 20250704 1.2 4.0 C/2025 D1 (Groeller) MPEC 2025-MC0 + PK25D020 2028 11 5.3292 7.326666 0.178790 314.0521 256.7339 5.3344 20250704 8.2 4.0 P/2025 D2 (PANSTARRS) MPC182885 + PK25D030 2024 07 25.7577 2.965576 0.252445 294.4749 186.6360 9.6439 20250704 14.7 4.0 P/2025 D3 (PANSTARRS) MPEC 2025-MC0 + PK25D040 2025 02 14.2846 3.254936 0.634437 332.8888 233.1200 15.9404 20250704 13.2 4.0 P/2025 D4 (ATLAS) MPEC 2025-MC0 + CK25D050 2025 05 13.2919 2.012173 0.999397 211.4931 0.7378 73.3810 20250704 17.6 4.0 C/2025 D5 (PANSTARRS) MPC184415 + CK25D060 2024 12 11.3854 2.503939 0.998421 285.4050 151.4874 145.7902 20250704 13.2 4.0 C/2025 D6 (ATLAS) MPC184415 + CK25E010 2026 09 23.7429 3.998169 0.997239 274.4212 344.5967 69.0653 20250704 9.7 4.0 C/2025 E1 (PANSTARRS) MPC184415 + CK25F010 2025 04 20.4730 1.069953 0.996315 334.2289 122.7051 109.2370 20250704 18.0 4.0 C/2025 F1 (ATLAS) MPEC 2025-MC0 + CK25F020 2025 05 1.1613 0.333494 1.000101 153.8370 329.8408 90.3649 20250704 11.2 4.0 C/2025 F2 (SWAN) MPC184415 + CK25J010 2026 06 11.6719 3.582168 0.997316 166.5786 273.9822 95.4429 20250704 9.1 4.0 C/2025 J1 (Borisov) MPEC 2025-MC0 + CK25K010 2025 10 8.4448 0.334140 1.000204 271.0342 97.5572 147.8644 20250704 12.2 4.0 C/2025 K1 (ATLAS) MPEC 2025-MC0 + CK25K020 2025 10 25.2197 2.864107 0.889281 232.4536 113.8362 113.9939 20250704 13.7 4.0 C/2025 K2 (PANSTARRS) MPEC 2025-MC0 + CK25K030 2028 12 13.7710 3.468841 1.001671 188.5952 350.6201 104.9334 20250704 6.4 4.0 C/2025 K3 (PANSTARRS) MPEC 2025-L43 + CK25K040 2025 07 27.8793 2.536762 0.941660 326.7628 297.0703 38.5749 20250704 14.1 4.0 C/2025 K4 (Siverd) MPEC 2025-L55 + CK25L010 2026 01 12.7456 1.679467 1.001385 341.2587 208.1062 114.1371 20250704 11.4 4.0 C/2025 L1 (ATLAS) MPEC 2025-MC0 + CK25L020 2025 12 20.5925 2.833819 0.996459 232.6394 134.9896 86.5959 20250704 11.7 4.0 C/2025 L2 MPEC 2025-MC0 + CK25M010 2029 08 3.2258 10.829066 0.998192 230.4263 66.9586 64.9012 20250704 2.9 4.0 C/2025 M1 (PANSTARRS) MPEC 2025-MD2 + CK25M020 2027 11 14.5684 2.629391 1.000637 98.0974 305.6139 173.1646 20250704 7.0 3.2 C/2025 M2 (PANSTARRS) MPC xxxxx +0001P 2061 08 29.6127 0.583093 0.967360 112.5257 59.6157 162.2174 20250704 4.0 6.0 1P/Halley 98, 1083 +0002P 2027 02 10.2633 0.339087 0.847131 187.2794 334.0149 11.3444 20250704 11.5 6.0 2P/Encke MPEC 2024-TP3 +0003D a 2024 12 2.1233 0.826876 0.767119 192.1286 276.6829 7.2157 20250704 11.0 6.0 3D-A/Biela 76, 1135 +0003D b 2025 06 28.0738 0.821837 0.767863 192.2545 276.2012 7.8798 20250704 11.0 6.0 3D-B/Biela 76, 1135 +0004P 2029 03 8.7775 1.622758 0.576304 207.1437 192.9104 8.0028 20250704 8.0 6.0 4P/Faye MPEC 2023-FK0 +0005D 2023 04 17.3504 0.512048 0.837880 20.3030 94.9066 18.6309 20250704 10.5 6.0 5D/Brorsen 27, 116 +0006P 2028 04 1.6155 1.357332 0.611934 178.0499 138.9509 19.5000 20250704 7.5 16.0 6P/d'Arrest MPEC 2022-WD2 +0007P 2027 08 29.6587 1.189488 0.648884 172.5839 93.2820 22.5921 20250704 10.0 6.0 7P/Pons-Winnecke MPEC 2023-A50 +0008P 2021 08 28.6170 1.022959 0.820706 207.4761 270.1770 54.9843 20250704 8.0 8.0 8P/Tuttle MPEC 2022-HC2 +0009P 2028 02 6.0856 1.733944 0.472654 184.4588 67.3044 10.6503 20250704 5.5 10.0 9P/Tempel MPEC 2024-YC7 +0010P 2026 08 2.1482 1.417412 0.537383 195.4916 117.8004 12.0274 20250704 5.0 10.0 10P/Tempel MPEC 2025-MC0 +0011P 2026 11 9.8690 1.387322 0.577447 168.0505 238.8628 14.4327 20250704 17.0 4.0 11P/Tempel-Swift-LINEAR MPEC 2024-R10 +0012P 2024 04 21.1414 0.781140 0.954669 199.0084 255.8567 74.1892 20250704 5.0 6.0 12P/Pons-Brooks MPEC 2025-MC0 +0013P 2024 06 30.0791 1.175442 0.930484 64.4224 85.8467 44.6658 20250704 5.0 6.0 13P/Olbers MPEC 2025-MC0 +0014P 2026 09 19.0038 2.738333 0.356667 159.1950 202.0231 27.9180 20250704 5.5 12.0 14P/Wolf MPC184415 +0015P 2028 02 9.7721 0.996755 0.716102 347.8653 13.7488 6.7870 20250704 12.0 4.0 15P/Finlay MPEC 2022-ED3 +0016P 2028 04 20.9298 1.883762 0.485608 245.3744 138.8250 3.0099 20250704 7.5 10.0 16P/Brooks MPEC 2022-X67 +0017P 2028 01 31.7234 2.089144 0.426308 24.6141 326.6081 19.0067 20250704 10.0 6.0 17P/Holmes MPEC 2023-J29 +0018D 2024 08 29.146 1.59300 0.58952 238.206 158.450 17.661 20250704 9.0 4.0 18D/Perrine-Mrkos 19, 80 +0019P 2022 02 2.3429 1.307090 0.637770 352.0078 74.2152 29.3154 20250704 4.5 10.0 19P/Borrelly MPEC 2024-YC7 +0021P 2025 03 25.3587 1.008943 0.711060 172.9355 195.3290 32.0497 20250704 9.0 6.0 21P/Giacobini-Zinner MPEC 2024-YC7 +0022P 2028 07 11.6619 1.505436 0.558795 162.9877 120.1855 4.8273 20250704 3.0 10.4 22P/Kopff MPEC 2024-L77 +0023P 2059 06 1.1288 0.464402 0.972584 129.9929 311.1697 19.4692 20250704 10.0 6.0 23P/Brorsen-Metcalf MPC 14747 +0024P 2026 01 8.2987 1.183885 0.708202 58.3981 78.3676 11.5063 20250704 6.5 14.0 24P/Schaumasse MPC110085 +0025D 2025 05 11.4152 1.448318 0.550410 244.7987 279.9705 2.8087 20250704 12.5 6.0 25D/Neujmin 2 NK 378 +0026P 2023 12 25.3133 1.083401 0.640609 2.1230 211.5314 22.4373 20250704 12.0 16.0 26P/Grigg-Skjellerup MPEC 2024-TP3 +0027P 2039 05 25.7016 0.737566 0.919647 195.8486 250.7045 29.4338 20250704 12.0 8.0 27P/Crommelin MPC 78188 +0028P 2021 03 10.1866 1.586934 0.772665 347.4487 346.4119 14.2925 20250704 8.5 6.0 28P/Neujmin MPEC 2025-A40 +0029P 2019 05 1.5593 5.794829 0.043265 52.0703 312.4036 9.3558 20250704 4.0 4.0 29P/Schwassmann-Wachmann MPEC 2025-MC0 +0030P 2024 08 17.2340 1.813906 0.514403 9.5160 117.2326 8.0533 20250704 9.5 6.0 30P/Reinmuth MPEC 2025-MC0 +0031P 2028 03 18.8331 3.412459 0.193442 17.9158 114.1132 4.5497 20250704 5.0 8.0 31P/Schwassmann-Wachmann MPEC 2025-A40 +0032P 2024 04 20.6923 2.025191 0.555309 54.7087 54.5325 9.9199 20250704 6.5 8.0 32P/ComasSola MPEC 2025-MC0 +0033P 2024 11 10.8792 2.242477 0.451931 20.2550 66.2797 22.2940 20250704 10.0 12.0 33P/Daniel MPC184416 +0034D 2026 08 25.2085 1.213737 0.758104 218.0376 57.8608 10.5825 20250704 9.0 4.0 34D/Gale 9, 314 +0035P 2092 04 9.939 0.73378 0.97429 29.223 356.171 64.511 20250704 9.0 4.0 35P/Herschel-Rigollet 15, 452 +0036P 2028 11 5.0163 3.030952 0.268116 201.2047 181.8261 9.9458 20250704 8.5 6.0 36P/Whipple MPEC 2023-RF3 +0037P 2024 10 11.2356 1.617869 0.532651 330.0631 314.5483 8.9478 20250704 10.5 4.8 37P/Forbes MPC184416 +0038P 2018 11 13.8755 1.579702 0.859770 359.5933 77.8613 18.4142 20250704 3.5 12.0 38P/Stephan-Oterma MPEC 2024-YC7 +0039P 2023 09 11.0440 5.766972 0.171399 115.3411 289.1604 1.7265 20250704 7.0 6.0 39P/Oterma MPEC 2024-AF0 +0040P 2025 11 11.9178 1.823642 0.631500 52.0413 128.8982 11.6404 20250704 5.5 12.0 40P/Vaisala MPC184416 +0041P 2028 02 16.1075 1.050914 0.659652 62.2154 140.9721 9.2162 20250704 10.0 16.0 41P/Tuttle-Giacobini-Kresak MPEC 2023-SQ0 +0042P 2026 01 14.9621 2.029539 0.584069 147.1321 150.1594 3.9883 20250704 13.0 6.0 42P/Neujmin MPC184416 +0043P 2025 08 4.6711 2.442898 0.436224 223.7999 243.9921 9.3315 20250704 8.0 6.0 43P/Wolf-Harrington MPC184416 +0044P 2022 04 22.0371 2.114062 0.426738 57.9917 286.4215 5.8959 20250704 8.3 6.0 44P/Reinmuth MPEC 2024-F34 +0045P 2027 08 31.5046 0.557541 0.817607 327.9503 87.6864 4.3240 20250704 13.5 8.0 45P/Honda-Mrkos-Pajdusakova MPEC 2022-O01 +0046P 2024 05 19.0962 1.055276 0.658716 356.3432 82.1619 11.7497 20250704 14.0 6.0 46P/Wirtanen MPEC 2024-F91 +0047P 2025 10 27.9811 2.807471 0.318177 357.9119 356.8821 13.0386 20250704 1.0 11.2 47P/Ashbrook-Jackson MPEC 2025-MC0 +0048P 2025 03 2.6435 2.006598 0.426542 216.7752 110.0639 12.2017 20250704 10.0 6.0 48P/Johnson MPEC 2025-MC0 +0049P 2025 04 10.6041 1.431324 0.599002 332.9254 118.7912 19.0598 20250704 11.3 4.4 49P/Arend-Rigaux MPEC 2025-MC0 +0050P 2024 05 12.6209 1.921910 0.529687 49.3107 355.1445 19.1008 20250704 9.5 6.0 50P/Arend MPC184417 +0051P 2022 09 30.6419 1.694207 0.542770 269.2322 83.6587 5.4264 20250704 10.0 8.0 51P/Harrington MPEC 2023-J29 +0051P a 2022 10 3.2225 1.694056 0.542963 83.6420 269.2290 5.4262 20250704 10.0 8.0 51P-A/Harrington NK 3014 +0051P d 2022 10 1.0654 1.693886 0.542900 269.2503 83.6470 5.4268 20250704 16.0 8.0 51P-D/Harrington MPEC 2023-J29 +0052P 2021 10 6.2948 1.772256 0.541111 139.6177 336.7529 10.2381 20250704 13.5 6.0 52P/Harrington-Abell MPEC 2023-XP6 +0053P 2028 12 26.1217 2.449547 0.549674 134.3371 148.8518 6.6026 20250704 7.7 4.8 53P/VanBiesbroeck MPEC 2023-TM6 +0054P 2024 09 4.2008 2.171971 0.427174 2.1130 358.7330 6.0619 20250704 10.0 6.0 54P/deVico-Swift-NEAT MPEC 2024-YC7 +0055P 2031 05 22.5950 0.974361 0.905740 172.4948 235.4110 162.4831 20250704 9.0 4.0 55P/Tempel-Tuttle MPC 31070 +0056P 2027 12 19.4764 2.489375 0.508338 44.2215 345.8871 8.1549 20250704 8.5 6.0 56P/Slaughter-Burnham MPEC 2023-TM6 +0057P 2028 03 4.6807 1.715751 0.501352 115.0613 188.7375 2.8533 20250704 12.5 6.0 57P/duToit-Neujmin-Delporte MPEC 2024-DC6 +0058P 2028 09 4.3250 1.384315 0.661640 200.5828 159.0392 13.0873 20250704 15.5 6.0 58P/Jackson-Neujmin MPEC 2024-A43 +0059P 2028 03 15.4677 2.342397 0.477033 127.6713 312.7283 9.3560 20250704 7.0 6.0 59P/Kearns-Kwee MPEC 2023-A50 +0060P 2025 07 20.6098 1.645705 0.533803 216.9139 267.3962 3.5799 20250704 11.5 6.0 60P/Tsuchinshan MPC182887 +0061P 2022 10 23.3883 2.129296 0.423050 221.7095 162.9610 5.9968 20250704 6.0 10.0 61P/Shajn-Schaldach MPEC 2024-JU4 +0062P 2023 12 25.2064 1.265128 0.624715 47.3323 68.6654 4.7369 20250704 8.0 10.0 62P/Tsuchinshan MPC182887 +0063P 2026 07 6.2592 1.973619 0.650811 168.7919 357.7613 19.6188 20250704 10.5 6.0 63P/Wild MPC 84320 +0064P 2028 03 31.0423 1.387221 0.688421 97.3363 299.7713 8.9540 20250704 9.5 12.0 64P/Swift-Gehrels MPEC 2024-A43 +0065P 2025 06 16.4691 2.926255 0.248137 213.6734 61.9753 9.1753 20250704 5.0 6.0 65P/Gunn MPEC 2025-MC0 +0066P 2018 05 12.5516 1.305387 0.784960 257.3817 21.8386 18.6452 20250704 15.0 4.0 66P/duToit MPEC 2021-F20 +0067P 2028 04 9.1123 1.211109 0.649829 22.2127 36.3137 3.8683 20250704 11.0 4.0 67P/Churyumov-Gerasimenko MPEC 2024-C04 +0068P 2030 11 27.2642 1.807969 0.635756 153.2203 175.0920 11.0992 20250704 12.6 4.0 68P/Klemola MPEC 2023-HD1 +0069P 2026 11 12.3530 2.271174 0.414694 343.5001 104.8080 22.0613 20250704 9.5 12.0 69P/Taylor MPEC 2024-C04 +0070P 2028 11 20.8520 2.003782 0.454810 1.7940 119.2353 6.6031 20250704 11.0 6.0 70P/Kojima MPEC 2023-VM5 +0071P 2023 01 21.3011 1.630056 0.486708 210.4411 59.2203 9.2898 20250704 9.8 6.0 71P/Clark MPEC 2024-YC7 +0072P 2023 06 15.5655 0.782586 0.818325 346.7420 26.7216 10.9436 20250704 17.5 10.0 72P/Denning-Fujikawa MPEC 2023-VM5 +0073P 2027 12 13.0154 0.858059 0.716923 208.6546 58.7496 7.1304 20250704 11.5 6.0 73P/Schwassmann-Wachmann MPEC 2023-RF3 +0073P b 2028 01 22.3258 0.934148 0.696050 75.7146 192.6193 10.6596 20250704 9.0 4.0 73P-B/Schwassmann-Wachmann B NK 1613 +0073P c 2028 01 16.9602 0.934218 0.695883 75.5791 192.7911 10.6718 20250704 9.0 4.0 73P-C/Schwassmann-Wachmann NK 2710 +0073P e 2028 02 3.8299 0.934480 0.696344 75.9874 192.3134 10.6282 20250704 9.0 4.0 73P-E/Schwassmann-Wachmann NK 934 +0073P g 2006 06 8.096 0.93920 0.69330 198.772 69.909 11.388 9.0 4.0 73P-G/Schwassmann-Wachmann MPC 56796 +0073P h 2006 06 8.281 0.93918 0.69330 198.778 69.903 11.389 9.0 4.0 73P-H/Schwassmann-Wachmann MPC 56796 +0073P j 2006 06 8.141 0.93966 0.69330 198.673 69.983 11.386 9.0 4.0 73P-J/Schwassmann-Wachmann MPC 56796 +0073P k 2006 06 8.224 0.93903 0.69330 198.809 69.881 11.390 9.0 4.0 73P-K/Schwassmann-Wachmann MPC 56797 +0073P l 2006 06 8.340 0.93914 0.69330 198.772 69.911 11.388 9.0 4.0 73P-L/Schwassmann-Wachmann MPC 56797 +0073P m 2006 06 8.262 0.93912 0.69330 198.787 69.895 11.389 9.0 4.0 73P-M/Schwassmann-Wachmann MPC 56797 +0073P n 2006 06 8.261 0.93920 0.69330 198.754 69.909 11.389 9.0 4.0 73P-N/Schwassmann-Wachmann MPC 56797 +0073P p 2006 06 7.872 0.93917 0.69330 198.783 69.900 11.390 9.0 4.0 73P-P/Schwassmann-Wachmann MPC 56797 +0073P q 2006 06 7.725 0.93941 0.69330 198.717 69.944 11.387 9.0 4.0 73P-Q/Schwassmann-Wachmann MPC 56797 +0073P r 2006 06 8.185 0.93918 0.69330 198.776 69.904 11.388 9.0 4.0 73P-R/Schwassmann-Wachmann MPC 56797 +0073P s 2006 06 8.689 0.98977 0.69330 188.229 77.364 11.127 9.0 4.0 73P-S/Schwassmann-Wachmann MPC 56797 +0073P t 2027 12 11.1414 0.857662 0.716939 208.5764 58.8450 7.1722 20250704 9.0 4.0 73P-T/Schwassmann-Wachmann MPEC 2023-J29 +0073P u 2006 06 9.016 0.93962 0.69330 198.659 69.994 11.384 9.0 4.0 73P-U/Schwassmann-Wachmann MPC 56797 +0073P v 2006 06 8.477 0.91217 0.69330 204.943 65.236 11.651 9.0 4.0 73P-V/Schwassmann-Wachmann MPC 56797 +0073P w 2006 06 8.500 0.93906 0.69330 198.803 69.884 11.390 9.0 4.0 73P-W/Schwassmann-Wachmann MPC 56797 +0073P x 2006 06 8.566 0.93913 0.69330 198.778 69.900 11.388 9.0 4.0 73P-X/Schwassmann-Wachmann MPC 56798 +0073P y 2006 06 8.770 0.93911 0.69330 198.785 69.879 11.391 9.0 4.0 73P-Y/Schwassmann-Wachmann MPC 56798 +0073P z 2006 06 8.309 0.94204 0.69330 198.017 70.493 11.349 9.0 4.0 73P-Z/Schwassmann-Wachmann MPC 56798 +0073P aa 2006 06 9.086 0.93905 0.69330 198.804 69.883 11.390 9.0 4.0 73P-AA/Schwassmann-Wachmann MPC 56798 +0073P ab 2006 06 8.697 0.93906 0.69330 198.792 69.888 11.390 9.0 4.0 73P-AB/Schwassmann-Wachmann MPC 56798 +0073P ac 2006 06 8.693 0.93918 0.69330 198.766 69.914 11.387 9.0 4.0 73P-AC/Schwassmann-Wachmann MPC 56798 +0073P ad 2006 06 8.694 0.94167 0.69330 198.119 70.416 11.355 9.0 4.0 73P-AD/Schwassmann-Wachmann MPC 56798 +0073P ae 2006 06 8.352 0.93910 0.69330 198.790 69.891 11.390 9.0 4.0 73P-AE/Schwassmann-Wachmann MPC 56798 +0073P af 2006 06 6.841 0.94144 0.69330 198.217 70.302 11.356 9.0 4.0 73P-AF/Schwassmann-Wachmann MPC 56798 +0073P ag 2006 06 9.016 0.93921 0.69330 198.724 69.932 11.386 9.0 4.0 73P-AG/Schwassmann-Wachmann MPC 56798 +0073P ah 2006 06 8.628 0.94293 0.69330 197.755 70.695 11.331 9.0 4.0 73P-AH/Schwassmann-Wachmann MPC 56798 +0073P ai 2006 06 8.737 0.93912 0.69330 198.806 69.885 11.392 9.0 4.0 73P-AI/Schwassmann-Wachmann MPC 56798 +0073P aj 2006 06 8.740 0.93930 0.69330 198.663 70.041 11.385 9.0 4.0 73P-AJ/Schwassmann-Wachmann MPC 56799 +0073P ak 2006 06 8.395 0.93924 0.69330 198.822 69.784 11.389 9.0 4.0 73P-AK/Schwassmann-Wachmann MPC 56799 +0073P al 2006 06 8.456 0.93892 0.69330 198.857 69.843 11.395 9.0 4.0 73P-AL/Schwassmann-Wachmann MPC 56799 +0073P am 2006 06 8.266 0.93912 0.69330 198.815 69.876 11.394 9.0 4.0 73P-AM/Schwassmann-Wachmann MPC 56799 +0073P an 2006 06 8.328 0.93906 0.69330 198.820 69.870 11.393 9.0 4.0 73P-AN/Schwassmann-Wachmann MPC 56799 +0073P ao 2006 06 7.808 0.94408 0.69330 197.007 71.286 11.210 9.0 4.0 73P-AO/Schwassmann-Wachmann MPC 56799 +0073P ap 2006 06 6.685 0.93918 0.69330 198.794 69.895 11.393 9.0 4.0 73P-AP/Schwassmann-Wachmann MPC 56799 +0073P aq 2006 06 7.919 0.93920 0.69330 198.770 69.911 11.387 9.0 4.0 73P-AQ/Schwassmann-Wachmann MPC 56799 +0073P ar 2006 06 6.833 0.93937 0.69330 198.722 69.946 11.385 9.0 4.0 73P-AR/Schwassmann-Wachmann MPC 56799 +0073P as 2006 06 6.335 0.93922 0.69330 198.773 69.906 11.392 9.0 4.0 73P-AS/Schwassmann-Wachmann MPC 56799 +0073P at 2006 06 6.228 0.93925 0.69330 198.778 69.901 11.391 9.0 4.0 73P-AT/Schwassmann-Wachmann MPC 56799 +0073P au 2006 06 8.093 0.93929 0.69330 198.744 69.928 11.385 9.0 4.0 73P-AU/Schwassmann-Wachmann MPC 56799 +0073P av 2006 06 6.490 0.93930 0.69330 198.751 69.945 11.388 9.0 4.0 73P-AV/Schwassmann-Wachmann MPC 56800 +0073P aw 2006 06 7.766 0.93947 0.69330 198.673 69.982 11.377 9.0 4.0 73P-AW/Schwassmann-Wachmann MPC 56800 +0073P ax 2006 06 9.533 0.93912 0.69330 198.757 69.915 11.388 9.0 4.0 73P-AX/Schwassmann-Wachmann MPC 56800 +0073P ay 2006 06 8.760 0.93918 0.69330 198.750 69.923 11.385 9.0 4.0 73P-AY/Schwassmann-Wachmann MPC 56800 +0073P az 2006 06 6.515 0.93962 0.69330 198.644 70.002 11.371 9.0 4.0 73P-AZ/Schwassmann-Wachmann MPC 56800 +0073P ba 2006 06 6.436 0.93976 0.69330 198.588 70.042 11.364 9.0 4.0 73P-BA/Schwassmann-Wachmann MPC 56800 +0073P bb 2006 06 7.087 0.93912 0.69330 198.807 69.882 11.395 9.0 4.0 73P-BB/Schwassmann-Wachmann MPC 56800 +0073P bc 2006 06 6.670 0.93922 0.69330 198.778 69.901 11.391 9.0 4.0 73P-BC/Schwassmann-Wachmann MPC 56800 +0073P bd 2006 06 6.417 0.93998 0.69330 198.503 70.085 11.352 9.0 4.0 73P-BD/Schwassmann-Wachmann MPC 56800 +0073P be 2006 06 6.863 0.93902 0.69330 198.861 69.841 11.405 9.0 4.0 73P-BE/Schwassmann-Wachmann MPC 56800 +0073P bf 2006 06 6.992 0.93918 0.69330 198.752 69.908 11.390 9.0 4.0 73P-BF/Schwassmann-Wachmann MPC 56800 +0073P bg 2006 06 8.741 0.93915 0.69330 198.750 69.925 11.384 9.0 4.0 73P-BG/Schwassmann-Wachmann MPC 56800 +0073P bh 2006 06 8.568 0.93874 0.69330 198.947 69.752 11.410 9.0 4.0 73P-BH/Schwassmann-Wachmann MPC 56801 +0073P bi 2006 06 8.639 0.93905 0.69330 198.877 69.819 11.404 9.0 4.0 73P-BI/Schwassmann-Wachmann MPC 56801 +0073P bj 2006 06 8.669 0.93914 0.69330 198.776 69.905 11.389 9.0 4.0 73P-BJ/Schwassmann-Wachmann MPC 56801 +0073P bk 2006 06 8.884 0.93931 0.69330 198.698 69.970 11.379 9.0 4.0 73P-BK/Schwassmann-Wachmann MPC 56801 +0073P bl 2006 06 8.885 0.93923 0.69330 198.739 69.930 11.385 9.0 4.0 73P-BL/Schwassmann-Wachmann MPC 56801 +0073P bm 2006 06 8.938 0.93962 0.69330 198.546 70.086 11.364 9.0 4.0 73P-BM/Schwassmann-Wachmann MPC 56801 +0073P bn 2006 06 8.203 0.93905 0.69330 198.815 69.871 11.398 9.0 4.0 73P-BN/Schwassmann-Wachmann MPC 56801 +0073P bo 2006 06 8.259 0.93913 0.69330 198.765 69.903 11.390 9.0 4.0 73P-BO/Schwassmann-Wachmann MPC 56801 +0073P bp 2006 06 8.302 0.93910 0.69330 198.807 69.881 11.395 9.0 4.0 73P-BP/Schwassmann-Wachmann MPC 56801 +0073P bq 2006 06 8.297 0.93900 0.69330 198.862 69.836 11.404 9.0 4.0 73P-BQ/Schwassmann-Wachmann MPC 56801 +0073P br 2006 06 6.154 0.93921 0.69330 198.774 69.910 11.389 9.0 4.0 73P-BR/Schwassmann-Wachmann MPC 56957 +0073P bs 2006 06 5.831 0.93918 0.69330 198.814 69.885 11.399 9.0 4.0 73P-BS/Schwassmann-Wachmann MPC 56957 +0073P bt 2028 01 20.0437 0.934228 0.696055 75.6345 192.7151 10.6656 20250704 11.5 6.0 73P-BT/Schwassmann-Wachmann MPC106348 +0073P bu 2027 07 2.8937 0.925956 0.676113 73.3795 196.9135 10.8759 20250704 19.0 4.0 73P-BU/Schwassmann-Wachmann MPEC 2022-P18 +0073P bv 2028 01 17.6504 0.872225 0.717211 205.4021 61.0920 7.4427 20250704 19.0 4.0 73P-BV/Schwassmann-Wachmann MPEC 2022-X67 +0073P bw 2022 08 23.7022 0.966786 0.786520 71.6148 193.0940 10.2021 20250704 18.2 4.0 73P-BW/Schwassmann-Wachmann MPEC 2022-R15 +0073P bx 2028 01 3.1157 0.867633 0.716844 206.9266 59.7771 7.2050 20250704 17.5 4.0 73P-BX/Schwassmann-Wachmann MPEC 2023-A50 +0073P by 2027 11 23.1100 0.931091 0.691088 75.2178 193.4173 10.7319 20250704 17.4 4.0 73P-BY/Schwassmann-Wachmann MPEC 2022-R15 +0074P 2026 06 26.6134 4.827587 0.044013 66.2196 52.9044 6.1646 20250704 5.0 6.0 74P/Smirnova-Chernykh MPC184417 +0075D 2027 11 2.4630 1.770001 0.499522 175.5892 269.5528 5.9270 20250704 9.5 6.0 75D/Kohoutek CCO 7 +0076P 2026 04 13.5563 1.596819 0.539456 0.0066 84.1109 30.4884 20250704 8.0 12.0 76P/West-Kohoutek-Ikemura MPEC 2022-K19 +0077P 2023 04 2.8231 2.346711 0.351801 196.6172 14.7496 24.3254 20250704 7.0 8.0 77P/Longmore MPEC 2024-UA9 +0078P 2026 06 25.0315 2.004745 0.463061 192.7588 210.5032 6.2571 20250704 5.5 8.0 78P/Gehrels MPEC 2025-MC0 +0079P 2023 09 30.3319 1.120107 0.619339 281.7545 280.5057 3.1488 20250704 16.0 4.0 79P/duToit-Hartley MPEC 2024-PC5 +0080P 2022 12 8.1731 1.617887 0.597704 339.2723 259.7723 29.9270 20250704 9.0 8.0 80P/Peters-Hartley MPEC 2024-Q20 +0081P 2022 12 15.8130 1.595794 0.537654 41.5497 136.0993 3.2382 20250704 7.0 6.0 81P/Wild MPEC 2024-RQ6 +0082P 2026 11 15.8658 3.624355 0.122885 226.4670 239.2149 1.1294 20250704 15.0 4.0 82P/Gehrels MPC133426 +0083D 2028 12 2.6306 2.146634 0.441455 334.3762 226.2961 17.8312 20250704 9.0 4.0 83D/Russell NK 932 +0084P 2027 02 12.6054 1.719285 0.515714 281.6827 108.1417 7.5528 20250704 9.5 8.0 84P/Giclas MPEC 2020-FB5 +0085D 2020 07 30.3445 1.131083 0.775864 333.0902 65.2975 4.1728 20250704 6.5 8.0 85D/Boethin unp +0086P 2022 02 1.4616 2.325639 0.362419 181.0594 72.0965 15.5021 20250704 11.0 6.0 86P/Wild MPEC 2022-YB4 +0087P 2029 04 1.8369 3.419602 0.216166 51.8743 184.8548 2.6670 20250704 7.2 10.0 87P/Bus MPEC 2020-SI8 +0088P 2026 03 18.7876 1.357670 0.563237 235.8810 56.6687 4.3820 20250704 11.0 6.0 88P/Howell MPEC 2025-MC0 +0089P 2024 03 26.6079 2.222633 0.407457 250.4307 41.3448 12.0710 20250704 11.5 6.0 89P/Russell MPC182887 +0090P 2032 05 17.1128 2.962965 0.510599 29.1902 13.1850 9.6390 20250704 8.5 6.0 90P/Gehrels MPEC 2022-K19 +0091P 2028 10 23.9571 3.079395 0.256367 357.2714 242.3850 16.1618 20250704 7.5 6.0 91P/Russell MPEC 2023-VM5 +0092P 2027 07 15.4050 1.816913 0.660037 163.7793 181.3623 19.4788 20250704 12.0 6.0 92P/Sanguin MPEC 2014-J58 +0093P 2026 05 2.9143 1.688585 0.613954 75.0247 339.5507 12.2094 20250704 9.5 6.0 93P/Lovas MPEC 2025-MC0 +0094P 2023 05 21.1923 2.225312 0.366008 92.3746 70.8473 6.1875 20250704 9.0 6.0 94P/Russell MPEC 2024-R10 +0095P 2046 08 13.2434 8.514205 0.378406 339.3543 209.1924 6.9286 20250704 6.5 2.0 95P/Chiron MPC 75717 +0096P 2023 01 31.3395 0.116069 0.961707 14.7371 93.9629 57.5868 20250704 13.0 4.8 96P/Machholz MPC182887 +0096P b 2023 01 31.1925 0.115937 0.961737 94.0190 14.5836 57.5039 20250704 13.0 4.8 96P-B/Machholz MPC106348 +0096P c 2012 07 14.6812 0.123794 0.958898 15.5380 94.3495 58.5311 9.0 4.0 96P-C/Machholz MPC103849 +0097P 2022 02 15.9639 2.576115 0.459932 230.1996 184.0736 17.9378 20250704 5.5 6.0 97P/Metcalf-Brewington MPEC 2024-GJ3 +0098P 2028 05 13.1408 1.636012 0.567209 157.7360 114.5010 10.6572 20250704 9.0 8.0 98P/Takamizawa MPEC 2021-W31 +0099P 2022 04 9.0245 4.699760 0.228764 174.5343 28.0642 4.3391 20250704 4.5 6.0 99P/Kowal MPEC 2024-R10 +0100P 2022 08 10.1292 2.019270 0.411350 181.9231 37.6857 25.5673 20250704 9.0 8.0 100P/Hartley MPEC 2023-OA6 +0101P 2020 01 12.9860 2.352736 0.595580 277.9848 116.1229 5.0485 20250704 10.0 4.8 101P/Chernykh MPEC 2024-R10 +0101P b 2020 01 30.7551 2.357792 0.595791 115.6047 278.5064 5.0502 20250704 9.0 4.0 101P-B/Chernykh MPC105241 +0102P 2028 07 10.7581 2.078281 0.455980 20.6748 339.3953 25.8538 20250704 6.5 8.0 102P/Shoemaker MPEC 2022-C56 +0103P 2023 10 12.4193 1.065310 0.693496 181.3280 219.7570 13.6077 20250704 8.5 8.0 103P/Hartley MPC184417 +0104P 2027 10 12.8004 1.072016 0.665899 227.3049 207.1827 5.7009 20250704 16.0 4.0 104P/Kowal MPEC 2023-G31 +0105P 2025 01 22.7495 2.052069 0.409152 46.3308 192.3932 9.1672 20250704 11.5 6.0 105P/SingerBrewster MPEC 2025-MC0 +0106P 2028 12 12.0085 1.531754 0.593519 353.7977 48.8660 19.5333 20250704 14.0 4.8 106P/Schuster MPEC 2024-R10 +0107P 2026 11 25.5917 0.969138 0.630953 95.5171 266.7271 2.7986 20250704 9.0 4.0 107P/Wilson-Harrington MPEC 2015-M77 +0108P 2028 12 8.3466 1.663488 0.555675 354.5328 50.3014 11.4322 20250704 8.0 12.0 108P/Ciffreo MPEC 2022-P82 +0109P 1992 12 20.6114 0.972309 0.962893 153.2801 139.7158 113.0987 20250704 4.0 6.0 109P/Swift-Tuttle 105, 420 +0110P 2028 08 22.2438 2.453253 0.319223 167.5620 287.4819 11.7115 20250704 1.0 12.0 110P/Hartley MPEC 2023-KD6 +0111P 2021 06 19.8815 3.707918 0.107170 1.4386 89.8101 4.2262 20250704 5.0 8.0 111P/Helin-Roman-Crockett MPC 75718 +0112P 2026 09 21.8038 1.441242 0.590835 21.5527 31.8117 24.2023 20250704 14.0 6.0 112P/Urata-Niijima MPEC 2021-S45 +0113P 2022 06 1.8063 2.145009 0.419659 115.7391 306.6203 5.2876 20250704 13.5 4.0 113P/Spitaler MPEC 2024-JU4 +0114P 2026 09 14.9536 1.571204 0.556142 172.8123 271.0264 18.3039 20250704 11.5 6.0 114P/Wiseman-Skiff MPEC 2023-A50 +0115P 2029 05 24.6434 2.058989 0.517914 120.9160 175.9789 11.6818 20250704 10.5 6.0 115P/Maury MPEC 2023-J29 +0116P 2022 07 16.7535 2.193704 0.370705 173.1571 20.9595 3.6046 20250704 2.5 10.0 116P/Wild MPEC 2024-RQ6 +0117P 2022 07 12.2057 3.078059 0.252522 224.7270 58.8184 8.6778 20250704 2.5 8.0 117P/Helin-Roman-Alu MPC182887 +0118P 2022 11 24.7596 1.829186 0.453808 314.9526 142.0539 10.0917 20250704 12.0 4.0 118P/Shoemaker-Levy MPEC 2024-MB8 +0119P 2022 08 12.4240 2.330947 0.388099 322.2722 104.5424 7.3929 20250704 3.5 8.0 119P/Parker-Hartley MPEC 2024-R10 +0120P 2029 04 4.7414 2.484643 0.374140 36.7855 358.7043 8.4813 20250704 12.0 4.0 120P/Mueller MPEC 2022-CN4 +0121P 2023 06 30.7425 3.732503 0.186711 11.9715 94.1049 20.1621 20250704 6.5 8.0 121P/Shoemaker-Holt MPEC 2025-MC0 +0122P 1995 10 2.3452 0.659421 0.962604 13.0044 79.7415 86.0264 20250704 7.5 5.2 122P/de Vico MPC 75718 +0123P 2026 09 22.1827 2.157345 0.444545 103.9486 45.9012 15.2795 20250704 12.2 4.0 123P/West-Hartley MPEC 2021-F20 +0124P 2026 06 23.6187 1.734452 0.486416 185.1151 359.9835 31.4034 20250704 13.5 2.8 124P/Mrkos MPEC 2024-UQ8 +0125P 2024 03 7.2231 1.526408 0.511982 87.1077 153.1496 9.9858 20250704 13.0 6.0 125P/Spacewatch MPEC 2024-UA9 +0126P 2023 07 5.0293 1.710657 0.696016 356.5594 357.8571 45.8716 20250704 6.0 8.0 126P/IRAS MPEC 2024-JU4 +0127P 2022 08 9.9949 2.215188 0.358737 6.3398 13.6164 14.2952 20250704 11.0 6.0 127P/Holt-Olmstead MPEC 2024-R10 +0128P 2026 07 16.7815 3.037294 0.322362 210.4964 214.3205 4.3710 20250704 8.5 4.0 128P/Shoemaker-Holt MPC 89014 +0129P 2022 12 3.5303 3.925070 0.085933 307.8813 184.8487 3.4414 20250704 11.0 4.0 129P/Shoemaker-Levy MPEC 2025-MC0 +0130P 2024 04 15.3465 1.825582 0.461263 246.3417 70.1785 6.0587 20250704 10.0 6.0 130P/McNaught-Hughes MPC184417 +0131P 2026 02 15.6317 2.407916 0.344747 179.2448 214.1358 7.3618 20250704 11.0 4.0 131P/Mueller MPEC 2025-A40 +0132P 2021 11 12.9243 1.697074 0.564009 216.5103 173.9780 5.3777 20250704 11.0 6.0 132P/Helin-Roman-Alu MPEC 2024-BE0 +0133P 2024 05 10.1059 2.670753 0.155649 131.8731 160.1009 1.3899 20250704 15.4 2.0 133P/Elst-Pizarro MPC 94676 +0134P 2030 01 8.4700 2.600576 0.585486 18.6537 201.9906 4.3330 20250704 11.5 4.0 134P/Kowal-Vavrova MPC 89012 +0135P 2022 04 6.0474 2.686057 0.293447 22.3728 213.0194 6.0628 20250704 7.0 8.0 135P/Shoemaker-Levy MPEC 2024-C04 +0136P 2025 01 3.4760 2.958513 0.293193 225.3253 137.4193 9.4273 20250704 11.0 4.0 136P/Mueller MPC182888 +0137P 2028 07 29.3561 1.931864 0.572952 141.2168 232.9273 4.8598 20250704 11.0 4.0 137P/Shoemaker-Levy MPEC 2023-J29 +0138P 2026 03 24.3038 1.694414 0.531542 95.6893 309.2718 10.0999 20250704 15.0 6.0 138P/Shoemaker-Levy MPEC 2016-U66 +0139P 2027 07 22.8219 3.392831 0.248302 165.9829 242.1795 2.3374 20250704 9.5 4.0 139P/Vaisala-Oterma MPEC 2020-HN5 +0140P 2031 10 5.4348 1.955197 0.695141 172.1532 343.3716 3.6942 20250704 11.5 6.0 140P/Bowell-Skiff MPEC 2015-E14 +0141P 2026 04 22.9758 0.807397 0.735887 153.6441 241.7760 13.9616 20250704 12.0 12.0 141P/Machholz MPEC 2024-R10 +0141P a 2026 04 23.3402 0.807402 0.735905 241.9288 153.5029 13.9417 20250704 12.0 12.0 141P-A/Machholz MPEC 2015-KD9 +0141P b 2026 04 15.3578 0.807701 0.735666 241.8177 153.5790 13.9857 20250704 9.0 4.0 141P-B/Machholz MPC 24216 +0141P d 2026 05 18.5884 0.806756 0.736850 242.1773 153.2287 13.8335 20250704 9.0 4.0 141P-D/Machholz MPC 37026 +0141P e 1994 09 19.2500 0.752528 0.750233 149.2667 246.1856 12.8152 9.0 4.0 141P-E/Machholz MPEC 2015-R12 +0141P f 1994 09 19.1963 0.752528 0.750009 149.2374 246.1881 12.7898 9.0 4.0 141P-F/Machholz MPEC 2015-R12 +0141P g 1994 09 19.1048 0.752528 0.749643 149.0784 246.3146 12.8259 9.0 4.0 141P-G/Machholz MPEC 2015-R12 +0141P h 2015 08 24.3866 0.761562 0.746822 149.4500 246.0900 12.8431 18.5 4.0 141P-H/Machholz MPC 95735 +0141P i 2026 04 13.6110 0.807234 0.735134 241.9385 153.4577 13.9417 20250704 17.5 4.0 141P-I/Machholz MPEC 2022-SU8 +0142P 2021 05 11.2303 2.522037 0.495941 174.0619 175.9599 12.2446 20250704 8.5 6.0 142P/Ge-Wang MPEC 2024-C04 +0143P 2026 12 26.1908 2.950506 0.382269 304.3600 242.4346 5.4373 20250704 13.5 2.0 143P/Kowal-Mrkos MPC182888 +0144P 2024 01 25.8242 1.399473 0.634966 216.3612 242.9246 3.9317 20250704 8.5 8.0 144P/Kushida MPEC 2024-YC7 +0145P 2026 01 31.9125 1.889814 0.542460 10.4057 26.7695 11.2778 20250704 13.5 4.0 145P/Shoemaker-Levy MPEC 2025-MC0 +0146P 2024 08 5.4151 1.418521 0.647582 317.0406 53.3551 23.1176 20250704 15.0 4.0 146P/Shoemaker-LINEAR MPC184418 +0147P 2023 12 7.4899 3.160568 0.211788 348.6069 91.6675 2.3115 20250704 14.0 4.0 147P/Kushida-Muramatsu MPEC 2024-UQ8 +0148P 2022 06 14.3082 1.627666 0.550392 8.0818 89.1952 3.6589 20250704 16.0 2.0 148P/Anderson-LINEAR MPEC 2024-JU4 +0149P 2026 12 16.4271 2.790296 0.324459 30.2209 143.7534 34.2363 20250704 8.0 8.0 149P/Mueller MPEC 2023-J29 +0150P 2024 03 12.5331 1.745372 0.549227 246.1236 272.0557 18.5485 20250704 13.5 4.0 150P/LONEOS MPEC 2024-NE4 +0151P 2029 08 17.9708 2.465089 0.572518 216.1554 143.1214 4.7253 20250704 10.0 6.0 151P/Helin MPEC 2022-K19 +0152P 2022 01 13.2315 3.109625 0.306807 164.4410 91.7755 9.8798 20250704 11.5 4.0 152P/Helin-Lawrence MPC182888 +0153P 2002 03 12.6696 0.496486 0.990166 34.2176 93.8032 28.5003 20250704 9.0 4.0 153P/Ikeya-Zhang MPC 46101 +0154P 2024 06 13.2071 1.552422 0.676262 47.9283 342.9953 17.6386 20250704 2.5 12.0 154P/Brewington MPC184418 +0155P 2019 11 17.4486 1.789655 0.727682 14.5320 97.1568 6.4107 20250704 10.0 4.8 155P/Shoemaker MPEC 2022-YN2 +0156P 2027 04 30.4989 1.333619 0.614856 0.5267 35.3337 17.2605 20250704 15.5 2.0 156P/Russell-LINEAR MPEC 2023-J29 +0157P 2022 09 10.1748 1.572509 0.556793 155.1797 287.4976 12.4245 20250704 10.0 4.0 157P/Tritton MPEC 2024-D33 +0157P b 2028 02 25.6889 1.551706 0.499892 287.2116 153.8796 12.4254 20250704 15.7 4.0 157P-B/Tritton MPEC 2022-VC5 +0158P 2022 09 10.7123 5.023860 0.117184 229.9077 124.3900 7.4561 20250704 9.0 4.0 158P/Kowal-LINEAR MPC182888 +0159P 2032 07 26.2781 3.615432 0.382529 4.7297 54.9388 23.4831 20250704 10.0 4.0 159P/LONEOS MPEC 2024-DC6 +0160P 2027 04 7.2212 1.795422 0.524993 12.7790 333.3479 15.5947 20250704 15.5 2.0 160P/LINEAR MPEC 2022-K19 +0161P 2026 11 27.9611 1.266711 0.835833 47.0670 1.5129 95.8182 20250704 8.5 6.0 161P/Hartley-IRAS MPC 75721 +0162P 2026 05 17.8245 1.289494 0.582933 357.2382 30.8758 27.5532 20250704 12.0 4.0 162P/SidingSpring MPEC 2025-MC0 +0163P 2026 11 23.9191 2.055426 0.453485 349.6376 102.0724 12.7212 20250704 14.5 4.0 163P/NEAT MPEC 2021-S45 +0164P 2025 05 27.4013 1.675097 0.541362 325.9511 88.2691 16.2773 20250704 11.0 4.0 164P/Christensen MPEC 2024-TD8 +0165P 2000 06 14.5845 6.782479 0.619272 125.8859 0.6705 15.9089 20250704 11.5 2.0 165P/LINEAR MPC 75721 +0166P 2002 06 6.1310 8.543615 0.382801 321.8558 64.4398 15.3775 20250704 5.5 4.0 166P/NEAT MPC 75722 +0167P 2001 03 26.1250 11.898357 0.267839 344.4340 295.8375 19.0747 20250704 9.5 2.0 167P/CINEOS MPEC 2023-J29 +0168P 2026 05 26.2478 1.358433 0.621264 15.1009 355.3875 21.5948 20250704 15.5 4.0 168P/Hergenrother MPEC 2023-J29 +0169P 2026 09 21.3346 0.603951 0.768036 218.1231 176.0566 11.2866 20250704 16.0 2.0 169P/NEAT MPC184418 +0170P 2023 04 15.6178 2.913523 0.305286 224.7164 142.6368 10.1303 20250704 12.0 4.0 170P/Christensen MPC184418 +0171P 2025 09 25.0392 1.766316 0.502806 347.0870 101.6999 21.9508 20250704 13.5 4.0 171P/Spahr MPC102102 +0172P 2025 11 2.5031 3.358156 0.204920 208.8917 30.8826 11.2230 20250704 13.0 4.0 172P/Yeung MPEC 2025-MC0 +0173P 2021 12 17.9105 4.216014 0.262382 29.2958 100.3458 16.4935 20250704 7.5 4.0 173P/Mueller MPEC 2023-N01 +0174P 2015 04 19.6935 5.865876 0.454790 163.4282 173.3407 4.3408 20250704 9.4 2.0 174P/Echeclus MPC 92985 +0175P 2026 09 2.9912 2.304042 0.375877 74.6524 109.8123 4.9280 20250704 14.0 4.0 175P/Hergenrother MPC114608 +0176P 2022 11 19.7924 2.582475 0.191810 34.4730 345.6301 0.2312 20250704 15.1 2.0 176P/LINEAR MPC 89015 +0177P 2006 08 29.8368 1.122283 0.954210 60.7638 271.8601 31.0053 20250704 15.0 4.0 177P/Barnard MPEC 2020-L06 +0178P 2027 06 21.4076 1.880797 0.482273 297.9628 102.7845 11.0926 20250704 13.5 4.0 178P/Hug-Bell MPEC 2024-R10 +0179P 2022 05 31.8329 4.123946 0.305397 297.2174 115.5079 19.8899 20250704 2.5 8.0 179P/Jedicke MPEC 2024-EF7 +0180P 2023 07 12.1454 2.499164 0.353846 94.6023 84.5587 16.8618 20250704 11.0 4.0 180P/NEAT MPEC 2024-F34 +0181P 2022 01 8.2492 1.164643 0.699773 336.2919 35.4415 17.4739 20250704 11.5 4.0 181P/Shoemaker-Levy MPC 89012 +0182P 2027 06 5.3732 0.990915 0.663950 54.2100 72.4538 16.2308 20250704 18.0 4.0 182P/LONEOS MPEC 2024-UQ8 +0183P 2027 09 15.3577 4.225582 0.102699 162.5946 3.5239 18.7253 20250704 12.5 2.0 183P/Korlevic-Juric MPEC 2024-VJ2 +0184P 2028 03 23.8336 1.711222 0.549782 186.5607 173.2671 4.5699 20250704 13.5 4.0 184P/Lovas MPEC 2020-W26 +0185P 2023 07 12.7829 0.931790 0.699397 181.9207 214.1228 14.0095 20250704 15.0 4.0 185P/Petriew MPEC 2024-F91 +0186P 2029 08 24.5729 4.255412 0.123762 268.4439 325.8680 28.6596 20250704 7.5 4.0 186P/Garradd MPEC 2022-X67 +0187P 2028 02 4.2104 3.839204 0.156184 131.6905 109.8457 13.6679 20250704 9.0 4.0 187P/LINEAR MPEC 2020-SI8 +0188P 2026 04 13.2751 2.546183 0.416689 26.8312 358.9133 10.5249 20250704 11.5 4.0 188P/LINEAR-Mueller MPEC 2025-MC0 +0189P 2027 09 13.4489 1.203020 0.590765 16.1825 281.6856 20.1209 20250704 19.0 4.0 189P/NEAT MPEC 2022-QD9 +0190P 2024 12 24.1577 2.019321 0.522754 50.5555 335.4680 2.1748 20250704 13.0 4.0 190P/Mueller MPC182889 +0191P 2028 02 29.6799 2.238772 0.385111 284.2680 98.1787 8.8395 20250704 13.0 4.0 191P/McNaught MPEC 2024-TD8 +0192P 2024 05 24.5009 1.462623 0.773386 313.0363 51.5756 24.5792 20250704 15.0 4.0 192P/Shoemaker-Levy MPC182889 +0193P 2028 06 1.4375 2.174275 0.392591 8.1145 335.1857 10.6789 20250704 14.0 4.0 193P/LINEAR-NEAT MPEC 2024-R10 +0194P 2024 02 4.3256 1.800065 0.563397 128.6209 349.5100 11.8034 20250704 16.0 4.0 194P/LINEAR MPEC 2024-GJ3 +0195P 2025 08 5.6876 4.440554 0.310855 250.6099 243.0968 36.4163 20250704 8.5 4.0 195P/Hill MPEC 2025-MC0 +0196P 2022 10 29.1628 2.179100 0.427506 12.1386 24.1245 19.2946 20250704 13.5 4.0 196P/Tichy MPEC 2024-GJ3 +0197P 2027 11 20.9421 1.108391 0.618901 189.9578 66.1913 25.2995 20250704 16.5 2.0 197P/LINEAR MPEC 2023-UR6 +0198P 2025 10 7.1103 1.994792 0.444686 69.0495 358.4688 1.3400 20250704 12.5 4.0 198P/ODAS MPEC 2024-VJ2 +0199P 2023 08 7.3319 2.910989 0.504383 191.7627 92.3436 24.9393 20250704 10.0 4.0 199P/Shoemaker MPEC 2024-Q20 +0200P 2030 08 6.3435 3.313208 0.331129 134.3839 234.8108 12.0950 20250704 9.0 4.0 200P/Larsen MPEC 2022-C56 +0201P 2027 07 20.1434 1.216036 0.637505 19.8042 41.5242 5.7369 20250704 14.0 4.0 201P/LONEOS MPC 93588 +0202P 2024 05 17.2913 3.069977 0.251062 274.4968 177.3004 2.1418 20250704 13.5 4.0 202P/Scotti MPC182889 +0203P 2030 04 8.8812 3.191416 0.316387 154.9398 290.2213 2.9760 20250704 14.5 2.0 203P/Korlevic MPEC 2025-A40 +0204P 2022 11 17.2977 1.834069 0.488292 356.7299 108.4731 6.5980 20250704 14.0 4.0 204P/LINEAR-NEAT MPEC 2024-JU4 +0205P 2028 09 13.5567 1.533544 0.567180 154.1526 179.6236 15.3003 20250704 13.0 4.0 205P/Giacobini MPEC 2023_O39 +0206P 2027 09 13.0061 1.567234 0.551123 189.5773 202.3409 33.6168 20250704 19.0 4.0 206P/Barnard-Boattini MPC 75725 +0207P 2024 01 31.8744 0.938409 0.758528 273.0301 198.1370 10.1985 20250704 16.0 4.0 207P/NEAT MPEC 2024-NE4 +0208P 2024 08 24.2828 2.529366 0.374178 310.7869 36.3302 4.4108 20250704 12.5 4.0 208P/McMillan MPC182889 +0209P 2024 07 14.4916 0.964145 0.674032 152.4806 62.7640 21.2829 20250704 17.0 2.0 209P/LINEAR MPEC 2024-TD8 +0210P 2025 11 22.7192 0.524444 0.834072 345.9176 93.8249 10.2819 20250704 13.5 4.0 210P/Christensen MPC105242 +0211P 2022 10 5.1877 2.326317 0.344494 4.3518 117.1007 18.9249 20250704 12.5 4.0 211P/Hill MPEC 2024-JU4 +0212P 2024 04 25.1531 1.612922 0.586758 14.0620 97.9717 22.1491 20250704 17.0 2.0 212P/NEAT MPEC 2024-GJ3 +0213P 2023 11 13.6463 1.981395 0.409875 6.5683 310.8808 10.4355 20250704 10.5 4.0 213P/VanNess MPC184418 +0213P b 2023 11 13.5153 1.981746 0.409749 6.5874 310.8773 10.4348 20250704 17.0 4.0 213P-B/Van Ness MPEC 2025-GB9 +0213P c 2023 11 12.5762 1.980779 0.409699 312.1927 5.1779 10.3501 20250704 17.5 4.0 213P-C/Van Ness MPC 76570 +0214P 2022 09 26.3906 1.857820 0.486287 190.1199 348.2118 15.1930 20250704 13.0 4.0 214P/LINEAR MPC 92986 +0215P 2028 11 24.2578 3.620793 0.164925 262.2424 56.6782 10.5763 20250704 11.0 4.0 215P/NEAT MPC184418 +0216P 2024 01 6.9991 2.126944 0.449022 151.7712 359.7802 9.0616 20250704 13.0 4.0 216P/LINEAR MPEC 2024-N80 +0217P 2025 05 24.9453 1.226376 0.689095 247.0372 125.3712 12.8655 20250704 12.0 4.0 217P/LINEAR MPEC 2025-MC0 +0218P 2026 03 3.8753 1.129821 0.630911 61.4250 174.6730 2.7266 20250704 16.0 4.0 218P/LINEAR MPEC 2022-K19 +0219P 2024 02 15.2853 2.355726 0.355968 108.0129 230.8765 11.5112 20250704 11.0 4.0 219P/LINEAR MPC182889 +0220P 2026 06 14.1436 1.558941 0.500389 180.5824 150.0908 8.1208 20250704 15.0 4.0 220P/McNaught MPEC 2024-A43 +0221P 2028 04 1.8321 1.617091 0.522277 42.0290 226.4338 10.8201 20250704 14.5 4.0 221P/LINEAR MPEC 2022-UY9 +0222P 2024 05 12.8881 0.825934 0.714818 346.2739 6.7525 5.0975 20250704 20.0 4.0 222P/LINEAR MPC 92277 +0223P 2027 07 24.7745 2.427427 0.416240 37.9836 346.7040 27.0059 20250704 12.0 4.0 223P/Skiff MPEC 2023-A50 +0224P 2022 09 30.1474 2.049197 0.405551 16.8159 40.0412 13.3012 20250704 15.5 4.0 224P/LINEAR-NEAT MPEC 2024-L77 +0225P 2023 08 7.8450 1.319841 0.638147 3.9062 14.2110 21.3611 20250704 18.0 4.0 225P/LINEAR MPEC 2024-F91 +0226P 2023 12 27.0565 1.774035 0.528848 341.0328 54.0134 44.0448 20250704 12.5 4.0 226P/Pigott-LINEAR-Kowalski MPEC 2024-MB8 +0227P 2024 03 8.3297 1.623582 0.527709 105.5946 36.8014 7.5072 20250704 16.5 2.0 227P/Catalina-LINEAR MPEC 2024-R10 +0228P 2028 09 5.1179 3.423626 0.177427 114.8048 30.9543 7.9158 20250704 14.1 4.0 228P/LINEAR MPEC 2022-HC2 +0229P 2025 03 5.8170 2.440411 0.378057 224.2295 157.8789 26.0963 20250704 13.0 4.0 229P/Gibbs MPC182889 +0230P 2028 08 20.5007 1.570550 0.545441 313.5821 106.9263 15.4722 20250704 13.0 4.0 230P/LINEAR MPEC 2025-MC0 +0231P 2027 08 4.5559 3.087160 0.239995 43.6956 132.7777 12.2726 20250704 14.5 2.0 231P/LINEAR-NEAT MPEC 2023-SQ0 +0232P 2028 09 20.5845 2.967480 0.336127 53.3042 56.0094 14.6429 20250704 11.5 4.0 232P/Hill MPC112394 +0233P 2026 01 8.1358 1.776702 0.412988 27.0242 74.8975 11.2889 20250704 15.0 4.0 233P/La Sagra MPEC 2021-N06 +0234P 2024 10 23.6747 2.820887 0.257304 357.4450 179.5641 11.5336 20250704 12.0 4.0 234P/LINEAR MPEC 2025-MC0 +0235P 2025 12 22.6249 1.978023 0.426068 352.1721 200.1751 9.8127 20250704 12.0 4.0 235P/LINEAR MPC184419 +0236P 2025 02 3.8455 1.828145 0.509338 119.4315 245.5692 16.3550 20250704 14.0 4.0 236P/LINEAR MPEC 2024-P23 +0237P 2023 05 14.3287 1.995993 0.432535 25.5430 245.3584 14.0098 20250704 14.5 2.0 237P/LINEAR MPC182890 +0238P 2028 01 24.0579 2.373822 0.250589 324.2642 51.6491 1.2637 20250704 14.5 4.0 238P/Read MPEC 2024-L77 +0239P 2028 06 17.6590 1.644834 0.631512 220.3855 255.9360 11.3065 20250704 17.5 2.0 239P/LINEAR MPEC 2021-F20 +0240P 2025 12 19.9593 2.121798 0.450292 352.0737 74.9115 23.5372 20250704 11.0 4.0 240P/NEAT MPEC 2025-MC0 +0241P 2021 07 26.1900 1.921260 0.610119 111.6171 305.4164 21.0949 20250704 13.5 4.0 241P/LINEAR MPEC 2022-J42 +0242P 2024 12 23.3963 3.971702 0.282853 244.9893 180.2375 32.4231 20250704 8.0 4.0 242P/Spahr MPEC 2025-MC0 +0243P 2026 02 25.5397 2.448036 0.360294 283.7033 87.6476 7.6441 20250704 12.5 4.0 243P/NEAT MPEC 2022-K19 +0244P 2022 11 20.1527 3.924582 0.199826 93.5160 354.0069 2.2576 20250704 9.0 4.0 244P/Scotti MPEC 2024-L77 +0245P 2026 03 31.1898 2.205485 0.455816 316.5000 316.8849 21.1713 20250704 14.0 4.0 245P/WISE MPEC 2022-CN4 +0246P 2029 10 22.9481 3.360567 0.218847 185.4303 74.1990 17.4513 20250704 10.5 4.0 246P/NEAT MPEC 2024-YC7 +0247P 2026 10 25.9553 1.484088 0.625589 47.5073 53.9858 13.6581 20250704 16.5 2.0 247P/LINEAR MPEC 2021-F20 +0248P 2025 09 14.9260 2.157755 0.639313 209.9910 207.7960 6.3519 20250704 14.0 4.0 248P/Gibbs MPEC 2025-MC0 +0249P 2025 02 1.7001 0.499573 0.819391 65.7558 239.0399 8.3842 20250704 15.5 4.0 249P/LINEAR MPEC 2022-YN2 +0250P 2025 05 16.7224 2.272322 0.398309 45.7039 73.3023 13.1519 20250704 14.5 4.0 250P/Larson MPC182890 +0251P 2024 02 13.1383 1.741164 0.504200 31.1915 219.3372 23.3885 20250704 16.5 2.0 251P/LINEAR MPEC 2024-TD8 +0252P 2026 11 7.7305 1.003688 0.671058 343.3742 190.9063 10.4200 20250704 17.5 4.0 252P/LINEAR MPEC 2021-S45 +0253P 2024 10 21.0338 2.026318 0.415259 230.8501 146.8273 4.9454 20250704 14.5 4.0 253P/PANSTARRS MPC182890 +0254P 2020 09 28.3434 3.148835 0.318451 219.7232 129.1789 32.5383 20250704 11.0 4.0 254P/McNaught MPC184419 +0255P 2027 09 25.5064 0.847190 0.712062 186.0457 275.6367 13.4054 20250704 9.0 4.0 255P/Levy NK 2214 +0256P 2023 03 11.9410 2.697412 0.418027 124.0629 81.3240 27.6233 20250704 14.0 2.0 256P/LINEAR MPEC 2024-L77 +0257P 2028 01 1.6894 2.152451 0.428761 117.7232 207.7291 20.2154 20250704 11.5 4.0 257P/Catalina MPEC 2023-A50 +0258P 2029 08 28.8006 3.468967 0.209575 25.6116 126.2361 6.7512 20250704 13.0 4.0 258P/PANSTARRS MPEC 2021-U31 +0259P 2026 08 12.1552 1.804889 0.338734 257.4858 51.3733 15.8981 20250704 15.5 4.0 259P/Garradd MPC106349 +0260P 2026 08 4.9948 1.417646 0.608779 18.4929 349.3035 15.0429 20250704 13.5 4.0 260P/McNaught MPEC 2022-O01 +0261P 2025 12 27.4041 2.014217 0.422797 67.3632 291.0506 6.0733 20250704 14.0 4.0 261P/Larson MPEC 2025-MC0 +0262P 2030 12 15.1166 1.264261 0.815956 171.0696 217.8862 29.2477 20250704 13.5 4.0 262P/McNaught-Russell MPC 82322 +0263P 2023 01 30.9286 1.234365 0.594070 35.0220 105.5040 11.5267 20250704 18.0 4.0 263P/Gibbs MPEC 2024-L77 +0264P 2027 03 15.6341 2.658271 0.340317 341.1386 219.1267 25.1362 20250704 13.0 4.0 264P/Larsen MPC114608 +0265P 2029 11 26.2074 1.505401 0.646694 33.5653 342.9202 14.3402 20250704 14.5 4.0 265P/LINEAR MPC 79870 +0266P 2026 12 7.3185 2.325054 0.340941 97.7945 4.9464 3.4284 20250704 14.7 4.0 266P/Christensen MPEC 2021-F20 +0267P 2024 04 24.9471 1.235244 0.614944 114.1969 228.5437 6.1396 20250704 19.5 4.0 267P/LONEOS MPC114608 +0268P 2024 12 18.4844 2.412718 0.474487 0.0185 125.6323 15.6615 20250704 14.0 4.0 268P/Bernardi MPEC 2025-MC0 +0269P 2033 07 11.3667 3.998236 0.433539 225.7356 241.7635 7.0838 20250704 10.0 4.0 269P/Jedicke MPEC 2023-J29 +0270P 2030 08 16.7057 3.522712 0.470188 209.9338 223.0239 2.9248 20250704 8.0 4.0 270P/Gehrels MPC 88332 +0271P 2032 03 21.8601 4.248648 0.395855 36.6224 9.2768 6.8665 20250704 11.0 4.0 271P/van Houten-Lemmon MPC 92277 +0272P 2022 07 17.5277 2.429473 0.455520 27.8904 109.4391 18.0824 20250704 16.0 2.0 272P/NEAT MPEC 2023-D41 +0273P 2012 12 21.9005 0.813206 0.974525 20.1221 320.3832 136.3598 20250704 11.5 4.0 273P/Pons-Gambart MPC 82723 +0274P 2022 04 9.1980 2.450851 0.440254 38.4962 81.3175 15.8205 20250704 13.0 4.0 274P/Tombaugh-Tenagra MPEC 2024-GJ3 +0275P 2026 10 27.9799 1.659079 0.713771 173.8936 348.6841 21.2540 20250704 17.0 4.0 275P/Hermann MPC 81862 +0276P 2024 12 11.1289 3.898614 0.273902 199.3872 211.2485 14.7702 20250704 11.5 4.0 276P/Vorobjov MPC184419 +0277P 2028 07 25.8656 1.902158 0.506394 152.4384 276.2600 16.7931 20250704 15.1 4.0 277P/LINEAR MPEC 2021-F20 +0278P 2027 09 14.8445 1.993756 0.451981 240.7326 12.4636 6.6123 20250704 14.0 4.0 278P/McNaught MPEC 2021-S45 +0279P 2023 04 18.7372 2.142600 0.399476 5.6247 346.0984 5.0531 20250704 14.0 4.0 279P/LaSagra MPEC 2024-A43 +0280P 2023 08 4.3863 2.638484 0.416830 104.6342 131.3779 11.7754 20250704 12.5 4.0 280P/Larsen MPEC 2024-RQ6 +0281P 2023 02 4.2954 4.036946 0.173927 27.0207 87.1663 4.7176 20250704 11.0 4.0 281P/MOSS MPEC 2023-D41 +0282P 2021 10 22.5892 3.440623 0.187654 9.0849 217.6071 5.8138 20250704 13.5 2.0 282P MPC133426 +0283P 2021 09 8.3727 2.127735 0.485013 22.1444 161.1238 14.4687 20250704 16.0 2.0 283P/Spacewatch MPEC 2022-K19 +0284P 2028 10 1.6398 2.301953 0.374296 202.4617 144.2639 11.8529 20250704 13.0 4.0 284P/McNaught MPEC 2024-D33 +0285P 2023 01 11.7915 1.720769 0.618056 178.3841 185.5143 25.0325 20250704 15.0 4.0 285P/LINEAR MPEC 2024-L77 +0286P 2022 05 12.7010 2.317809 0.431432 23.9797 283.5766 17.2320 20250704 14.0 4.0 286P/Christensen MPEC 2024-LE0 +0287P 2023 07 10.9780 3.045931 0.272862 190.5453 138.6512 16.3474 20250704 13.5 4.0 287P/Christensen MPEC 2025-A40 +0288P 2027 06 29.0024 2.441705 0.199596 280.2840 83.1063 3.2383 20250704 16.0 2.0 288P MPC133426 +0289P 2025 04 14.3164 0.954323 0.686450 9.8749 68.8907 5.9002 20250704 19.0 4.0 289P/Blanpain MPEC 2024-O39 +0290P 2029 07 22.2060 2.309858 0.628255 181.8614 302.6716 20.0448 20250704 10.5 4.0 290P/Jager MPC 95214 +0291P 2023 05 3.9869 2.567496 0.433851 173.5663 237.6620 6.3096 20250704 13.0 4.0 291P/NEAT MPEC 2024-YC7 +0292P 2029 03 3.7232 2.500057 0.589873 319.6624 90.8953 24.3226 20250704 12.5 4.0 292P/Li MPEC 2022-K19 +0293P 2027 11 29.0349 2.111436 0.419549 40.9890 78.3603 9.0609 20250704 14.5 4.0 293P/Spacewatch MPEC 2022-L66 +0294P 2025 08 11.1921 1.273047 0.600939 237.5853 309.6005 17.7430 20250704 15.5 4.0 294P/LINEAR MPC184419 +0295P 2026 07 22.7323 2.026030 0.617631 73.0443 7.3800 21.0852 20250704 12.0 4.0 295P/LINEAR MPEC 2022-K19 +0296P 2027 03 20.3891 1.782952 0.486240 350.2866 263.5226 25.3713 20250704 14.0 4.0 296P/Garradd MPEC 2021-N06 +0297P 2027 10 19.9504 2.556886 0.283980 142.4030 92.1760 11.2462 20250704 15.0 4.0 297P/Beshore MPC102956 +0298P 2027 06 24.7549 2.199710 0.386942 100.6216 52.7852 7.8724 20250704 15.0 4.0 298P/Christensen MPC114609 +0299P 2024 04 29.9912 3.155735 0.280933 323.6129 271.5804 10.4689 20250704 11.5 4.0 299P/Catalina-PANSTARRS MPEC 2025-MC0 +0300P 2027 09 14.1266 0.830073 0.692139 222.8766 95.6225 5.6766 20250704 16.0 4.0 300P/Catalina MPEC 2023-VM5 +0301P 2028 05 17.0638 2.379936 0.586252 193.4295 351.0621 10.3287 20250704 13.0 4.0 301P/LINEAR-NEAT MPC 89014 +0302P 2025 03 9.3921 3.288629 0.229311 208.6243 121.7158 6.0357 20250704 12.5 4.0 302P/Lemmon-PANSTARRS MPEC 2025-MC0 +0303P 2026 02 19.9179 2.468168 0.510259 357.0308 347.9481 7.0163 20250704 13.5 4.0 303P/NEAT MPC 92278 +0304P 2026 03 18.2008 1.257202 0.600839 335.2807 58.9374 2.6056 20250704 16.5 4.0 304P/Ory MPEC 2022-K19 +0305P 2024 11 17.1334 1.418159 0.694082 147.3992 240.0968 11.6704 20250704 18.0 4.0 305P/Skiff MPC182890 +0306P 2025 08 1.6484 1.272971 0.592565 0.8983 341.3516 8.3030 20250704 19.0 4.0 306P/LINEAR MPC 92278 +0307P 2028 12 2.3094 1.881235 0.674981 222.2557 158.1108 4.4345 20250704 15.0 4.0 307P/LINEAR MPC 92278 +0308P 2032 04 30.7055 4.197750 0.364116 333.7592 63.0996 4.8520 20250704 13.0 2.0 308P/Lagerkvist-Carsenty MPEC 2022-C56 +0309P 2024 03 28.9451 1.670218 0.618207 49.9195 10.1388 17.0196 20250704 15.0 4.0 309P/LINEAR MPC184419 +0310P 2023 10 23.1186 2.416318 0.422057 31.5167 8.8834 13.1202 20250704 13.5 4.0 310P/Hill MPC182891 +0311P 2024 01 1.8952 1.935961 0.115481 144.2951 279.1686 4.9713 20250704 17.0 4.0 311P/PANSTARRS MPC184419 +0312P 2027 03 15.4981 1.990949 0.426654 207.6970 144.6347 19.7459 20250704 16.0 4.0 312P/NEAT MPEC 2024-NE4 +0313P 2025 12 2.7414 2.421607 0.234452 254.9870 105.9254 10.9810 20250704 15.0 4.0 313P/Gibbs MPEC 2024-N80 +0314P 2016 10 13.8324 4.214549 0.418602 213.8673 267.6232 3.9921 20250704 9.5 4.0 314P/Montani MPC105243 +0315P 2027 11 16.5068 2.358899 0.522106 65.9212 68.6363 17.7352 20250704 11.0 4.0 315P/LONEOS MPEC 2023-J29 +0316P 2024 10 3.8536 3.717207 0.156376 186.9300 245.8771 9.8723 20250704 13.5 4.0 316P/LONEOS-Christensen MPC182891 +0317P 2025 10 30.8651 1.266615 0.572019 334.8889 275.4727 11.9747 20250704 17.5 4.0 317P/WISE MPEC 2020-C98 +0318P 2015 10 22.3491 2.455728 0.673223 313.2996 35.6084 17.8638 20250704 8.5 6.0 318P/McNaught-Hartley MPC102103 +0319P 2022 03 30.5522 1.188236 0.666456 203.5916 111.3656 15.0971 20250704 15.0 4.0 319P/Catalina-McNaught MPC184420 +0320P 2026 06 27.8520 0.975490 0.684915 0.7574 295.9406 4.9028 20250704 20.5 4.0 320P/McNaught MPC 96281 +0321P 2023 10 26.4906 0.046006 0.981005 172.7401 165.0263 20.0551 20250704 20.0 4.0 321P/SOHO MPC105243 +0322P 2023 08 21.1682 0.050360 0.979926 57.0856 351.3360 11.4471 20250704 19.0 4.0 322P/SOHO MPC102103 +0323P 2025 03 14.2328 0.040377 0.983454 353.3282 323.9435 5.2123 20250704 20.0 4.0 323P/SOHO MPC182891 +0323P b 2025 12 16.2376 0.040087 0.986129 353.9671 323.4636 5.4613 20250704 26.0 4.0 323P-B/SOHO MPEC 2024-F21 +0323P c 2025 04 7.1016 0.039783 0.984770 353.2140 324.1853 5.3384 20250704 27.0 4.0 323P-C/SOHO MPEC 2024-F21 +0324P 2026 10 14.7439 2.624073 0.152792 57.4120 270.5690 21.3993 20250704 13.0 4.0 324P/LaSagra MPEC 2021-W31 +0325P 2022 03 23.8755 1.465738 0.587080 344.9096 256.8587 16.8458 20250704 14.0 4.0 325P/Yang-Gao MPEC 2024-LE0 +0326P 2023 12 28.2395 2.760625 0.320523 278.0306 99.7611 2.4738 20250704 13.5 4.0 326P/Hill MPEC 2024-LE0 +0327P 2022 09 1.8346 1.558832 0.562502 185.0394 173.9987 36.2302 20250704 16.0 4.0 327P/VanNess MPEC 2024-M41 +0328P 2024 07 27.9277 1.872203 0.553170 30.6717 341.5404 17.6815 20250704 14.5 4.0 328P/LONEOS-Tucker MPEC 2024-YC7 +0329P 2027 09 25.6143 1.664014 0.678880 343.6040 87.6875 21.7189 20250704 13.5 4.0 329P/LINEAR-Catalina MPC101101 +0330P 2033 09 5.4845 2.972771 0.550602 188.8383 293.0840 15.7404 20250704 12.0 4.0 330P/Catalina MPEC 2023-J29 +0331P 2025 12 24.6869 2.878493 0.041441 185.6178 216.7423 9.7408 20250704 12.0 4.0 331P/Gibbs MPEC 2024-Q20 +0332P 2027 01 19.7074 1.574327 0.489860 152.2978 3.7545 9.3859 20250704 18.0 4.0 332P/Ikeya-Murakami MPEC 2016-K18 +0332P a 2027 01 19.7089 1.574294 0.489868 3.7384 152.3148 9.3857 20250704 9.0 4.0 332P-A/Ikeya-Murakami MPEC 2016-K18 +0332P b 2016 03 17.1650 1.572891 0.489707 152.3711 3.8028 9.3805 19.0 4.0 332P-B/Ikeya-Murakami MPEC 2016-EI8 +0332P c 2027 01 19.5985 1.574260 0.489874 3.7389 152.3061 9.3848 20250704 16.5 4.0 332P-C/Ikeya-Murakami MPEC 2016-K18 +0332P d 2016 03 17.2819 1.572064 0.489778 152.4393 3.7923 9.3761 19.0 4.0 332P-D/Ikeya-Murakami MPEC 2016-ED0 +0332P e 2016 03 17.0610 1.573139 0.489220 152.2825 3.8228 9.3774 21.0 4.0 332P-E/Ikeya-Murakami MPEC 2016-ED0 +0332P f 2016 03 17.8554 1.584174 0.499189 152.8203 3.4757 9.5293 21.0 4.0 332P-F/Ikeya-Murakami MPEC 2016-ED0 +0332P g 2016 03 19.5375 1.549652 0.492004 154.4000 3.6955 9.2523 19.0 4.0 332P-G/Ikeya-Murakami MPEC 2016-ED0 +0332P h 2027 01 20.1321 1.574241 0.489910 3.7386 152.3068 9.3853 20250704 19.0 4.0 332P-H/Ikeya-Murakami MPC100285 +0332P i 2016 03 17.3515 1.573073 0.489555 152.3297 3.8048 9.3791 20.5 2.0 332P-I/Ikeya-Murakami MPEC 2016-ED0 +0332P j 2016 03 17.7739 1.575357 0.494294 152.7712 3.6729 9.4296 20.5 2.0 332P-J/Ikeya-Murakami MPEC 2016-EI8 +0333P 2024 11 29.2982 1.113023 0.736284 26.0221 115.7065 132.0225 20250704 15.0 4.0 333P/LINEAR MPEC 2025-MC0 +0334P 2017 06 4.4910 4.422029 0.352011 90.0750 90.3535 20.3641 20250704 10.5 4.0 334P/NEAT MPEC 2023-J29 +0335P 2022 08 12.5548 1.620883 0.546886 162.3229 330.7907 7.2980 20250704 16.8 4.0 335P/Gibbs MPEC 2023-M14 +0336P 2028 05 14.1299 2.786719 0.446463 308.7143 298.1680 17.8784 20250704 13.5 4.0 336P/McNaught MPC105244 +0337P 2022 06 23.2463 1.741228 0.480041 166.2874 102.0418 17.0659 20250704 17.0 4.0 337P/WISE MPEC 2024-A43 +0338P 2024 08 3.3107 2.287463 0.412809 4.6354 9.7361 25.3762 20250704 12.0 4.0 338P/McNaught MPC182891 +0339P 2023 08 30.9891 1.346922 0.635816 172.6740 27.4568 5.7348 20250704 17.0 4.0 339P/Gibbs MPC101101 +0340P 2025 08 29.2588 3.057949 0.279953 36.0646 291.6597 2.0790 20250704 14.3 4.0 340P/Boattini MPC133426 +0341P 2025 04 22.7119 2.506431 0.415035 312.3634 29.9524 3.7965 20250704 12.5 4.0 341P/Gibbs MPEC 2023-J29 +0342P 2027 02 7.7011 0.051745 0.982983 27.6535 73.3066 11.6894 20250704 9.0 4.0 342P/SOHO MPC101101 +0343P 2029 11 4.6914 2.266183 0.584796 137.6085 257.0545 5.5976 20250704 14.0 4.0 343P/NEAT-LONEOS MPEC 2024-PC5 +0344P 2027 07 24.8552 2.797678 0.423733 140.6279 273.1015 3.4997 20250704 13.0 4.0 344P/Read MPEC 2023-J29 +0345P 2024 08 31.1069 3.139905 0.221381 196.7815 154.5045 2.7279 20250704 12.0 4.0 345P/LINEAR MPEC 2024-TP3 +0346P 2026 08 1.2592 2.216384 0.503908 336.0798 102.4578 22.2193 20250704 14.0 4.0 346P/Catalina MPEC 2022-K19 +0347P 2023 07 19.2306 2.206704 0.386985 98.0832 260.9905 11.7659 20250704 15.0 4.0 347P/PANSTARRS MPEC 2024-RQ6 +0348P 2027 09 19.1501 2.182452 0.307504 135.7793 312.9122 17.7430 20250704 14.0 4.0 348P/PANSTARRS MPEC 2022-ED3 +0349P 2024 05 26.9386 2.509589 0.298596 255.7461 331.7386 5.4893 20250704 14.0 4.0 349P/Lemmon MPEC 2024-LE0 +0350P 2026 03 17.4558 3.694318 0.094723 140.0633 65.2953 7.3655 20250704 14.0 4.0 350P/McNaught MPC184420 +0351P 2025 03 26.2430 3.132175 0.294646 352.5823 283.3848 12.7786 20250704 12.5 4.0 351P/Wiegert-PANSTARRS MPEC 2025-MC0 +0352P 2017 06 18.3758 2.556308 0.615924 309.3676 28.0532 21.0030 20250704 13.2 4.0 352P/Skiff MPEC 2023-J29 +0353P 2026 07 1.4712 2.211809 0.469700 230.4851 121.5090 28.4194 20250704 14.5 4.0 353P/McNaught MPEC 2020-AA5 +0354P 2023 10 14.2698 2.005317 0.124451 132.9406 320.0580 5.2508 20250704 15.5 4.0 354P/LINEAR MPEC 2024-EF7 +0355P 2024 04 1.2361 1.705925 0.507953 336.2567 51.4234 11.0460 20250704 15.5 2.0 355P/LINEAR-NEAT MPEC 2023-CD7 +0356P 2026 06 12.3367 2.674633 0.355852 226.2194 160.7909 9.6421 20250704 14.0 4.0 356P/WISE MPEC 2022-F14 +0357P 2027 10 29.6638 2.512567 0.436002 1.5088 44.5668 6.3124 20250704 15.5 4.0 357P/Hill MPC114609 +0358P 2023 11 9.4870 2.392294 0.239479 299.3246 85.6670 11.0668 20250704 18.0 4.0 358P/PANSTARRS MPEC 2024-EF7 +0359P 2027 08 24.4334 3.142588 0.323097 200.2799 149.7441 10.2618 20250704 13.5 4.0 359P/LONEOS MPC110086 +0360P 2024 10 3.8421 1.851747 0.499437 354.3360 2.1484 24.1051 20250704 19.5 6.0 360P/WISE MPEC 2025-A40 +0361P 2029 06 21.6708 2.764816 0.439519 219.1369 203.2270 13.8973 20250704 12.0 4.0 361P/Spacewatch MPEC 2023-CD7 +0363P 2024 11 13.2264 1.721007 0.518568 340.7652 146.7578 5.3938 20250704 17.5 4.0 363P/Lemmon MPC184420 +0364P 2023 05 12.5433 0.820481 0.717228 212.8495 45.8039 11.8768 20250704 17.0 2.0 364P/PANSTARRS MPEC 2024-M41 +0365P 2023 10 9.5245 1.320355 0.581671 67.4148 86.6556 9.8498 20250704 17.0 4.0 365P/PANSTARRS MPC111775 +0366P 2025 01 30.8850 2.279963 0.348655 152.9928 70.7230 8.8567 20250704 15.0 4.0 366P/Spacewatch MPC114610 +0367P 2025 01 11.5156 2.527924 0.280145 172.6798 58.6607 8.4590 20250704 17.5 2.0 367P/Catalina MPC112395 +0368P 2031 09 23.8648 2.072453 0.625593 118.9860 257.8565 15.4825 20250704 14.0 4.0 368P/NEAT MPC114610 +0369P 2027 12 18.9631 1.944533 0.555894 13.2441 47.2830 10.3192 20250704 15.0 4.0 369P/Hill MPC114610 +0370P 2018 06 12.7381 2.478791 0.615119 356.7882 55.0867 19.4163 20250704 13.0 4.0 370P/NEAT MPEC 2021-F20 +0371P 2027 04 25.9905 2.188281 0.476557 308.5662 67.2837 17.3835 20250704 16.0 4.0 371P/LINEAR-Skiff MPC114610 +0372P 2028 05 24.1708 3.830701 0.151190 325.9494 27.5491 9.5036 20250704 13.5 4.0 372P/McNaught MPEC 2020-K19 +0373P 2026 09 4.9576 2.301557 0.393822 221.1442 231.9297 13.7708 20250704 14.5 4.0 373P/Rinner MPEC 2021-F20 +0374P 2030 02 14.3547 2.666606 0.463603 51.5926 7.8626 10.7601 20250704 14.0 4.0 374P/Larson MPC114610 +0375P 2018 12 23.8851 1.883911 0.660275 119.4594 359.8270 17.3754 20250704 16.0 4.0 375P/Hill MPEC 2021-F20 +0376P 2019 09 12.9200 2.798371 0.513755 285.3380 312.8513 1.1662 20250704 12.5 4.0 376P/LONEOS MPEC 2024-RQ6 +0377P 2020 07 9.5692 5.011060 0.251486 354.9021 225.9200 9.0332 20250704 9.5 4.0 377P/Scotti MPEC 2022-N37 +0378P 2020 10 6.0619 3.374142 0.463296 193.2976 93.7911 19.1599 20250704 12.0 4.0 378P/McNaught MPEC 2025-A40 +0379P 2026 02 22.8342 2.263347 0.350177 184.7061 30.4458 12.4367 20250704 15.0 4.0 379P/Spacewatch MPC115889 +0380P 2028 08 8.2670 2.961789 0.333684 87.6558 127.6936 8.0352 20250704 12.5 4.0 380P/PANSTARRS MPEC 2023-C45 +0381P 2019 09 24.9643 2.282917 0.680493 173.8466 173.3230 28.3351 20250704 17.5 2.0 381P/LINEAR-Spacewatch MPEC 2021-J28 +0382P 2021 10 28.3449 4.328461 0.264848 162.4728 170.0054 8.2766 20250704 8.0 4.0 382P/Larson MPC182891 +0383P 2026 07 2.5883 1.425096 0.598465 133.7207 207.8548 12.3165 20250704 18.0 4.0 383P/Christensen MPEC 2022-OB6 +0384P 2024 09 19.1168 1.111854 0.616248 37.6999 354.1876 7.2842 20250704 19.5 4.0 384P/Kowalski MPC182891 +0385P 2028 08 4.9082 2.565649 0.401828 44.4677 357.0314 16.8220 20250704 13.0 4.0 385P/Hill MPEC 2021-F20 +0386P 2028 10 13.7363 2.358364 0.417535 353.1072 134.9160 15.2472 20250704 14.5 4.0 386P/PANSTARRS MPEC 2021-L04 +0387P 2030 03 13.1774 1.261910 0.736965 162.8542 259.2388 8.9379 20250704 15.0 4.0 387P/Boattini MPEC 2021-J28 +0388P 2019 07 26.8715 1.994890 0.619355 42.3753 37.0063 23.8768 20250704 13.0 4.0 388P/Gibbs MPEC 2021-S45 +0389P 2019 12 31.3755 1.656543 0.705757 249.3169 218.8474 160.0788 20250704 16.0 4.0 389P/Siding Spring MPEC 2022-OB6 +0390P 2020 03 22.2975 1.706916 0.706616 232.5635 152.1975 18.5209 20250704 12.0 4.0 390P/Gibbs MPEC 2024-EF7 +0391P 2028 05 11.0622 4.136490 0.118357 186.9076 124.7728 21.2567 20250704 8.0 4.0 391P/Kowalski MPEC 2021-F20 +0392P 2020 04 3.0410 1.941407 0.683942 71.9736 24.7971 4.9282 20250704 14.5 4.0 392P/LINEAR MPEC 2021-J28 +0393P 2030 05 7.1711 4.229249 0.119041 329.1983 36.4023 16.7830 20250704 11.0 4.0 393P/Spacewatch-Hill MPC182892 +0394P 2028 11 30.0892 2.732463 0.368407 54.4586 98.1002 8.5279 20250704 16.0 2.4 394P/PANSTARRS MPEC 2020-KB7 +0395P 2022 02 20.3859 4.241226 0.411221 100.7243 220.9599 3.5690 20250704 10.0 4.0 395P/Catalina-NEAT MPC182892 +0396P 2019 08 29.3234 3.963291 0.417047 8.3097 136.6063 5.4428 20250704 12.0 4.0 396P MPEC 2020-KB7 +0397P 2027 12 21.2048 2.281927 0.404553 14.5889 8.2069 10.9195 20250704 12.0 4.0 397P/Lemmon MPEC 2022-OB6 +0398P 2026 07 7.9257 1.300444 0.583769 127.5535 320.1345 11.0278 20250704 15.5 4.0 398P/Boattini MPEC 2021-L04 +0399P 2028 10 12.5662 2.096881 0.447267 214.4534 207.1150 13.3158 20250704 14.0 4.0 399P/PANSTARRS MPEC 2023-XP6 +0400P 2027 11 3.0442 2.103061 0.409580 238.9571 176.3451 10.9250 20250704 15.5 2.8 400P/PANSTARRS MPEC 2024-TD8 +0401P 2019 12 3.0175 2.435750 0.578335 309.3459 359.9219 12.8005 20250704 12.5 4.0 401P/McNaught MPEC 2022-K19 +0402P 2021 12 16.0692 3.943111 0.440010 327.0029 123.0429 30.8289 20250704 9.0 4.0 402P/LINEAR MPEC 2024-LE0 +0403P 2020 09 17.9188 2.693524 0.504215 163.9749 277.5604 12.3323 20250704 12.0 4.0 403P/Catalina MPEC 2021-J28 +0404P 2023 10 31.4591 4.132390 0.124124 168.9568 260.0406 9.8041 20250704 10.0 4.0 404P/Bressi MPC184420 +0405P 2027 10 29.5753 1.116393 0.690213 3.3107 112.1936 9.3792 20250704 17.5 4.0 405P/Lemmon MPEC 2021-L04 +0406P 2027 06 24.8976 1.642990 0.541005 11.5608 352.3853 1.2098 20250704 17.0 4.0 406P/Gibbs MPEC 2021-F20 +0407P 2026 07 25.5808 2.181073 0.375748 93.0901 80.2447 4.8753 20250704 14.0 4.0 407P/PANSTARRS-Fuls MPEC 2022-YN2 +0408P 2022 10 6.0521 3.472178 0.268385 226.6977 189.4514 19.3513 20250704 11.0 4.0 408P/Novichonok-Gerke MPC184420 +0409P 2021 01 28.7117 1.747916 0.710261 15.0407 143.6400 17.1494 20250704 14.0 4.0 409P/LONEOS-Hill MPEC 2022-ED3 +0410P 2021 06 24.7850 3.249096 0.511716 313.2825 139.9301 9.3881 20250704 12.5 4.0 410P/NEAT-LINEAR MPEC 2022-M21 +0411P 2021 01 25.7754 2.430318 0.581825 46.5726 77.6510 12.3886 20250704 13.5 4.0 411P/Christensen MPC184420 +0412P 2026 05 30.6293 1.621018 0.479060 155.8546 0.8410 8.9293 20250704 17.0 4.0 412P/WISE MPEC 2021-F20 +0413P 2028 10 3.3006 2.175333 0.417724 186.7298 38.9473 15.9586 20250704 14.0 4.0 413P/Larson MPC184420 +0414P 2025 09 26.3283 0.524157 0.812271 210.7110 257.8153 23.4073 20250704 19.0 4.0 414P/STEREO MPEC 2024-JU4 +0415P 2029 06 13.6759 3.304729 0.195555 345.8864 160.2577 31.8104 20250704 12.0 4.0 415P/Tenagra MPEC 2022-J42 +0416P 2029 02 23.8484 2.181460 0.455501 134.4565 355.7301 3.3636 20250704 15.5 4.0 416P/Scotti MPC184420 +0417P 2027 05 13.5670 1.495336 0.553558 126.4785 111.9644 9.9227 20250704 16.5 4.0 417P/NEOWISE MPEC 2021-W31 +0418P 2021 10 16.3547 1.710714 0.663896 307.3328 277.6164 5.7809 20250704 13.0 4.0 418P/LINEAR MPEC 2022-TA0 +0419P 2028 06 15.4757 2.567916 0.273478 187.8389 40.4069 2.7946 20250704 12.5 4.0 419P/PANSTARRS MPEC 2023-UR6 +0420P 2022 05 18.0112 2.766897 0.495100 156.4043 173.5140 14.5028 20250704 11.5 4.0 420P/Hill MPEC 2024-L77 +0421P 2021 01 23.5089 1.652411 0.674382 259.8561 55.3301 10.0757 20250704 14.0 4.0 421P/McNaught MPEC 2021-W31 +0422P 2022 01 10.6723 3.101403 0.505666 304.7566 36.0119 39.5802 20250704 11.0 4.0 422P/Christensen MPEC 2024-N80 +0423P 2021 09 26.8043 5.423284 0.122794 80.9409 33.3020 8.3424 20250704 8.0 4.0 423P/Lemmon MPEC 2023-FK0 +0424P 2021 10 30.8379 1.369022 0.690342 312.5556 51.2130 8.6814 20250704 17.0 4.0 424P/LaSagra MPEC 2022-CN4 +0425P 2021 09 20.9495 2.898435 0.543692 200.9945 210.0873 16.4133 20250704 12.0 4.0 425P/Kowalski MPEC 2024-C04 +0426P 2023 09 10.3078 2.672822 0.161028 118.3888 280.3967 17.7841 20250704 13.5 4.0 426P/PANSTARRS MPEC 2024-N80 +0428P 2027 11 17.9730 1.680833 0.518190 36.8943 299.3103 8.5028 20250704 15.0 4.0 428P/Gibbs MPEC 2023-J29 +0429P 2028 09 16.3443 1.810572 0.490827 75.7380 322.0124 7.5142 20250704 15.5 4.0 429P/LINEAR-Hill MPEC 2024-EF7 +0430P 2027 05 22.4765 1.550671 0.500296 94.4544 54.6457 4.4756 20250704 16.5 4.0 430P/Scotti MPEC 2022-L66 +0431P 2028 08 8.6959 1.817357 0.477330 200.0033 202.8377 22.3797 20250704 14.0 4.0 431P/Scotti MPEC 2025-A40 +0432P 2026 12 15.4230 2.306664 0.240827 105.2680 239.1307 10.0678 20250704 17.0 4.0 432P/PANSTARRS MPEC 2021-U31 +0434P 2021 10 27.1015 3.001544 0.274295 128.4493 288.9126 6.3363 20250704 13.0 4.0 434P/Tenagra MPEC 2024-D33 +0435P 2026 10 26.6485 2.062158 0.317549 244.2068 98.5242 18.8745 20250704 17.0 4.0 435P/PANSTARRS MPEC 2021-W31 +0436P 2021 12 7.7571 1.964867 0.669037 282.7632 87.1564 20.1993 20250704 14.5 4.0 436P/Garradd MPEC 2022-X67 +0437P 2022 08 20.2864 3.403731 0.255049 207.0670 245.8407 3.6890 20250704 13.0 4.0 437P/Lemmon-PANSTARRS MPEC 2023-B57 +0438P 2027 10 25.1379 2.257167 0.414134 58.9835 260.1086 8.2807 20250704 14.5 4.0 438P/Christensen MPEC 2025-A40 +0439P 2028 03 5.7056 1.853907 0.469080 342.1062 56.4378 7.1119 20250704 13.5 4.0 439P/LINEAR MPEC 2022-C56 +0440P 2022 03 30.4039 2.051569 0.760871 183.3017 328.8036 12.3511 20250704 15.5 4.0 440P/Kobayashi MPEC 2024-N80 +0441P 2025 09 9.3825 3.327880 0.194635 178.8667 143.5887 2.5746 20250704 13.5 4.0 441P/PANSTARRS MPEC 2025-MC0 +0442P 2022 08 17.6330 2.315815 0.532577 310.6379 31.9455 6.0574 20250704 13.5 4.0 442P/McNaught MPEC 2024-N80 +0443P 2022 10 9.3952 2.957649 0.282927 145.0726 108.9335 19.8879 20250704 13.5 4.0 443P/PANSTARRS-Christensen MPEC 2024-TD8 +0444P 2022 06 30.0061 1.537705 0.557324 172.8594 88.1848 22.7266 20250704 17.0 4.0 444P/WISE-PANSTARRS MPEC 2023-VM5 +0445P 2022 08 16.1976 2.370166 0.414184 213.2020 126.5907 1.0889 20250704 15.0 4.0 445P/Lemmon-PANSTARRS MPEC 2024-BE0 +0446P 2022 05 28.6713 1.610606 0.646778 344.6227 336.3347 16.6297 20250704 16.5 4.0 446P/McNaught MPEC 2024-NE4 +0447P 2022 08 16.1958 4.628443 0.177251 97.5034 302.6372 7.4413 20250704 12.0 4.0 447P/Sheppard-Tholen MPEC 2022-YB4 +0448P 2022 09 6.1298 2.115873 0.418144 218.8014 161.7540 12.1449 20250704 16.0 4.0 448P/PANSTARRS MPEC 2024-PC5 +0449P 2027 09 25.1263 1.872742 0.479768 176.7668 242.5219 15.4700 20250704 16.0 4.0 449P/Leonard MPEC 2024-DC6 +0450P 2027 02 2.8797 5.440262 0.314302 23.6885 124.2385 10.6927 20250704 6.5 4.0 450P/LONEOS MPC184420 +0451P 2022 11 27.9759 2.798926 0.559236 186.7938 300.8677 26.4850 20250704 15.5 4.0 451P/Christensen MPEC 2023-HD1 +0452P 2023 04 25.9960 4.177814 0.428569 37.0976 123.6653 6.4219 20250704 9.0 4.0 452P/Sheppard-Jewitt MPEC 2024-NE4 +0453P 2023 03 3.3701 2.279125 0.583147 70.8999 42.8920 27.0594 20250704 14.0 4.0 453P/WISE-Lemmon MPEC 2023-RF3 +0454P 2022 07 26.6642 2.689364 0.361422 20.1965 54.5860 19.8093 20250704 14.0 4.0 454P/PANSTARRS MPEC 2023-CD7 +0455P 2023 02 24.9171 2.193396 0.304433 237.5353 146.1801 14.1348 20250704 17.0 4.0 455P/PANSTARRS MPEC 2022-Y14 +0456P 2025 04 14.9040 2.802233 0.115880 233.0004 243.1437 16.9651 20250704 13.5 4.0 456P/PANSTARRS MPC182892 +0457P 2024 08 20.0657 2.332003 0.118384 104.3169 175.9634 5.2257 20250704 15.5 4.0 457P/Lemmon-PANSTARRS MPEC 2025-A40 +0458P 2022 10 30.7909 2.634898 0.317256 104.9360 1.5605 13.6221 20250704 17.3 4.0 458P/Jahn MPEC 2023-HD1 +0459P 2023 02 21.6841 1.367918 0.577859 205.2259 256.9876 7.1737 20250704 15.5 4.0 459P/Catalina MPEC 2024-N80 +0460P 2026 09 21.6425 1.016485 0.664223 351.9346 180.5168 18.9000 20250704 21.0 4.0 460P/PANSTARRS MPEC 2023-G14 +0461P 2027 05 3.0446 1.353454 0.569566 174.8309 194.3770 18.3988 20250704 18.5 4.0 461P/WISE MPEC 2024-GJ3 +0462P 2022 08 1.1450 2.049568 0.578484 4.2195 322.6630 7.0467 20250704 17.0 4.0 462P/LONEOS-PANSTARRS MPEC 2024-BE0 +0463P 2023 03 29.8570 0.517809 0.825895 216.3407 283.2180 29.2960 20250704 18.0 4.0 463P/NEOWISE MPEC 2024-GJ3 +0464P 2023 02 27.3158 3.369707 0.280580 267.5247 309.5782 21.6734 20250704 10.5 4.0 464P/PANSTARRS MPEC 2024-Q20 +0465P 2023 05 8.9350 2.324230 0.613149 140.9833 217.9553 25.8618 20250704 12.5 4.0 465P/Hill MPEC 2024-NE4 +0466P 2023 05 10.8324 2.104153 0.478903 198.0041 117.9041 12.9260 20250704 14.0 4.0 466P/PANSTARRS MPEC 2024-JU4 +0467P 2022 11 26.4597 5.508697 0.054484 267.4698 43.2629 2.4793 20250704 9.0 4.0 467P/LINEAR-Grauer MPEC 2025-A40 +0468P 2023 11 21.0946 3.950404 0.444965 322.5765 356.1260 50.4520 20250704 11.5 4.0 468P/SidingSpring MPEC 2024-O39 +0469P 2025 12 8.4097 3.004998 0.308009 43.4949 178.9673 20.1722 20250704 13.5 4.0 469P/PANSTARRS MPEC 2025-A40 +0470P 2023 12 16.7256 2.725640 0.389370 151.6864 246.1685 8.8441 20250704 15.5 4.0 470P/PANSTARRS MPC182892 +0471P 2023 12 19.8262 2.119676 0.627700 94.7850 283.3125 4.7970 20250704 12.0 4.0 471P/LINEAR-Lemmon MPC182892 +0472P 2024 07 14.1098 3.387337 0.564539 218.8371 205.8446 10.8242 20250704 10.5 4.0 472P/NEAT-LINEAR MPEC 2025-MC0 +0473P 2024 02 26.2364 1.406390 0.823597 42.9374 22.1901 56.8963 20250704 13.5 4.0 473P/NEAT MPEC 2024-MB8 +0474P 2023 07 15.6570 2.541809 0.188053 11.2619 26.7499 1.0969 20250704 15.5 4.0 474P/Hogan MPEC 2024-B74 +0475P 2024 06 1.6594 4.077403 0.442811 40.4092 147.3599 14.5237 20250704 11.0 4.0 475P/Spacewatch-LINEAR MPEC 2025-MC0 +0476P 2024 10 16.4747 3.123423 0.345869 46.7333 57.0497 19.0052 20250704 12.5 4.0 476P/PANSTARRS MPC184421 +0477P 2023 12 26.5239 1.748547 0.417537 305.8757 59.1455 8.9138 20250704 14.5 4.0 477P/PANSTARRS MPEC 2024-GJ3 +0478P 2024 05 2.1691 2.393959 0.343751 13.2438 127.2629 12.5247 20250704 13.5 4.0 478P/ATLAS MPEC 2024-L77 +0479P 2024 05 5.2609 1.243192 0.778907 263.5055 295.8325 15.3997 20250704 15.0 4.0 479P/Elenin MPEC 2024-PC5 +0480P 2023 04 23.7546 3.475067 0.246320 214.4162 229.9817 13.7167 20250704 12.0 4.0 480P/PANSTARRS MPC182893 +0481P 2023 07 9.2969 3.073663 0.343467 356.8024 93.5503 6.0826 20250704 13.5 4.0 481P/Lemmon-PANSTARRS MPEC 2025-A40 +0482P 2023 06 2.1702 1.907115 0.492366 339.7254 126.0773 24.4871 20250704 13.5 4.0 482P/PANSTARRS MPEC 2024-JU4 +0483P a 2027 11 10.8017 2.484875 0.222282 49.1787 199.2558 14.1862 20250704 13.5 4.0 483P-A/PANSTARRS MPEC 2024-R10 +0483P b 2027 11 10.5630 2.485004 0.222223 49.1686 199.2551 14.1870 20250704 17.0 4.0 483P-B/PANSTARRS MPEC 2025-MC0 +0484P 2028 03 10.6196 2.130381 0.432943 240.7993 265.3806 14.4743 20250704 16.0 4.0 484P/Spacewatch MPEC 2024-DD5 +0485P 2023 08 25.2222 3.992865 0.417180 196.1008 261.6446 10.0161 20250704 13.0 4.0 485P/Sheppard-Tholen MPEC 2024-JU4 +0486P 2025 04 3.8511 2.308971 0.363531 93.9465 219.0231 2.2095 20250704 14.5 4.0 486P/Leonard MPEC 2025-MC0 +0487P 2024 10 20.5896 1.814722 0.648449 0.8422 49.2030 39.3660 20250704 13.5 4.0 487P/SidingSpring MPEC 2025-MC0 +0488P 2024 05 19.5308 1.679241 0.551150 1.7356 323.9322 11.3751 20250704 16.5 4.0 488P/NEAT-PANSTARRS MPEC 2024-UA9 +0489P 2025 12 4.3315 1.561205 0.647145 109.4261 20.6089 4.0262 20250704 15.5 4.0 489P/Denning MPEC 2024-Q14 +0490P 2024 09 28.1771 1.069089 0.647169 332.5463 307.5996 12.2664 20250704 21.0 4.0 490P/ATLAS MPEC 2024-YC7 +0491P 2024 09 5.9963 3.716415 0.258693 298.8796 311.6842 9.3663 20250704 9.5 4.0 491P/Spacewatch-PANSTARRS MPEC 2025-MC0 +0492P 2024 07 20.4439 1.781954 0.690614 40.9829 11.3049 11.4011 20250704 15.0 4.0 492P/LINEAR MPEC 2025-MC0 +0493P 2026 01 14.0908 3.823245 0.466559 83.1990 1.1049 24.1114 20250704 12.0 2.0 493P/LONEOS MPC182893 +0494P 2024 05 30.9940 2.440513 0.356827 48.8798 245.0431 7.7900 20250704 16.0 4.0 494P/PANSTARRS MPEC 2024-RQ6 +0495P 2025 10 22.3683 3.459918 0.272564 141.3356 291.6171 26.3550 20250704 11.5 4.0 495P/Christensen MPEC 2025-A40 +0496P 2025 03 10.2745 1.621031 0.734208 42.2448 63.5862 14.8144 20250704 14.0 4.0 496P/Hill MPEC 2025-MC0 +0497P 2025 02 15.3076 2.075032 0.630437 32.4014 40.3711 10.4367 20250704 17.5 4.0 497P/Spacewatch-PANSTARRS MPC184421 +0498P 2024 12 18.9102 1.964332 0.572297 179.0800 279.2308 14.4828 20250704 14.7 4.0 498P/LINEAR MPC184421 +0499P 2025 03 4.3926 0.931058 0.691460 2.5578 139.3085 24.5822 20250704 18.5 4.0 499P/Catalina MPEC 2025-MC0 +0500P 2025 03 31.9455 2.131834 0.375864 46.6895 111.5277 2.3015 20250704 16.0 4.0 500P/PANSTARRS MPEC 2025-MC0 +0501P 2024 04 14.3035 0.671861 0.698452 53.6932 139.7800 10.0469 20250704 21.5 4.0 501P/Rankin MPC182882 +0502P 2025 08 5.0863 4.229499 0.471173 37.7414 264.4848 11.3996 20250704 8.5 4.0 502P/NEAT MPEC 2025-MC0 +0503P 2025 11 5.5669 1.897332 0.481312 17.9514 268.5821 10.5748 20250704 15.0 4.0 503P/PANSTARRS MPEC 2025-MC0 +0001I 2017 09 9.4886 0.255240 1.199252 241.6845 24.5997 122.6778 20170904 23.0 2.0 1I/`Oumuamua MPC107687 +0002I 2019 12 8.5548 2.006548 3.356633 209.1251 308.1480 44.0527 20191223 11.0 4.0 2I/Borisov MPEC 2023-L37 +0003I 2025 10 29.3067 1.368955 6.232602 127.8542 322.2298 175.1151 20250505 11.8 4.0 3I/ATLAS MPEC 2025-N35 diff --git a/python/PiFinder/pointing_model/pointing_model.py b/python/PiFinder/pointing_model/pointing_model.py index 740bca633..0aee79490 100644 --- a/python/PiFinder/pointing_model/pointing_model.py +++ b/python/PiFinder/pointing_model/pointing_model.py @@ -22,10 +22,10 @@ import quaternion -def get_q_hor2scope(az, alt): +def get_q_hor2frame(az, alt): """ - Returns the quaternion to rotate from the horizontal frame to the scope frame - at coordinates (az, alt) for an ideal AltAz mount. + Returns the quaternion to rotate from the horizontal frame to the frame + (typically scope) at coordinates (az, alt) for an ideal AltAz mount. INPUTS: az: [rad] Azimuth of scope axis @@ -35,20 +35,20 @@ def get_q_hor2scope(az, alt): * np.quaternion(np.cos((np.pi / 2 - alt) / 2), np.sin((np.pi / 2 - alt) / 2), 0, 0) -def get_altaz_from_q_hor2scope(q_hor2scope): +def get_azalt_of_q_hor2frame(q_hor2frame): """ - Returns the (az, alt) pointing of the scope which is defined by the z axis - of the q_hor2scope quaternion. + Returns the (az, alt) pointing of the frame which is defined by the z axis + of the q_hor2frame quaternion. RETURNS: az: [rad] alt: [rad] """ pz = np.quaternion(0, 0, 0, 1) # Vector z represented as a pure quaternion - scope_axis = q_hor2scope * pz * q_hor2scope.conj() # Returns a pure quaternion along scope axis + frame_axis = q_hor2frame * pz * q_hor2frame.conj() # Returns a pure quaternion along scope axis - alt = np.pi / 2 - np.arccos(scope_axis.z) - az = np.pi - np.arctan2(scope_axis.y, scope_axis.x) + alt = np.pi / 2 - np.arccos(frame_axis.z) + az = np.pi - np.arctan2(frame_axis.y, frame_axis.x) return az, alt @@ -67,3 +67,4 @@ def get_quat_angular_diff(q1, q2): d_theta = 2 * np.pi - d_theta return d_theta # In radians + From 8ab3613c2ec0ef8c3bfda79831f7225c4b2ed191 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 5 Jul 2025 21:02:43 +0100 Subject: [PATCH 064/253] Add new class ImuDeadReckoning --- .../PiFinder/pointing_model/pointing_model.py | 143 ++++++++++++++++++ 1 file changed, 143 insertions(+) diff --git a/python/PiFinder/pointing_model/pointing_model.py b/python/PiFinder/pointing_model/pointing_model.py index 0aee79490..c49749ef1 100644 --- a/python/PiFinder/pointing_model/pointing_model.py +++ b/python/PiFinder/pointing_model/pointing_model.py @@ -68,3 +68,146 @@ def get_quat_angular_diff(q1, q2): return d_theta # In radians + +class ImuDeadReckoning(): + """ + Use the plate-solved coordinates and IMU measurements to estimate the + pointing using plate solving when available or dead-reckoning using the IMU + when plate solving isn't available (e.g. when the scope is moving or + between frames). + + All angles are in radians. + + EXAMPLE: + # Set up: + pointing_tracker = ImuDeadReckoning('flat') + pointing_tracker.set_alignment(q_scope2cam) + + # Update with plate solved and IMU data: + pointing_tracker.update_plate_solve_and_imu(az_solved, alt_solve, q_x2imu) + q_hor2scope = pointing_tracker.get_q_hor2scope() + + # Dead-reckoning using IMU + pointing_tracker.update_imu(q_x2imu) + q_hor2scope = pointing_tracker.get_q_hor2scope() + az, alt = get_azalt_of_q_hor2frame(q_hor2frame) + """ + + def __init__(self, screen_direction): + """ """ + # IMU-to-camera orientation. Fixed by PiFinder type + self._set_screen_direction(screen_direction) + + # Alignment: + self.q_scope2cam = None + self.q_cam2scope = None + + # The poinging of the camera and scope frames wrt the horizontal frame. + # These get updated by plate solving and IMU dead-reckoning. + self.q_hor2cam = None + # True when q_hor2cam is estimated by IMU dead-reckoning. + # False when set by plate solving + self.dead_reckoning = False + + # The IMU's unkonwn drifting reference frame X. This is solved for + # every time we have a simultaneous plate solve and IMU measurement. + self.q_hor2x = None + + def set_alignment(self, + q_scope2cam: quaternion.quaternion): + """ + Set the alignment between the PiFinder camera center and the scope + pointing. + + INPUTS: + q_scope2cam: Quaternion that rotates the scope frame to the camera frame. + """ + self.q_scope2cam = q_scope2cam.normalized() + self.q_cam2scope = self.q_scope2cam.conj() + + def update_plate_solve_and_imu(self, + solved_az: float, + solved_alt: float, + q_x2imu: quaternion.quaternion): + """ + Update the state with the az/alt measurements from plate solving in the + camera frame. If the IMU measurement (which should be taken at the same + time) is available, q_x2imu (the unknown drifting reference frame) will + be solved for. + + INPUTS: + solved_az: [rad] Azimuth of the camera pointing from plate solving. + solved_alt: [rad] Alt of the camera pointing from plate solving. + q_x2imu: [quaternion] Raw IMU measurement quaternions. This is the IMU + frame orientation wrt unknown drifting reference frame X. + """ + # Currently assumes that the camera is right way up on a perfect + # altaz mount. TODO: Generalize to rotated camera + self.q_hor2cam = get_q_hor2frame(solved_az, solved_alt).normalized() + self.dead_reckoning = False + + # Calculate the IMU's unknown reference frame X using the plate solved + # coordinates and IMU measurements taken from the same time. If the IMU + # measurement isn't provided (e.g. None or zeros), the existing q_hor2x + # will continue to be used. + if q_x2imu: + self.q_hor2x = self.q_hor2cam * self.q_cam2imu * q_x2imu.conj() + self.q_hor2x = self.q_hor2x.normalized() + + def update_imu(self, + q_x2imu: quaternion.quaternion): + """ + Update the state with the raw IMU measurement. Does a dead-reckoning + estiamte of the camera and scope pointing. + + INPUTS: + q_x2imu: Quaternion of the IMU orientation w.r.t. an unknown and drifting + reference frame X used by the IMU. + """ + if self.q_hor2x is not None: + # Dead reckoning estimate by IMU if q_hor2x has been estimated by a + # previous plate solve. + self.q_hor2cam = self.q_hor2x * q_x2imu * self.q_imu2cam + self.q_hor2cam = self.q_hor2cam.normalized() + + self.dead_reckoning = True + + def get_q_hor2scope(self): + """ """ + if self.q_hor2cam and self.q_cam2scope: + q_hor2scope = self.q_hor2cam * self.q_cam2scope + return q_hor2scope + else: + None + + def get_cam_azalt(self): + """ """ + az_rad, alt_rad = get_azalt_of_q_hor2frame(self.q_hor2cam) + return az_rad, alt_rad, self.dead_reckoning + + def get_scope_azalt(self): + """ """ + NotImplementedError() + + def reset(self): + """ + Resets the internal state. + """ + self.q_hor2x = None + + def _set_screen_direction(self, screen_direction: str): + """ + Sets the screen direction which determines the fixed orientation between + the IMU and camera (q_imu2cam). + """ + if screen_direction == "flat": + # Rotate -90° around y_imu so that z_imu' points along z_camera + q1 = np.quaternion(np.cos(-np.pi / 4), 0, np.sin(-np.pi / 4), 0) + # Rotate -90° around z_imu' to align with the camera cooridnates + q2 = np.quaternion(np.cos(-np.pi / 4), 0, 0, np.sin(-np.pi / 4)) + self.q_imu2cam = q1 * q2 # Intrinsic rotation: q1 followed by q2 + else: + raise ValueError('Unsupported screen_direction') + + self.q_imu2cam = self.q_imu2cam.normalized() + self.q_cam2imu = self.q_imu2cam.conj() From 814328240faf75e4a0c370b6626787500ffdede8 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 5 Jul 2025 22:10:47 +0100 Subject: [PATCH 065/253] Update ImuDeadReckoning() class --- .../PiFinder/pointing_model/pointing_model.py | 39 +++++++++++++------ 1 file changed, 27 insertions(+), 12 deletions(-) diff --git a/python/PiFinder/pointing_model/pointing_model.py b/python/PiFinder/pointing_model/pointing_model.py index c49749ef1..a5553e278 100644 --- a/python/PiFinder/pointing_model/pointing_model.py +++ b/python/PiFinder/pointing_model/pointing_model.py @@ -78,19 +78,27 @@ class ImuDeadReckoning(): All angles are in radians. + HOW IT WORKS: + The IMU quaternion measurements, q_x2imu, are relative to some arbitrary + drifting frame X. This uses the latest plate solved coordinate with the + latest IMU measurement to solve for the IMU's reference frame X. The frame + X is expressed by the quaternion rotation q_hor2x from the Horizontal frame + to X. Once we know q_hor2x, we can infer the camera pointing using the IMU + data by dead reckoning: q_hor2cam = q_hor2x * q_x2imu * q_imu2cam + EXAMPLE: # Set up: pointing_tracker = ImuDeadReckoning('flat') pointing_tracker.set_alignment(q_scope2cam) # Update with plate solved and IMU data: - pointing_tracker.update_plate_solve_and_imu(az_solved, alt_solve, q_x2imu) + pointing_tracker.update_plate_solve_and_imu(solved_cam_az, solved_cam_alt, q_x2imu) q_hor2scope = pointing_tracker.get_q_hor2scope() # Dead-reckoning using IMU pointing_tracker.update_imu(q_x2imu) q_hor2scope = pointing_tracker.get_q_hor2scope() - az, alt = get_azalt_of_q_hor2frame(q_hor2frame) + az, alt = get_azalt_of_q_hor2frame(q_hor2scope) """ def __init__(self, screen_direction): @@ -126,9 +134,9 @@ def set_alignment(self, self.q_cam2scope = self.q_scope2cam.conj() def update_plate_solve_and_imu(self, - solved_az: float, - solved_alt: float, - q_x2imu: quaternion.quaternion): + solved_cam_az: float | None, + solved_cam_alt: float | None, + q_x2imu: quaternion.quaternion | None): """ Update the state with the az/alt measurements from plate solving in the camera frame. If the IMU measurement (which should be taken at the same @@ -136,15 +144,18 @@ def update_plate_solve_and_imu(self, be solved for. INPUTS: - solved_az: [rad] Azimuth of the camera pointing from plate solving. - solved_alt: [rad] Alt of the camera pointing from plate solving. + solved_cam_az: [rad] Azimuth of the camera pointing from plate solving. + solved_cam_alt: [rad] Alt of the camera pointing from plate solving. q_x2imu: [quaternion] Raw IMU measurement quaternions. This is the IMU frame orientation wrt unknown drifting reference frame X. """ # Currently assumes that the camera is right way up on a perfect # altaz mount. TODO: Generalize to rotated camera - self.q_hor2cam = get_q_hor2frame(solved_az, solved_alt).normalized() - self.dead_reckoning = False + if (solved_cam_az is None) or (solved_cam_alt is None): + return # No update + else: + self.q_hor2cam = get_q_hor2frame(solved_cam_az, solved_cam_alt).normalized() + self.dead_reckoning = False # Calculate the IMU's unknown reference frame X using the plate solved # coordinates and IMU measurements taken from the same time. If the IMU @@ -181,9 +192,13 @@ def get_q_hor2scope(self): None def get_cam_azalt(self): - """ """ - az_rad, alt_rad = get_azalt_of_q_hor2frame(self.q_hor2cam) - return az_rad, alt_rad, self.dead_reckoning + """ + Returns the (az, alt) of the camera and a Boolean dead_reckoning to + indicate if the estimate is from dead-reckoning (True) or from plate + solving (False). + """ + az_cam, alt_cam = get_azalt_of_q_hor2frame(self.q_hor2cam) + return az_cam, alt_cam, self.dead_reckoning # Angles are in radians def get_scope_azalt(self): """ """ From 6d25aa4ca7f797f35496a0626fdc8851eac8c09b Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 5 Jul 2025 22:11:15 +0100 Subject: [PATCH 066/253] Remove unused dictionary entry (now using the new ImuDeadReckoning() class) --- python/PiFinder/solver.py | 3 --- 1 file changed, 3 deletions(-) diff --git a/python/PiFinder/solver.py b/python/PiFinder/solver.py index eeb2af304..c09f1fb2b 100644 --- a/python/PiFinder/solver.py +++ b/python/PiFinder/solver.py @@ -65,9 +65,6 @@ def solver( "Dec": None, "Roll": None, }, - "imu": { - "q_hor2x": None, - }, # RA, Dec, Roll at the target pixel "RA": None, "Dec": None, From 42b5943214d947b15146b1ba9ba1f17a7ccdaf69 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 5 Jul 2025 22:12:02 +0100 Subject: [PATCH 067/253] Update integrator.py to use ImuDeadReckoning() --- python/PiFinder/integrator.py | 98 +++++++++++------------------------ 1 file changed, 30 insertions(+), 68 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index cce35d578..189df6a89 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -86,7 +86,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr "constellation": None, } cfg = config.Config() - #""" Disable dependence of IMU on PiFinder type + # TODO: Capture flip_alt_offset by q_imu2camera if ( cfg.get_option("screen_direction") == "left" or cfg.get_option("screen_direction") == "flat" @@ -96,10 +96,13 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr flip_alt_offset = True else: flip_alt_offset = False - #""" imu_moved_ang_threshold = np.deg2rad(0.1) # Use IMU tracking if the angle moved is above this - + + # Set up dead-reckoning tracking by the IMU: + pointing_tracker = ImuDeadReckoning(cfg.get_option("screen_direction")) + #pointing_tracker.set_alignment(q_scope2cam) # TODO: Enable when q_scope2cam is available + # This holds the last image solve position info # so we can delta for IMU updates last_image_solve = None @@ -174,9 +177,9 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr roll_target_calculated + solved["Roll_offset"] ) - # Use plate-solved pointing and IMU measurement to set up - # IMU dead reckoning: - solved["imu"]["q_hor2x"] = get_imu_reference_frame(solved, shared_state) + # Update with plate solved coordinates of camera center & IMU measurement + update_plate_solve_and_imu__degrees(pointing_tracker, solved) + # From the alignment. Add this offset to the camera center to get # the scope altaz coordinates. TODO: This could be calculated once # at alignment? @@ -215,27 +218,22 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr if angle_moved > imu_moved_ang_threshold: # Estimate camera pointing using IMU dead-reckoning logger.debug("Track using IMU. Angle moved since last_image_solve = {:} (> threshold = {:})".format(np.rad2deg(angle_moved), np.rad2deg(imu_moved_ang_threshold))) - - q_x2imu = imu["quat"] # Latest IMU meas: quaternion rot. of IMU rel. to some frame X - #q_x2imu = np.quaternion(q_x2imu.w, -q_x2imu.x, -q_x2imu.y, -q_x2imu.z) # HACK: Reverse the angle part of quaternion - q_hor2x = last_image_solve["imu"]["q_hor2x"] - q_imu2cam = np.quaternion(1, 0, 0, 0) # Identity so this could be removed later (TODO) - q_hor2cam = q_hor2x * q_x2imu * q_imu2cam - q_hor2cam = q_hor2cam.normalized() + + # Dead-reckoning using IMU + pointing_tracker.update_imu(imu["quat"]) # Latest IMU meas + # Store estimate: - az_rad, alt_rad = pointing.get_altaz_from_q_hor2scope(q_hor2cam) - solved["camera_center"]["Az"] = np.rad2deg(az_rad) - solved["camera_center"]["Alt"] = np.rad2deg(alt_rad) + az_cam, alt_cam, dead_reckoning_flag = pointing_tracker.get_cam_azalt() + solved["camera_center"]["Az"] = np.rad2deg(az_cam) + solved["camera_center"]["Alt"] = np.rad2deg(alt_cam) # Transform to scope center + # TODO: need to define q_cam2scope solved["Az"] = solved["camera_center"]["Az"] + cam2scope_offset_az solved["Alt"] = solved["camera_center"]["Alt"] + cam2scope_offset_alt - # TODO: need to define q_cam2scope - #q_hor2scope = q_hor2cam * q_cam2scope logger.debug(" IMU quat = ({:}, {:}, {:}, {:}".format(q_x2imu.w, q_x2imu.x, q_x2imu.y, q_x2imu.z)) - """ DISABLE - Use quaternions # calc new alt/az - OLD method lis_imu = last_image_solve["imu_pos"] @@ -329,55 +327,19 @@ def estimate_roll_offset(solved, dt): return roll_offset -def get_imu_reference_frame(solved, shared_state): +def update_plate_solve_and_imu__degrees(pointing_tracker, solved): """ - The IMU quaternion measurements, q_x2imu, are relative to some arbitrary - drifting frame X. This uses the latest plate solved coordinate with the - latest IMU measurement to solve for the IMU's reference frame X. The frame - X is expressed by the quaternion rotation q_hor2x from the Horizontal frame - to X. Once we know q_hor2x, we can infer the camera pointing using the IMU - data by dead reckoning: q_hor2cam = q_hor2x * q_x2imu * q_imu2cam - - This assumes that plate solving was successful and camera coordinates are - available. It also assumes that the IMU measurement is available. If these - conditions are not met, this function will return None. We also assume that - the plate solve and IMU measurements availalbe are simultaneous. Note that - q_hor2x will drift over time. - - INPUT: - solved: Dictionary of the latest plate-solved data - - RETURNS: - q_hor2x: [numpy.quaternion] Quaternion of the IMU's drifting reference - frame X relative to the Horizontal frame. Returns None if the - plate-solved pointing or IMU data aren't available. + Wrapper for ImuDeadReckoning.update_plate_solve_and_imu() to interface + degrees to radians. """ - q_hor2x = None - - if solved["Alt"]: + if (solved["Az"] is None) or (solved["Alt"] is None): + return # No update + else: # Successfully plate solved & camera pointing exists - #imu = shared_state.imu() # TODO: Usage above. Remove? Also remove shared_state as input? - imu_meas = solved["imu_quat"] # Should be the IMU measurement at the time of plate solving - if imu_meas: - # We have both the plate solved camera pointing and an IMU - # measurement (we'll assume that they are at the same timestamp). - - # Get plate-solved pointing from the camera as quaternion: - # Assumes that the PiFinder camera is on a perfect altaz mount - q_hor2cam = pointing.get_q_hor2scope( - np.deg2rad(solved["camera_center"]["Az"]), - np.deg2rad(solved["camera_center"]["Alt"])) - - # Get latest IMU data: quaternion rot. of IMU rel. to some drifting - # reference frame X that the IMU uses as its reference - q_x2imu = imu_meas # Rename to make the transformation expilicit - q_x2imu = q_x2imu.normalized() - - # Solve for the arbitrary drifting reference frame X using the - # camera pointing. This will be used during dead reckoning with - # the IMU until the next plate solve. - q_cam2imu = np.quaternion(1, 0, 0, 0) # Identity so this could be removed later (TODO) - q_hor2x = q_hor2cam * q_cam2imu * q_x2imu.conj() - q_hor2x = q_hor2x.normalized() - - return q_hor2x + q_x2imu = solved["imu_quat"] # IMU measurement at the time of plate solving + # Convert to radians: + solved_cam_az = np.deg2rad(solved["camera_center"]["Az"]) + solved_cam_alt = np.deg2rad(solved["camera_center"]["Alt"]) + # Update: + pointing_tracker.update_plate_solve_and_imu( + solved_cam_az, solved_cam_alt, q_x2imu) From 7a181b84752c605b6a165c864c8c0dee8ac6f8ad Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 5 Jul 2025 22:33:33 +0100 Subject: [PATCH 068/253] Debug on PiFinder in test mode --> The charts move up/down and left/right reversed? --- python/PiFinder/integrator.py | 8 +++----- python/PiFinder/pointing_model/pointing_model.py | 8 ++++---- 2 files changed, 7 insertions(+), 9 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 189df6a89..ddfae214b 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -72,9 +72,6 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr "Dec": None, "Roll": None, }, - "imu": { - "q_hor2x": None, - }, "Roll_offset": 0, # May/may not be needed - for experimentation "imu_pos": None, "imu_quat": None, # IMU quaternion as numpy quaternion (scalar-first) - TODO: Move to "imu" @@ -100,7 +97,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr imu_moved_ang_threshold = np.deg2rad(0.1) # Use IMU tracking if the angle moved is above this # Set up dead-reckoning tracking by the IMU: - pointing_tracker = ImuDeadReckoning(cfg.get_option("screen_direction")) + pointing_tracker = pointing.ImuDeadReckoning(cfg.get_option("screen_direction")) #pointing_tracker.set_alignment(q_scope2cam) # TODO: Enable when q_scope2cam is available # This holds the last image solve position info @@ -202,7 +199,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr imu = shared_state.imu() if imu: dt = shared_state.datetime() - if last_image_solve and last_image_solve["Alt"] and last_image_solve["imu"]["q_hor2x"]: + if last_image_solve and last_image_solve["Alt"]: # If we have alt, then we have a position/time # TODO: For debugging -- remove later @@ -232,6 +229,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr solved["Az"] = solved["camera_center"]["Az"] + cam2scope_offset_az solved["Alt"] = solved["camera_center"]["Alt"] + cam2scope_offset_alt + q_x2imu = imu["quat"] logger.debug(" IMU quat = ({:}, {:}, {:}, {:}".format(q_x2imu.w, q_x2imu.x, q_x2imu.y, q_x2imu.z)) """ DISABLE - Use quaternions diff --git a/python/PiFinder/pointing_model/pointing_model.py b/python/PiFinder/pointing_model/pointing_model.py index a5553e278..c31fdd438 100644 --- a/python/PiFinder/pointing_model/pointing_model.py +++ b/python/PiFinder/pointing_model/pointing_model.py @@ -17,7 +17,7 @@ computational overhead. Normalization should be done manually as and when necessary. """ - +from typing import Union # When updated to Python 3.10+, remove and use new type hints import numpy as np import quaternion @@ -134,9 +134,9 @@ def set_alignment(self, self.q_cam2scope = self.q_scope2cam.conj() def update_plate_solve_and_imu(self, - solved_cam_az: float | None, - solved_cam_alt: float | None, - q_x2imu: quaternion.quaternion | None): + solved_cam_az: Union[float, None], + solved_cam_alt: Union[float, None], + q_x2imu: Union[quaternion.quaternion, None]): """ Update the state with the az/alt measurements from plate solving in the camera frame. If the IMU measurement (which should be taken at the same From 01b73045d521c05a84ef912c15dec76364f0d185 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 5 Jul 2025 23:50:56 +0100 Subject: [PATCH 069/253] Remove cached astro_data/comets.txt --- astro_data/comets.txt | 1210 ----------------------------------------- 1 file changed, 1210 deletions(-) delete mode 100644 astro_data/comets.txt diff --git a/astro_data/comets.txt b/astro_data/comets.txt deleted file mode 100644 index 472fc4b8d..000000000 --- a/astro_data/comets.txt +++ /dev/null @@ -1,1210 +0,0 @@ - PJ96R020 2026 06 15.6745 2.587038 0.314255 333.4893 40.0442 2.5990 20250704 11.5 4.0 P/1996 R2 (Lagerkvist) NK 1615 - PJ98V24S 2027 09 7.8602 3.419486 0.243572 244.8885 159.0392 5.0293 20250704 13.0 2.0 P/1998 VS24 (LINEAR) MPC 75703 - PJ99R28O 2025 10 30.3015 1.122846 0.672179 231.3531 137.8412 7.5671 20250704 20.0 2.0 P/1999 RO28 (LONEOS) NK 731 - PJ99XC0N 2025 12 21.5458 3.297933 0.211738 161.5850 285.2398 5.0299 20250704 13.5 2.0 P/1999 XN120 (Catalina) MPC 75704 - PK00R020 2025 12 2.2970 1.628205 0.530635 176.5816 160.2706 11.6788 20250704 18.0 4.0 P/2000 R2 (LINEAR) NK 744 - PK01H050 2030 10 22.4786 2.442418 0.599232 224.5839 328.6752 8.3721 20250704 12.0 4.0 P/2001 H5 (NEAT) MPC 43019 - PK02E57J 2018 06 20.3595 2.621228 0.593937 167.2801 330.2272 4.9892 20250704 12.5 4.0 P/2002 EJ57 (LINEAR) MPEC 2023-UR6 - CK02J040 2003 09 24.4189 3.679001 1.001480 231.0777 70.7672 46.2191 20250704 5.5 4.0 C/2002 J4 (NEAT) MPEC 2025-MC0 - CK02V94Q 2006 02 11.2313 6.754417 0.963841 99.8060 35.0947 70.6542 20250704 9.5 2.0 C/2002 VQ94 (LINEAR) MPC 75007 - CK03A020 2003 11 5.3536 11.358825 0.997992 346.4661 154.5014 8.0703 20250704 3.5 4.0 C/2003 A2 (Gleason) MPC184407 - PK03F020 2019 11 14.0800 3.017230 0.538690 192.9613 358.9258 11.6414 20250704 16.5 2.0 P/2003 F2 (NEAT) MPC 50354 - PK03T120 2024 07 3.7270 0.593913 0.770165 219.7935 174.5760 11.0232 20250704 17.0 4.0 P/2003 T12 (SOHO) MPC105235 - PK04FE0Y 2027 02 22.1271 4.011069 0.192763 254.2527 327.2620 2.1628 20250704 12.5 2.0 P/2004 FY140 (LINEAR) MPEC 2022-YN2 - PK04R030 2021 09 15.5693 3.539101 0.254511 37.2042 305.1204 12.8020 20250704 14.5 4.0 P/2004 R3 (LINEAR-NEAT) MPC 53304 - PK04V050 2027 08 6.1704 4.433645 0.448768 87.1922 47.7411 19.3369 20250704 8.0 4.0 P/2004 V5 (LINEAR-Hill) MPC 75705 - PK04V05b 2027 08 7.1429 4.433650 0.448786 87.1964 47.7415 19.3370 20250704 8.0 4.0 P/2004 V5-B (LINEAR-Hill) MPC 75705 - PK05E010 2023 09 28.1442 4.402630 0.377310 193.9260 335.4965 4.2606 20250704 10.0 4.0 P/2005 E1 (Tubbiolo) MPC 54164 - PK05J010 2025 07 11.7011 1.539552 0.569371 338.9130 268.7998 31.7406 20250704 16.5 4.0 P/2005 J1 (McNaught) MPC 79019 - PK05L010 2021 12 30.2903 2.918240 0.255502 160.6361 127.1294 8.7116 20250704 9.5 4.0 P/2005 L1 (McNaught) MPC 74246 - PK05S020 2029 01 26.0642 6.399606 0.198472 230.0075 161.3329 3.1386 20250704 7.5 4.0 P/2005 S2 (Skiff) MPC 75706 - PK05T030 2026 08 19.8367 6.253637 0.174306 7.0925 27.6222 6.2321 20250704 9.0 4.0 P/2005 T3 (Read) MPC 73461 - PK05T040 2034 05 27.7990 0.647952 0.930715 41.7934 25.8235 160.2495 20250704 15.0 4.0 P/2005 T4 (SWAN) MPC 73461 - PK05T050 2025 06 14.9495 3.253537 0.551752 304.7819 57.0618 21.3837 20250704 11.0 4.0 P/2005 T5 (Broughton) MPC 75706 - PK06H30R 2028 10 9.2759 1.219300 0.843610 117.5134 309.7571 31.9572 20250704 11.0 4.0 P/2006 HR30 (Siding Spring) MPC 75707 - PK07C020 2026 03 21.1614 3.692610 0.474461 180.1137 275.2338 8.6131 20250704 10.0 4.0 P/2007 C2 (Catalina) MPC 75707 - CK07D010 2007 06 14.2652 8.739058 0.992948 339.7559 171.0359 41.5138 20250704 3.5 4.0 C/2007 D1 (LINEAR) MPC 84315 - PK07K020 2027 01 26.4272 2.312960 0.686486 347.0842 188.4114 7.5937 20250704 14.0 4.0 P/2007 K2 (Gibbs) MPEC 2024-GJ3 - PK07Q020 2020 11 24.9451 1.875139 0.668762 162.8469 172.2269 10.1933 20250704 16.0 4.0 P/2007 Q2 (Gilmore) MPC 60925 - PK07S010 2022 10 6.4057 2.528204 0.337919 245.2750 141.3266 5.9631 20250704 13.0 4.0 P/2007 S1 (Zhao) MPC 73462 - CK07S020 2008 09 4.4604 5.534766 0.557012 210.1446 296.1307 16.9168 20250704 6.5 4.0 C/2007 S2 (Lemmon) MPEC 2024-GJ3 - PK07S24A 2022 12 1.6222 2.682679 0.568889 107.7937 233.2250 17.1074 20250704 12.6 4.0 P/2007 SA24 (Lemmon) MPC184407 - PK07T020 2023 11 17.4894 0.652992 0.785448 359.6672 3.3932 9.7479 20250704 18.5 4.0 P/2007 T2 (Kowalski) MPC 61994 - CK08E010 2008 08 22.7347 4.812373 0.552906 270.3654 188.9188 34.8643 20250704 7.0 4.0 C/2008 E1 (Catalina) MPEC 2024-GJ3 - PK08O030 2031 12 23.6945 2.494280 0.696141 341.2022 47.6073 32.3092 20250704 13.0 4.0 P/2008 O3 (Boattini) MPC 64114 - PK08Y030 2031 10 6.0837 4.434442 0.448247 238.1336 262.8384 38.7791 20250704 8.5 4.0 P/2008 Y3 (McNaught) MPC 75710 - PK09B010 2026 06 30.4359 2.448371 0.635934 129.0052 297.1088 22.2596 20250704 13.0 4.0 P/2009 B1 (Boattini) MPC 75710 - CK09G010 2009 04 17.2493 1.135426 0.997488 175.5050 120.8778 108.0258 20250704 9.0 4.0 C/2009 G1 (STEREO) MPC 66466 - PK09K37F 2026 01 17.7381 2.835021 0.310584 143.9695 111.9435 11.3882 20250704 14.9 4.0 P/2009 KF37 MPC184407 - PK09O030 2031 01 25.9363 2.439635 0.686123 154.4194 183.7171 16.2514 20250704 12.5 4.0 P/2009 O3 (Hill) MPC 75710 - PK09Q050 2029 12 18.2453 2.901313 0.609306 209.2050 160.2043 40.9534 20250704 10.0 4.0 P/2009 Q5 (McNaught) MPC 68902 - PK09T020 2031 06 11.3196 1.792267 0.767478 216.0080 216.3107 27.5983 20250704 14.0 4.0 P/2009 T2 (La Sagra) MPC112389 - PK09W51X 2026 04 15.0691 0.802392 0.739687 118.2946 31.5222 9.5980 20250704 19.0 2.0 P/2009 WX51 (Catalina) MPC105235 - PK09Y020 2026 12 1.7429 2.370647 0.637394 172.2450 262.0829 29.9730 20250704 13.0 4.0 P/2009 Y2 (Kowalski) MPC 74247 - CK10B010 2011 02 3.3115 2.951526 0.998812 211.6053 277.2239 102.2533 20250704 7.5 4.0 C/2010 B1 (Cardinal) MPEC 2025-MC0 - PK10C010 2028 09 21.6606 5.248020 0.263932 2.9081 141.5889 9.1157 20250704 9.5 4.0 P/2010 C1 (Scotti) MPC 75008 - PK10D020 2027 07 9.4935 3.682713 0.451691 120.0181 319.8767 57.1358 20250704 16.0 4.0 P/2010 D2 (WISE) MPC 75008 - PK10E020 2035 08 1.2950 2.409731 0.720935 8.2107 177.8278 15.4272 20250704 14.0 4.0 P/2010 E2 (Jarnac) MPC 75009 - PK10H020 2025 03 9.6697 3.075968 0.197768 128.0526 64.1889 14.2791 20250704 6.0 4.0 P/2010 H2 (Vales) MPC 72851 - PK10H030 2026 05 25.2347 0.043779 0.985576 26.0731 77.1812 23.1476 20250704 20.0 2.0 P/2010 H3 (SOHO) MPC 70361 - PK10H040 2027 05 21.6070 4.850226 0.267127 179.0801 44.7467 2.3178 20250704 10.5 4.0 P/2010 H4 (Scotti) MPEC 2024-GJ3 - PK10H050 2029 05 22.1622 6.057244 0.155371 174.9503 24.5049 14.0524 20250704 13.0 2.0 P/2010 H5 (Scotti) MPC 74637 - PK10J030 2037 07 18.9143 2.479074 0.724183 157.4156 106.5400 13.2261 20250704 11.0 4.0 P/2010 J3 (McMillan) MPC 98558 - PK10J81C 2034 05 29.3121 1.798294 0.778065 12.5078 30.8499 38.7660 20250704 9.0 4.0 P/2010 JC81 (WISE) MPC 84315 - PK10K43G 2023 08 26.6677 2.886398 0.482859 354.4253 325.6755 13.6508 20250704 12.7 4.0 P/2010 KG43 MPC184408 - AK10LD5N 2011 05 25.0831 1.747446 0.999956 181.5734 184.8573 64.4494 20250704 14.0 2.0 A/2010 LN135 MPEC 2024-H77 - PK10LF5H 2025 04 9.0281 2.224067 0.405990 308.5243 221.1200 8.8068 20250704 14.3 4.0 P/2010 LH155 MPEC 2025-MC0 - PK10T020 2024 02 23.3112 3.767622 0.325558 350.1592 57.8039 7.8584 20250704 11.5 4.0 P/2010 T2 (PANSTARRS) MPC 74248 - PK10U010 2026 09 9.9309 4.875199 0.248348 86.5411 280.8067 8.2273 20250704 9.5 4.0 P/2010 U1 (Boattini) MPC 82316 - CK10U030 2019 02 28.1178 8.439200 0.999720 88.0860 42.9925 55.5451 20250704 1.0 4.0 C/2010 U3 (Boattini) MPEC 2023-J95 - PK10U55H 2028 06 2.3024 2.893832 0.564699 225.3179 232.8238 8.0369 20250704 11.0 4.0 P/2010 UH55 (Spacewatch) MPC 79021 - PK11C020 2032 02 3.9780 5.399558 0.271185 160.2818 11.9611 10.8954 20250704 9.0 4.0 P/2011 C2 (Gibbs) MPC 84021 - PK11FE3R 2029 02 1.1823 3.767619 0.452601 349.6424 190.8466 15.9620 20250704 14.0 2.0 P/2011 FR143 (Lemmon) MPC 79866 - PK11J15B 2032 01 11.2291 5.057127 0.314803 110.6890 153.5860 19.1256 20250704 9.0 4.0 P/2011 JB15 (Spacewatch-Boattini) MPC 82317 - PK11N010 2027 12 30.9553 2.833482 0.545450 330.4970 77.6283 35.7858 20250704 11.5 4.0 P/2011 N1 (ASH) MPC 87913 - PK11P010 2030 12 21.6843 5.026749 0.326332 349.1731 4.2570 5.6517 20250704 9.0 4.0 P/2011 P1 (McNaught) MPEC 2022-ED3 - PK11S010 2014 08 24.5291 6.869150 0.200949 192.9581 218.8974 2.6884 20250704 8.0 4.0 P/2011 S1 (Gibbs) MPEC 2022-HC2 - PK11V010 2026 04 23.5445 1.742199 0.548368 269.6064 46.4915 7.3828 20250704 15.5 4.0 P/2011 V1 (Boattini) MPEC 2023-UR6 - PK11W010 2022 02 9.4668 3.326063 0.288462 283.0394 161.8061 3.7160 20250704 11.5 4.0 P/2011 W1 (PANSTARRS) MPC 82718 - PK11Y020 2027 10 2.2012 1.798732 0.711202 132.0737 309.3199 6.3921 20250704 15.0 4.0 P/2011 Y2 (Boattini) MPC 79342 - PK12B010 2030 03 8.4604 3.859022 0.410151 161.9110 36.2093 7.6053 20250704 9.0 4.0 P/2012 B1 (PANSTARRS) MPEC 2022-K19 - PK12C030 2011 10 6.7469 3.605925 0.630111 344.9542 135.3677 9.0920 13.0 4.0 P/2012 C3 (PANSTARRS) MPC 78590 - PK12F020 2029 03 19.1316 2.916185 0.540602 33.1595 226.9507 14.6979 20250704 12.0 4.0 P/2012 F2 (PANSTARRS) MPC 84931 - PK12G010 2029 03 27.9017 2.790620 0.329570 266.0156 283.2365 12.1681 20250704 15.0 4.0 P/2012 G1 (PANSTARRS) MPEC 2022-ED3 - PK12K030 2026 07 15.9055 2.100831 0.421691 172.1370 125.8052 13.1815 20250704 15.0 4.0 P/2012 K3 (Gibbs) MPC 80898 - CK12K51A 2011 11 6.2250 4.867013 0.990873 93.9951 344.8338 70.7262 20250704 8.7 4.0 C/2012 KA51 MPC184408 - PK12N00J 2037 02 1.2490 1.299790 0.846498 338.3853 315.6965 84.3166 20250704 14.5 4.0 P/2012 NJ (La Sagra) MPC 88326 - PK12O010 2025 11 1.1138 1.440115 0.593564 238.2783 91.9402 7.4280 20250704 17.5 4.0 P/2012 O1 (McNaught) MPC 81470 - PK12O020 2026 04 1.5161 1.701681 0.531237 183.4092 120.6611 24.4555 20250704 17.0 4.0 P/2012 O2 (McNaught) MPC 80899 - PK12T020 2027 01 21.1846 4.790599 0.162061 311.1940 73.8747 12.5699 20250704 10.0 4.0 P/2012 T2 (PANSTARRS) MPC 82320 - PK12T030 2027 08 9.9407 2.367570 0.615588 195.4624 114.3246 9.5537 20250704 15.0 4.0 P/2012 T3 (PANSTARRS) MPC 80900 - PK12U020 2031 12 5.8936 3.559587 0.500463 228.4494 185.2698 10.7580 20250704 12.5 4.0 P/2012 U2 (PANSTARRS) MPC 82720 - PK13A76L 2029 06 28.1054 2.044186 0.685521 27.1199 146.0951 144.9148 20250704 16.0 4.0 P/2013 AL76 (Catalina) MPC 82721 - PK13G010 2032 01 18.8759 3.384771 0.509970 51.3612 221.3153 5.4571 20250704 11.0 4.0 P/2013 G1 (Kowalski) MPC 91612 - PK13G040 2022 06 19.1635 2.617823 0.409419 214.5176 339.5876 5.9201 20250704 15.0 4.0 P/2013 G4 (PANSTARRS) MPC 84025 - PK13J020 2029 03 13.7692 2.144094 0.655828 37.8559 289.2886 15.5000 20250704 13.0 4.0 P/2013 J2 (McNaught) MPC 91613 - PK13N030 2034 04 9.8814 3.030163 0.590852 323.8770 17.5954 2.1670 20250704 13.0 4.0 P/2013 N3 (PANSTARRS) MPC 86229 - PK13N050 2031 04 2.5429 1.826074 0.731439 176.9590 187.1587 23.4106 20250704 17.0 4.0 P/2013 N5 (PANSTARRS) MPC 85834 - PK13P010 2013 02 15.2090 3.416295 0.602422 138.1214 160.7054 18.6861 20250704 12.0 4.0 P/2013 P1 (PANSTARRS) MPC 85834 - PK13R030 2024 03 20.8677 2.192545 0.277191 11.4886 341.7963 0.8655 20250704 14.0 4.0 P/2013 R3 (Catalina-PANSTARRS) MPEC 2022-V95 - PK13R03a 2024 03 20.4911 2.192562 0.277123 11.5661 341.7509 0.8646 20250704 9.0 4.0 P/2013 R3-A (Catalina-PANSTARRS) unp - PK13R03b 2024 03 20.8905 2.192597 0.277167 11.5019 341.8072 0.8658 20250704 9.0 4.0 P/2013 R3-B (Catalina-PANSTARRS) MPEC 2015-M77 - PK13T010 2027 10 12.9908 2.204181 0.623556 346.1728 10.0839 24.2686 20250704 16.5 4.0 P/2013 T1 (PANSTARRS) MPC 85835 - PK13T020 2026 06 11.3921 1.746196 0.500186 345.5644 0.8052 9.4467 20250704 16.0 4.0 P/2013 T2 (Schwartz) MPC 86643 - PK13W010 2027 03 15.9270 1.415369 0.593844 1.2472 117.8354 4.7000 20250704 17.5 4.0 P/2013 W1 (PANSTARRS) MPC 91613 - PK13Y46G 2023 01 20.4708 1.726138 0.470799 244.7258 46.6249 7.5142 20250704 10.0 4.0 P/2013 YG46 (Spacewatch) MPC101095 - PK14A020 2028 03 14.1665 2.091959 0.646693 356.2039 106.6561 24.5634 20250704 15.0 4.0 P/2014 A2 (Hill) MPC 89728 - PK14C010 2028 07 3.1355 2.649487 0.341965 188.2265 39.8248 3.2090 20250704 15.5 4.0 P/2014 C1 (TOTAS) MPEC 2024-F34 - CK14F030 2021 05 27.4757 5.731364 0.601668 5.1334 325.9781 6.5210 20250704 6.0 4.0 C/2014 F3 (Sheppard-Trujillo) MPEC 2022-WD2 - PK14L020 2030 05 26.3798 2.233642 0.646155 182.6888 149.3365 5.1903 20250704 12.0 4.0 P/2014 L2 (NEOWISE) MPC 98560 - PK14L030 2014 06 20.9231 1.873836 0.771036 178.6542 115.5305 6.2536 20250704 16.0 4.0 P/2014 L3 (Hill) MPC 90769 - PK14M040 2029 03 18.9963 2.368624 0.595989 148.1279 263.1999 3.3472 20250704 15.0 4.0 P/2014 M4 (PANSTARRS) MPC 91614 - PK14O030 2035 02 25.7246 4.685939 0.382417 204.6507 87.6244 7.7890 20250704 10.5 4.0 P/2014 O3 (PANSTARRS) MPC 98560 - CK14Od2G 2022 01 4.9929 9.984642 0.185334 255.3420 145.8259 9.0324 20250704 6.0 4.0 C/2014 OG392 (PANSTARRS) MPC182878 - PK14U040 2027 09 13.8851 1.883631 0.463706 347.8408 11.9262 6.4220 20250704 18.0 4.0 P/2014 U4 (PANSTARRS) MPC 91616 - CK14UR1N 2031 01 16.3106 10.960439 1.004248 326.0768 189.9629 95.4446 20250704 2.5 3.2 C/2014 UN271 (Bernardinelli-Bernstein) MPEC 2025-MC0 - PK14V010 2027 11 27.5861 2.557771 0.533392 177.6468 166.1798 22.4990 20250704 14.0 4.0 P/2014 V1 (PANSTARRS) MPC 95211 - PK14W040 2032 11 23.9288 4.242812 0.355140 67.7508 33.3026 15.2833 20250704 11.0 4.0 P/2014 W4 (PANSTARRS) MPC105542 - PK14X010 2030 06 15.0090 1.791673 0.710924 33.9558 61.5428 26.0481 20250704 15.0 4.0 P/2014 X1 (Elenin) MPC 94281 - PK15A030 2015 02 23.4562 1.165660 0.850870 249.6656 277.4875 172.5515 20250704 20.0 4.0 P/2015 A3 (PANSTARRS) MPC 92275 - PK15B010 2015 09 6.5437 5.997301 0.366940 188.6655 352.8487 18.0890 20250704 8.5 4.0 P/2015 B1 (PANSTARRS) MPC 99270 - PK15B040 2015 02 9.3427 3.719384 0.562652 227.0984 266.1377 1.7676 20250704 11.0 4.0 P/2015 B4 (Lemmon-PANSTARRS) MPC109141 - PK15C010 2032 02 1.6100 2.824579 0.568428 178.0607 348.7420 13.8813 20250704 12.5 4.0 P/2015 C1 (TOTAS-Gibbs) MPC101096 - PK15D050 2014 04 10.7322 4.544292 0.491924 39.6293 74.0869 20.5511 20250704 9.0 4.0 P/2015 D5 (Kowalski) MPC109141 - PK15D060 2034 07 1.2392 4.536751 0.362717 125.9079 45.3766 20.3058 20250704 10.5 4.0 P/2015 D6 (Lemmon-PANSTARRS) MPEC 2024-R10 - PK15K050 2032 11 2.6672 3.016799 0.551612 106.0921 134.3121 39.9251 20250704 13.5 4.0 P/2015 K5 (PANSTARRS) MPC 95213 - PK15M020 2035 03 16.5792 5.966221 0.177672 225.7217 86.6990 3.9678 20250704 8.5 4.0 P/2015 M2 (PANSTARRS) MPC107684 - PK15P040 2030 12 11.6187 2.510179 0.584997 280.7429 104.6750 8.7223 20250704 14.0 4.0 P/2015 P4 (PANSTARRS) MPC 99819 - PK15PM9D 2034 12 14.9724 4.864893 0.325037 352.6763 342.7492 2.0200 20250704 11.5 2.0 P/2015 PD229 (Cameron-ISON) MPEC 2022-K19 - PK15Q020 2015 09 13.3654 1.820127 0.752296 244.6420 228.5249 146.5493 20250704 15.5 4.0 P/2015 Q2 (Pimentel) MPC 96867 - PK15R010 2029 10 7.6909 2.160652 0.632855 300.5079 48.3923 22.6808 20250704 14.0 4.0 P/2015 R1 (PANSTARRS) MPC 98562 - PK15R020 2024 12 15.7157 2.454984 0.451973 149.8752 168.6021 15.4827 20250704 14.5 4.0 P/2015 R2 (PANSTARRS) MPC 95734 - PK15T19O 2025 11 23.5388 2.911378 0.359609 89.3432 321.6614 6.5055 20250704 14.0 4.0 P/2015 TO19 (Lemmon-PANSTARRS) MPC102953 - PK15TK0P 2016 11 3.5781 3.359973 0.537360 82.6033 6.9023 8.7782 20250704 11.0 4.0 P/2015 TP200 (LINEAR) MPC110080 - PK15W020 2015 10 8.5676 2.660895 0.635185 117.7196 294.0689 11.6209 20250704 13.0 4.0 P/2015 W2 (Catalina) MPC101098 - PK15X030 2026 10 23.6464 2.799425 0.439829 306.9776 77.2548 24.4221 20250704 15.0 4.0 P/2015 X3 (PANSTARRS) MPEC 2023-J29 - PK15X060 2025 05 11.3314 2.273686 0.174154 329.6969 106.9295 4.5659 20250704 16.0 4.0 P/2015 X6 (PANSTARRS) MPC115881 - PK16A030 2017 04 26.7130 4.821603 0.387126 340.8018 187.1275 8.5217 20250704 10.0 4.0 P/2016 A3 (PANSTARRS) MPEC 2022-OB6 - PK16A070 2027 05 27.7398 2.182866 0.569635 352.8313 220.5194 16.2498 20250704 16.0 4.0 P/2016 A7 (PANSTARRS) MPC102098 - PK16G010 2025 05 16.1412 2.041076 0.210016 111.0871 204.0100 10.9700 20250704 14.0 4.0 P/2016 G1 (PANSTARRS) MPEC 2021-P47 - CK16J020 2016 04 12.6533 1.496297 1.000355 318.2561 186.2634 130.3767 20250704 17.0 4.0 C/2016 J2 (Denneau) MPEC 2024-C04 - PK16P010 2027 03 6.0686 2.283411 0.287243 271.0683 319.0083 24.4528 20250704 15.0 4.0 P/2016 P1 (PANSTARRS) MPC102099 - PK16P050 2023 05 22.0551 4.430852 0.057309 33.8505 185.3752 7.0380 20250704 13.2 4.0 P/2016 P5 (COIAS) MPC184408 - CK16Q020 2021 05 11.5880 7.079904 1.002346 84.5271 322.3497 109.3247 20250704 6.0 4.0 C/2016 Q2 (PANSTARRS) MPEC 2024-H50 - PK16R040 2028 11 19.5093 2.803989 0.474705 174.0972 168.2658 10.8634 20250704 12.5 4.0 P/2016 R4 (Gibbs) MPEC 2022-K19 - PK16S010 2017 03 20.6542 2.379675 0.712113 273.1569 227.6406 94.7315 20250704 12.0 4.0 P/2016 S1 (PANSTARRS) MPC105543 - PK16W48M 2017 02 27.6996 1.763865 0.784197 36.1797 59.9444 117.6165 20250704 15.0 4.0 P/2016 WM48 (Lemmon) MPC106345 - CK16X010 2019 04 30.8464 7.560867 0.997282 224.6167 256.3013 26.4693 20250704 6.0 4.0 C/2016 X1 (Lemmon) MPEC 2021-P47 - CK17B030 2019 01 30.0654 3.933033 0.998795 284.7580 2.2490 54.2256 20250704 6.0 4.0 C/2017 B3 (LINEAR) MPEC 2022-OB6 - PK17B040 2017 01 5.8178 2.800894 0.364952 11.0197 121.4578 20.0584 14.5 4.0 P/2017 B4 (PANSTARRS) MPC103847 - PK17D010 2027 01 30.9620 2.710809 0.437819 8.0875 82.1915 20.7713 20250704 14.0 4.0 P/2017 D1 (Fuls) MPEC 2022-OB6 - PK17D040 2016 09 10.9271 2.785583 0.630653 212.1344 264.9133 10.5614 20250704 13.0 4.0 P/2017 D4 (PANSTARRS) MPEC 2022-OB6 - PK17F36L 2025 08 8.6591 2.830970 0.032757 90.2137 313.4509 15.6870 20250704 14.7 4.0 P/2017 FL36 (PANSTARRS) MPC184408 - PK17G010 2016 04 21.3013 2.510961 0.650879 225.2568 247.1364 5.1551 20250704 13.5 4.0 P/2017 G1 (PANSTARRS) MPEC 2024-C04 - PK17G020 2017 06 10.4816 2.820744 0.648953 105.2066 79.8952 47.9682 20250704 13.0 4.0 P/2017 G2 (PANSTARRS) MPC108595 - CK17K020 2022 12 18.5344 1.799875 0.998948 236.1716 88.2219 87.6429 20250704 1.5 4.0 C/2017 K2 (PANSTARRS) MPC184408 - PK17K030 2030 07 30.9363 2.351663 0.579109 253.2862 354.1784 4.2723 20250704 14.5 4.0 P/2017 K3 (Gasparovic) MPEC 2021-N06 - CK17K050 2020 03 25.4539 7.677126 1.002898 171.9347 102.4583 82.2794 20250704 5.0 4.0 C/2017 K5 (PANSTARRS) MPEC 2021-P47 - CK17M040 2019 01 17.6183 3.235718 1.000164 167.4074 66.0109 105.6277 20250704 6.0 4.0 C/2017 M4 (ATLAS) MPEC 2022-OB6 - PK17P010 2018 06 18.8549 5.473605 0.308962 122.7684 221.4692 7.6880 20250704 10.0 4.0 P/2017 P1 (PANSTARRS) MPC114599 - PK17S080 2027 05 4.5075 1.691800 0.391136 254.9230 191.5071 29.8401 20250704 16.0 4.0 P/2017 S8 (PANSTARRS) MPEC 2022-OB6 - CK17T020 2020 05 6.0897 1.603682 0.999000 92.7777 64.4351 57.2833 20250704 5.0 4.0 C/2017 T2 (PANSTARRS) MPEC 2024-A43 - PK17T13W 2018 06 23.7848 2.065285 0.710648 120.0220 322.1191 44.8841 20250704 15.0 2.0 P/2017 TW13 (Lemmon) MPC115882 - PK17U030 2030 03 15.8502 4.423343 0.100854 296.4660 165.0559 15.9225 20250704 11.0 4.0 P/2017 U3 (PANSTARRS) MPEC 2022-K19 - CK17U070 2019 09 16.2391 6.418830 1.002723 326.4149 276.3210 142.6395 20250704 8.3 2.0 C/2017 U7 (PANSTARRS) MPEC 2023-A50 - PK17W030 2018 02 26.7198 3.853815 0.507077 327.7731 210.0647 18.1889 20250704 10.5 4.0 P/2017 W3 (Gibbs) MPC114601 - CK17Y020 2020 11 4.8999 4.621078 1.001045 147.8031 66.0290 128.4477 20250704 15.0 4.0 C/2017 Y2 (PANSTARRS) MPEC 2024-DC6 - PK17Y030 2018 02 6.3655 1.276706 0.869645 67.3210 154.0257 27.6318 20250704 16.5 4.0 P/2017 Y3 (Leonard) MPC111770 - CK18A030 2019 01 8.6385 3.293761 0.990477 86.5181 194.3603 139.6109 20250704 8.5 4.0 C/2018 A3 (ATLAS) MPEC 2021-P47 - PK18A050 2031 01 31.3389 2.674316 0.524502 359.5561 87.7836 23.6241 20250704 15.0 4.0 P/2018 A5 (PANSTARRS) MPC109147 - CK18A060 2019 07 10.2894 3.016619 0.798840 264.2645 340.4607 77.1628 20250704 9.0 4.0 C/2018 A6 (Gibbs) MPEC 2024-JU4 - PK18C010 2031 07 31.0441 2.640101 0.532676 235.8127 270.1885 5.1011 20250704 13.5 4.0 P/2018 C1 (Lemmon-Read) MPC114601 - CK18D04O 2019 08 17.1215 2.421970 0.905132 176.4266 251.3960 160.4450 20250704 11.0 4.0 C/2018 DO4 (Lemmon) MPEC 2022-M88 - CK18F010 2018 12 10.1211 2.990928 0.986199 71.4188 177.3236 46.1777 20250704 11.5 4.0 C/2018 F1 (Grauer) MPEC 2021-R75 - CK18F040 2019 11 30.8210 3.448655 0.998003 263.1942 26.5400 78.1407 20250704 11.0 6.0 C/2018 F4 (PANSTARRS) MPEC 2023-A50 - CK18F04a 2019 11 30.8091 3.448523 0.997950 263.1910 26.5402 78.1409 20250704 11.0 6.0 C/2018 F4-A MPEC 2021-Y10 - CK18F04b 2019 11 30.7459 3.448339 0.998039 263.1768 26.5397 78.1418 20250704 11.0 6.0 C/2018 F4-B MPEC 2023-D41 - PK18H020 2027 03 18.2524 2.029226 0.539827 119.1705 67.9862 7.4163 20250704 16.6 2.0 P/2018 H2 (PANSTARRS) MPC114602 - CK18K03J 2019 09 8.6662 3.617288 0.994751 217.5306 91.6955 136.6200 20250704 12.2 2.0 C/2018 KJ3 (Lemmon) MPEC 2021-R75 - CK18L020 2018 11 29.4188 1.721709 0.992680 56.3436 242.9908 67.2192 20250704 10.0 4.0 C/2018 L2 (ATLAS) MPEC 2021-P47 - PK18L040 2029 07 28.4695 1.690964 0.658312 140.5009 145.2199 26.5956 20250704 17.5 4.0 P/2018 L4 (PANSTARRS) MPC114603 - CK18N020 2019 11 12.0904 3.135748 1.002029 25.3263 24.5290 77.4927 20250704 6.0 4.0 C/2018 N2 (ASASSN) MPEC 2022-YN2 - PK18P040 2018 11 6.8374 3.689579 0.448990 8.5165 353.1591 23.0772 20250704 12.0 4.0 P/2018 P4 (PANSTARRS) MPC114603 - CK18P050 2019 02 25.5182 4.603980 0.641529 132.0324 216.2721 7.2465 20250704 11.0 4.0 C/2018 P5 (PANSTARRS) MPEC 2021-P47 - CK18R030 2019 06 7.9891 1.284591 0.999287 112.8119 324.3538 69.6862 20250704 9.5 4.0 C/2018 R3 (Lemmon) MPC118841 - CK18R050 2019 01 10.7853 3.637759 0.841698 178.2719 171.2728 103.6802 20250704 11.5 4.0 C/2018 R5 (Lemmon) MPC114603 - CK18S020 2018 11 5.2573 5.491788 0.617817 290.9543 85.1075 64.1106 20250704 7.5 4.0 C/2018 S2 (TESS) MPEC 2022-QC6 - CK18U010 2021 11 2.1021 4.985700 1.000084 180.3481 75.5136 108.3258 20250704 5.0 4.0 C/2018 U1 (Lemmon) MPC184408 - CK18V010 2018 12 4.1910 0.390572 1.000463 89.5853 129.6200 144.2041 20250704 12.0 4.0 C/2018 V1 (Machholz-Fujikawa-Iwamoto) MPC114604 - CK18V020 2018 11 26.4584 2.492141 0.901315 319.2950 357.2290 159.1610 20250704 15.0 4.0 C/2018 V2 (ATLAS) MPC115884 - PK18V02N 2026 08 15.7446 2.119352 0.478142 138.9254 226.4377 18.2567 20250704 15.0 4.0 P/2018 VN2 (Leonard) MPEC 2025-A40 - AK18V030 2019 09 10.4842 1.329570 0.989542 3.5727 308.8233 164.9119 20250704 15.7 2.0 A/2018 V3 MPEC 2025-A40 - CK18V040 2019 03 2.4092 3.204276 0.985200 0.1041 78.2470 69.0425 20250704 12.5 4.0 C/2018 V4 (Africano) MPEC 2022-M21 - PK18V050 2018 10 6.1962 4.708732 0.475752 260.8991 171.2903 10.5771 20250704 12.5 4.0 P/2018 V5 (Trujillo-Sheppard) MPEC 2021-P47 - CK18W010 2019 05 13.9747 1.351258 0.937853 251.1649 233.6294 83.3933 20250704 15.5 2.0 C/2018 W1 (Catalina) MPEC 2021-P47 - CK18W020 2019 09 5.7416 1.465370 1.000947 158.2402 181.9877 116.5332 20250704 9.5 4.0 C/2018 W2 (Africano) MPEC 2021-P47 - AK18W030 2021 04 13.1668 4.281592 0.993880 313.8598 251.6873 104.8377 20250704 10.7 2.0 A/2018 W3 MPEC 2023-M14 - CK18X020 2019 07 9.8921 2.110888 0.985030 162.0125 340.6296 23.1088 20250704 12.0 4.0 C/2018 X2 (Fitzsimmons) MPC119996 - CK18X030 2019 01 1.6579 2.694913 0.782898 359.8709 78.7970 43.4256 20250704 14.5 4.0 C/2018 X3 (PANSTARRS) MPC114604 - CK18Y010 2019 02 3.3150 1.293693 0.989762 357.8677 147.3324 160.4846 20250704 11.5 4.0 C/2018 Y1 (Iwamoto) MPEC 2024-A43 - PK18Y020 2019 01 4.6903 3.877806 0.480017 162.3940 297.1156 11.6956 20250704 11.5 4.0 P/2018 Y2 (Africano) MPC114605 - PK19A010 2030 05 6.9278 2.196694 0.570316 150.7890 312.2099 13.7724 20250704 16.0 4.0 P/2019 A1 (PANSTARRS) MPC114605 - PK19A020 2018 11 24.3796 3.521630 0.383296 323.9616 139.3657 14.8739 20250704 10.5 4.0 P/2019 A2 (ATLAS) MPEC 2021-P47 - PK19A030 2024 03 2.7296 2.304051 0.267596 325.6444 31.2573 15.3549 20250704 16.0 4.0 P/2019 A3 (PANSTARRS) MPEC 2022-M21 - PK19A040 2027 05 26.8653 2.385905 0.087429 343.2446 119.3536 13.3059 20250704 15.0 4.0 P/2019 A4 (PANSTARRS) MPEC 2022-L66 - CK19A050 2019 06 7.0715 6.312808 0.706469 355.8306 146.5112 67.5515 20250704 9.5 4.0 C/2019 A5 (PANSTARRS) MPEC 2021-P47 - PK19A060 2031 01 25.6369 1.926550 0.640355 156.2525 280.1733 33.2987 20250704 16.0 4.0 P/2019 A6 (Lemmon-PANSTARRS) MPC114605 - CK19A090 2019 07 27.2835 1.426383 0.963721 237.8776 278.4713 84.4005 20250704 15.0 4.0 C/2019 A9 (PANSTARRS) MPC118842 - CK19B010 2019 03 18.2485 1.603967 0.988528 174.8299 290.2318 123.4940 20250704 16.0 4.0 C/2019 B1 (Africano) MPEC 2022-L66 - PK19B020 2027 02 24.2855 2.523560 0.357694 0.5825 175.6464 16.9504 20250704 14.5 4.0 P/2019 B2 (Groeller) MPC115885 - CK19B030 2021 01 19.5604 6.830083 0.998099 263.9991 358.4017 66.6061 20250704 5.5 4.0 C/2019 B3 (PANSTARRS) MPEC 2024-JU4 - CK19C010 2020 05 4.5994 6.567159 0.990495 319.0178 212.3679 36.0373 20250704 10.0 4.0 C/2019 C1 (ATLAS) MPEC 2021-P47 - CK19D010 2019 05 8.7352 1.592204 0.988322 70.7138 231.6685 34.0126 20250704 13.0 4.0 C/2019 D1 (Flewelling) MPEC 2022-O08 - CK19E030 2023 11 15.6415 10.313297 0.998106 280.7196 347.1944 84.3157 20250704 2.5 4.0 C/2019 E3 (ATLAS) MPEC 2025-MC0 - CK19F010 2021 06 21.1232 3.608322 1.000265 251.3013 38.6642 54.2541 20250704 5.5 4.0 C/2019 F1 (ATLAS-Africano) MPEC 2024-GJ3 - CK19F020 2019 09 7.7956 2.238729 0.864779 11.6092 175.3448 19.3361 20250704 12.0 4.0 C/2019 F2 (ATLAS) MPEC 2025-A40 - CK19G020 2019 12 6.4381 2.306186 0.994256 82.7893 208.2395 159.2544 20250704 15.0 4.0 C/2019 G2 (PANSTARRS) MPEC 2024-E01 - AK19G030 2018 12 3.6143 2.836336 0.834254 161.7245 49.8915 156.8091 20250704 17.1 2.0 A/2019 G3 MPEC 2022-VC5 - PK19G21G 2019 05 9.6257 3.946177 0.471643 208.5912 340.5657 6.0827 20250704 12.0 4.0 P/2019 GG21 (PANSTARRS) MPC114607 - CK19H010 2019 04 26.8205 1.839807 0.991912 19.2390 269.3122 104.3568 20250704 15.5 4.0 C/2019 H1 (NEOWISE) MPEC 2022-M21 - CK19J010 2019 04 5.8702 2.481492 0.962652 167.5646 98.2364 24.5222 20250704 12.0 4.0 C/2019 J1 (Lemmon) MPEC 2023-A50 - CK19J020 2019 07 21.1670 1.714037 0.989293 98.5458 25.4593 105.2110 20250704 13.0 4.0 C/2019 J2 (Palomar) MPEC 2021-R75 - CK19J030 2019 08 1.8901 2.361450 0.999871 16.4883 270.6557 131.2935 20250704 13.5 4.0 C/2019 J3 (ATLAS) MPC117071 - CK19J06U 2019 06 2.8962 2.031357 0.999851 94.7649 21.6836 148.2981 20250704 14.5 4.0 C/2019 JU6 (ATLAS) MPEC 2022-M21 - CK19K010 2020 02 10.8398 2.021602 0.999302 265.7831 73.3121 87.0187 20250704 10.0 4.0 C/2019 K1 (ATLAS) MPEC 2022-O08 - CK19K040 2019 06 15.3003 2.275876 0.998607 140.0231 180.3025 105.2873 20250704 12.5 4.0 C/2019 K4 (Ye) MPC119997 - CK19K050 2019 06 21.2566 2.055285 0.987781 175.1414 177.2804 15.2915 20250704 13.0 4.0 C/2019 K5 (Young) MPEC 2021-P47 - CK19K060 2020 05 18.5124 3.917298 0.995749 187.4284 42.9778 132.3901 20250704 11.5 4.0 C/2019 K6 (PANSTARRS) MPEC 2021-P47 - CK19K070 2020 06 17.0927 4.474084 1.000309 27.3544 308.0371 103.4765 20250704 6.0 4.0 C/2019 K7 (Smith) MPEC 2024-GJ3 - CK19K080 2019 07 20.1212 3.198693 0.998071 85.3731 290.9886 93.0474 20250704 11.5 4.0 C/2019 K8 (ATLAS) MPEC 2021-R75 - CK19L010 2019 08 7.0104 2.905335 0.704062 50.0086 254.4271 9.9737 20250704 13.5 4.0 C/2019 L1 (PANSTARRS) MPEC 2023-A50 - CK19L020 2019 04 3.8918 1.620715 0.935551 18.8471 12.5830 152.1463 20250704 16.0 4.0 C/2019 L2 (NEOWISE) MPC115886 - PK19L02D 2020 01 29.9897 4.488398 0.131411 116.4230 178.6902 11.6137 20250704 8.5 4.0 P/2019 LD2 (ATLAS) MPEC 2024-GJ3 - CK19L030 2022 01 10.1262 3.558779 1.003160 171.7521 290.7167 48.3459 20250704 4.5 4.0 C/2019 L3 (ATLAS) MPEC 2025-MC0 - PK19L04M 2019 06 20.0705 2.359775 0.586175 68.2091 72.8883 36.4160 20250704 9.5 4.0 P/2019 LM4 (Palomar) MPEC 2024-YC7 - CK19L07B 2019 03 27.6115 2.494844 0.928785 336.7784 4.0055 164.2786 20250704 17.0 4.0 C/2019 LB7 (Kleyna) MPC118095 - CK19M030 2018 12 31.4469 2.424672 0.999517 87.9350 155.0519 99.6519 20250704 12.2 4.0 C/2019 M3 (ATLAS) MPC118095 - CK19M040 2019 09 9.5803 9.191042 1.000370 260.3409 52.6421 65.6913 20250704 5.0 4.0 C/2019 M4 (TESS) MPEC 2023-JA2 - CK19N010 2020 11 30.5158 1.703084 0.998241 193.3440 13.5123 82.5319 20250704 7.5 4.0 C/2019 N1 (ATLAS) MPEC 2023-C45 - AK19N020 2019 08 22.4331 1.940091 0.998286 347.0670 276.2241 89.3209 20250704 12.5 2.0 A/2019 N2 MPEC 2023-CD8 - CK19N03J 2020 10 22.2422 4.362925 1.001431 246.8718 142.4924 99.3351 20250704 9.0 4.0 C/2019 NJ3 (Lemmon) MPEC 2022-A21 - CK19O020 2023 04 6.0719 9.680939 0.835215 129.5753 48.2630 93.2995 20250704 5.0 4.0 C/2019 O2 (PANSTARRS) MPEC 2025-MC0 - CK19O030 2021 03 8.4073 8.820735 1.002710 60.1002 300.4764 89.7961 20250704 3.5 4.0 C/2019 O3 (Palomar) MPC182878 - AK19O040 2020 02 11.1350 3.642310 0.890387 61.8239 354.9263 115.0040 20250704 15.5 2.0 A/2019 O4 MPEC 2021-P47 - CK19Q010 2020 07 22.1922 5.002731 1.002396 56.2548 42.4671 155.7212 20250704 8.5 4.0 C/2019 Q1 (Lemmon) MPEC 2024-EF7 - AK19Q020 2019 07 23.6649 1.260802 0.978554 176.5095 188.1250 158.9713 20250704 18.0 2.0 A/2019 Q2 MPC117072 - PK19S020 2029 06 21.3612 3.775711 0.204678 216.9312 93.1803 10.4637 20250704 13.5 4.0 P/2019 S2 (PANSTARRS) MPC117072 - PK19S030 2025 12 19.1677 1.807087 0.470749 213.0959 150.1407 8.6940 20250704 18.3 4.0 P/2019 S3 (PANSTARRS) MPEC 2022-CN4 - CK19S040 2020 04 9.3893 3.439097 0.986183 71.3706 63.1558 92.0955 20250704 11.0 4.0 C/2019 S4 (Lemmon) MPEC 2021-S45 - AK19T010 2021 01 14.9389 4.274749 0.889697 90.9821 6.9299 120.8206 20250704 13.0 2.0 A/2019 T1 MPEC 2023-N01 - CK19T020 2021 04 22.5147 2.643334 0.999228 239.3867 155.6546 111.3718 20250704 9.0 4.0 C/2019 T2 (Lemmon) MPEC 2023-R20 - CK19T030 2021 03 4.7246 5.953492 0.998707 112.4886 139.5435 121.8745 20250704 6.8 4.0 C/2019 T3 (ATLAS) MPEC 2023-UR6 - CK19T040 2022 06 8.6638 4.237537 0.995186 351.1087 199.9017 53.6246 20250704 5.0 4.0 C/2019 T4 (ATLAS) MPC182878 - PK19T050 2019 08 3.4432 1.523256 0.809776 189.6242 247.6127 33.4929 20250704 15.0 4.0 P/2019 T5 (ATLAS) MPEC 2021-P47 - PK19T060 2019 11 8.8876 2.054917 0.622457 329.0590 71.2477 18.6986 20250704 15.5 4.0 P/2019 T6 (PANSTARRS) MPEC 2021-P47 - PK19U040 2026 04 28.5243 1.844755 0.475747 181.0825 200.0015 11.6954 20250704 19.0 4.0 P/2019 U4 (PANSTARRS) MPC118096 - CK19U050 2023 03 29.4452 3.624255 1.000180 181.4498 2.6127 113.5125 20250704 4.5 4.0 C/2019 U5 (PANSTARRS) MPEC 2025-MC0 - CK19U060 2020 06 18.3188 0.906504 0.997015 329.4302 235.7500 60.9864 20250704 10.0 4.0 C/2019 U6 (Lemmon) MPEC 2022-H04 - CK19V010 2020 07 17.5719 3.092875 0.998825 51.1932 83.1481 61.9482 20250704 11.0 4.0 C/2019 V1 (Borisov) MPEC 2022-N37 - PK19V020 2020 10 17.2446 5.007460 0.331876 335.6331 189.1377 11.8069 20250704 10.0 4.0 P/2019 V2 (Groeller) MPEC 2022-L66 - PK19W010 2029 01 22.3031 3.333198 0.267194 18.8898 35.3616 23.4666 20250704 12.9 4.0 P/2019 W1 (PANSTARRS) MPEC 2023-A50 - PK19X010 2019 07 24.7030 4.301967 0.303829 36.9897 43.6770 10.2457 20250704 10.4 4.0 P/2019 X1 (Pruyne) MPEC 2021-P47 - PK19X020 2026 11 15.2889 1.815318 0.500474 213.5159 250.8309 15.8946 20250704 18.0 4.0 P/2019 X2 (Pan-STARRS) MPEC 2020-C98 - CK19Y010 2020 03 17.1972 0.826391 0.990629 57.9153 31.4771 73.2790 20250704 13.7 4.0 C/2019 Y1 (ATLAS) MPC119999 - CK19Y040 2020 05 29.6537 0.257236 0.999222 177.4097 120.7913 44.9348 20250704 11.8 6.0 C/2019 Y4 (ATLAS) MPEC 2024-A43 - CK19Y04a 2020 05 29.7075 0.255391 1.001364 177.2419 121.1590 45.3695 20250704 11.6 6.0 C/2019 Y4-A (ATLAS) MPEC 2020-L06 - CK19Y04b 2020 05 29.6623 0.256924 0.999811 177.3688 120.8545 45.0161 20250704 12.1 6.0 C/2019 Y4-B (ATLAS) MPEC 2025-CE3 - CK19Y04c 2020 05 29.6613 0.256463 1.002092 177.2746 120.8863 45.1533 20250704 12.7 6.0 C/2019 Y4-C (ATLAS) MPEC 2020-L06 - CK19Y04d 2020 05 29.7471 0.255786 0.996199 177.4177 121.2479 45.2063 20250704 12.5 6.0 C/2019 Y4-D (ATLAS) MPEC 2020-L06 - CK19Y050 2019 08 16.5695 4.933889 0.992819 303.6649 51.7668 82.7743 20250704 11.0 4.0 C/2019 Y5 (PANSTARRS) MPEC 2023-A50 - AK20A010 2019 11 30.2101 1.671654 0.934353 302.4016 119.0638 149.0316 20250704 18.0 2.0 A/2020 A1 MPEC 2023-A50 - CK20A020 2020 01 7.1186 0.975249 0.998989 68.0144 286.1891 120.5054 20250704 13.5 4.0 C/2020 A2 (Iwamoto) MPEC 2022-YN2 - CK20A030 2019 06 26.8752 5.753183 0.998860 268.2359 120.7985 146.6210 20250704 8.0 4.0 C/2020 A3 (ATLAS) MPEC 2023-A50 - PK20A040 2019 11 24.4624 2.834334 0.654470 144.9043 312.2812 25.0027 20250704 15.0 4.0 P/2020 A4 (PANSTARRS-Lemmon) MPEC 2022-P91 - AK20B010 2019 12 27.6508 1.739218 0.966608 154.8788 309.8032 18.5405 20250704 21.0 2.0 A/2020 B1 MPEC 2020-N08 - CK20B020 2020 01 27.2915 2.756049 0.959407 143.6281 354.1778 55.7550 20250704 10.0 4.0 C/2020 B2 (Lemmon) MPEC 2020-HN5 - CK20B030 2019 10 20.7757 3.327419 0.996833 324.9303 185.7465 20.7068 20250704 13.0 4.0 C/2020 B3 (Rankin) MPEC 2022-N37 - PK20B040 2021 11 19.3153 6.435367 0.192890 342.0503 185.9489 11.6031 20250704 10.5 4.0 P/2020 B4 (Sheppard) MPEC 2023-KD6 - CK20F020 2022 07 12.5203 8.813532 1.002600 48.2374 250.3008 163.5897 20250704 4.5 4.0 C/2020 F2 (ATLAS) MPC184409 - CK20F030 2020 07 4.9327 0.293493 0.999270 37.3485 61.0770 129.1144 20250704 7.5 5.2 C/2020 F3 (NEOWISE) MPEC 2021-O56 - CK20F050 2021 03 16.1872 4.326158 0.973664 310.6172 350.5414 52.2322 20250704 6.5 3.2 C/2020 F5 (MASTER) MPEC 2024-UQ8 - CK20F060 2020 04 10.3420 3.498170 0.989778 344.3346 207.8408 174.5842 20250704 14.5 2.8 C/2020 F6 (PANSTARRS) MPEC 2020-L06 - CK20F070 2021 11 13.8690 5.334920 0.990654 227.9832 321.8223 93.9823 20250704 7.0 4.0 C/2020 F7 (Lemmon) MPEC 2024-A43 - CK20F080 2020 05 25.8322 0.432700 1.000066 68.1111 259.8028 110.5565 20250704 10.0 4.0 C/2020 F8 (SWAN) MPEC 2023-J29 - PK20G010 2027 01 24.2733 0.501977 0.860814 207.6480 240.0986 18.5072 20250704 17.0 4.0 P/2020 G1 (Pimentel) MPEC 2020-L06 - CK20H020 2020 04 26.8894 0.828497 0.995322 26.5850 277.6716 124.7791 20250704 14.0 3.2 C/2020 H2 (Pruyne) MPEC 2022-YB4 - CK20H030 2020 06 5.7161 2.300288 1.000000 30.4456 270.6227 62.5292 13.5 4.0 C/2020 H3 (Wierzchos) MPEC 2020-HM1 - CK20H040 2020 08 29.2295 0.927483 0.980616 117.5769 307.4563 84.4946 20250704 15.0 3.2 C/2020 H4 (Leonard) MPEC 2020-L06 - CK20H050 2020 12 9.9606 9.335100 0.998435 326.2656 210.6147 70.2290 20250704 5.0 4.0 C/2020 H5 (Robinson) MPC184409 - CK20H060 2021 09 29.5794 4.696878 0.997639 20.1931 213.6921 79.9888 20250704 8.0 3.2 C/2020 H6 (ATLAS) MPEC 2024-JU4 - CK20H070 2020 06 2.9509 4.419545 0.996854 82.6780 323.5194 135.9235 11.0 4.0 C/2020 H7 (Lemmon) MPEC 2020-KB7 - CK20H080 2020 06 4.7913 4.663399 0.992103 128.8196 68.4385 99.7029 20250704 10.5 4.0 C/2020 H8 (PANSTARRS) MPEC 2021-N06 - AK20H090 2019 12 21.7839 2.562001 0.992501 312.6202 213.1196 137.8737 20250704 18.0 2.0 A/2020 H9 MPEC 2022-ED3 - CK20H110 2020 09 12.5557 7.621011 0.999752 91.3662 303.0571 151.3735 20250704 8.5 4.0 C/2020 H11 (PANSTARRS-Lemmon) MPEC 2023-HN7 - CK20J010 2021 04 18.0382 3.345139 0.999664 341.5800 226.5860 142.3072 20250704 8.5 3.2 C/2020 J1 (SONEAR) MPEC 2023-KD6 - CK20K010 2023 05 8.7544 3.074038 0.998740 213.9707 94.3664 89.6713 20250704 5.5 4.0 C/2020 K1 (PANSTARRS) MPC184409 - CK20K020 2020 08 4.4309 8.880287 1.000975 67.3102 288.4337 90.9888 20250704 10.8 4.0 C/2020 K2 (PANSTARRS) MPEC 2021-N06 - CK20K030 2020 06 1.0031 1.583069 1.000000 64.4924 28.3546 129.0152 14.5 4.0 C/2020 K3 (Leonard) MPEC 2020-KF9 - CK20K040 2020 03 4.9823 1.744028 0.927105 308.7843 264.2744 125.5850 20250704 16.5 4.0 C/2020 K4 (PANSTARRS) MPEC 2020-L06 - CK20K050 2021 06 4.2523 1.540685 1.000806 249.6415 86.1417 67.0686 20250704 11.0 4.0 C/2020 K5 (PANSTARRS) MPEC 2021-R75 - CK20K060 2021 09 14.7385 5.866114 1.002131 44.2782 291.5993 103.6306 20250704 8.0 4.0 C/2020 K6 (Rankin) MPEC 2023-N01 - CK20K070 2019 10 25.2971 6.388359 0.932501 358.0812 286.1322 32.0443 20250704 8.0 4.0 C/2020 K7 (PANSTARRS) MPEC 2023-A50 - CK20K080 2020 09 15.7041 0.471517 1.000318 260.1612 181.3013 31.3813 20250704 15.0 3.2 C/2020 K8 (Catalina-ATLAS) MPEC 2021-P47 - PK20K090 2029 09 29.3369 2.860423 0.320135 197.0903 166.3110 23.1904 20250704 12.5 4.0 P/2020 K9 (Lemmon-PANSTARRS) MPEC 2021-BE3 - PK20M010 2019 12 23.2268 2.796580 0.473521 72.4927 142.6150 8.5345 20250704 14.5 4.0 P/2020 M1 (PANSTARRS) MPEC 2023-C45 - CK20M030 2020 10 25.7447 1.275150 0.953299 328.6688 71.1765 23.4703 20250704 14.5 4.0 C/2020 M3 (ATLAS) MPEC 2022-H30 - AK20M040 2020 11 22.7831 5.940836 0.999750 104.4804 348.6144 160.1025 20250704 14.5 2.0 A/2020 M4 MPEC 2023-N01 - PK20M04K 2027 04 18.8851 6.130198 0.015095 93.5850 0.6643 6.7814 20250704 8.0 4.0 P/2020 MK4 (PANSTARRS) MPEC 2024-NE4 - CK20M050 2021 08 19.7509 2.999892 1.000120 126.2454 352.0194 93.1737 20250704 9.0 4.0 C/2020 M5 (ATLAS) MPEC 2023-FK0 - CK20N010 2021 03 13.1422 1.317603 1.000863 186.8357 279.8569 29.7659 20250704 12.5 4.0 C/2020 N1 (PANSTARRS) MPEC 2022-GA9 - CK20N020 2020 08 24.3134 1.783895 0.982399 331.2024 257.1794 161.0387 20250704 16.0 3.2 C/2020 N2 (ATLAS) MPEC 2021-P47 - CK20O020 2021 08 27.2803 4.856592 0.999607 10.1743 256.7913 71.7623 20250704 8.0 3.2 C/2020 O2 (Amaral) MPEC 2024-JU4 - PK20O030 2021 01 24.9718 4.170330 0.102414 81.1988 266.8180 8.4445 20250704 12.0 4.0 P/2020 O3 (PANSTARRS) MPEC 2023-C45 - CK20P010 2020 10 21.2082 0.341800 1.000437 8.9328 53.4879 45.1117 20250704 14.0 3.2 C/2020 P1 (NEOWISE) MPEC 2021-BE3 - CK20P030 2021 04 22.9255 6.816067 1.003695 82.3495 19.4842 61.8554 20250704 6.0 4.0 C/2020 P3 (ATLAS) MPEC 2024-JU4 - CK20P06V 2021 09 25.8054 2.291077 0.945003 71.2814 329.1285 128.1544 20250704 10.0 4.0 C/2020 PV6 (PANSTARRS) MPEC 2022-PB4 - CK20Q010 2020 08 15.3118 1.319387 0.978840 10.0289 52.4120 142.9230 20250704 14.0 4.0 C/2020 Q1 (Borisov) MPEC 2022-L66 - CK20Q020 2020 01 24.8104 5.419477 0.488831 118.2064 179.8272 3.3358 20250704 12.0 3.2 C/2020 Q2 (PANSTARRS) MPEC 2023-CD7 - CK20R020 2022 02 25.3556 4.699299 0.989082 211.8843 195.1268 53.2156 20250704 9.0 4.0 C/2020 R2 (PANSTARRS) MPEC 2024-F34 - CK20R040 2021 03 2.2096 1.020673 0.989503 46.5134 323.2334 164.4038 20250704 13.5 4.0 C/2020 R4 (ATLAS) MPEC 2022-K19 - PK20R050 2020 05 27.4464 3.429771 0.313126 82.7543 272.9384 11.4395 20250704 9.5 6.0 P/2020 R5 (PANSTARRS) MPEC 2023-C45 - CK20R060 2019 09 6.8288 3.139433 0.989213 271.9979 12.2354 82.8913 20250704 11.0 4.0 C/2020 R6 (Rankin) MPEC 2021-Y10 - CK20R070 2022 09 16.0347 2.951825 0.999647 347.7610 268.3097 114.9031 20250704 7.0 3.2 C/2020 R7 (ATLAS) MPEC 2024-PC5 - PK20S010 2021 01 16.9119 2.959814 0.506859 255.1634 129.4907 13.7148 20250704 14.0 4.0 P/2020 S1 (PANSTARRS) MPEC 2021-BE3 - CK20S020 2020 12 22.0380 1.763836 0.827933 202.4247 197.7094 22.3749 20250704 17.0 4.0 C/2020 S2 (PANSTARRS) MPEC 2022-ST7 - CK20S030 2020 12 11.3747 0.392596 0.997222 350.0484 222.5184 20.0662 20250704 13.5 3.2 C/2020 S3 (Erasmus) MPEC 2024-JU4 - CK20S040 2023 02 9.5797 3.370440 1.002743 21.0598 117.6825 20.5701 20250704 8.5 3.2 C/2020 S4 (PANSTARRS) MPEC 2024-N80 - PK20S050 2028 10 11.3241 2.689414 0.337333 53.2758 316.0205 12.3402 20250704 14.5 4.0 P/2020 S5 (PANSTARRS) MPEC 2021-BE3 - PK20S070 2020 11 17.5411 2.974214 0.409502 40.6632 328.0828 16.0702 20250704 14.5 4.0 P/2020 S7 (PANSTARRS) MPEC 2021-BE3 - CK20S080 2021 04 10.3604 2.355653 0.990150 160.1292 24.0082 108.5435 20250704 12.5 4.0 C/2020 S8 (Lemmon) MPEC 2021-P47 - CK20T020 2021 07 10.5646 2.052449 0.992378 150.3455 83.0341 27.8396 20250704 11.0 3.2 C/2020 T2 (Palomar) MPEC 2022-TD3 - PK20T030 2027 08 27.4539 1.433027 0.592436 357.0804 73.9918 7.2985 20250704 18.0 3.2 P/2020 T3 (PANSTARRS) MPEC 2021-N06 - CK20T040 2021 07 6.0946 2.187607 1.000649 79.5700 50.6069 83.8279 20250704 13.0 3.2 C/2020 T4 (PANSTARRS) MPEC 2021-N06 - CK20T050 2020 10 7.7313 1.897925 0.996874 90.3842 237.8435 66.5575 20250704 16.0 4.0 C/2020 T5 (Lemmon) MPEC 2021-BE3 - PK20U020 2028 05 1.4747 1.846108 0.511336 84.7713 342.8164 6.4197 20250704 18.0 4.0 P/2020 U2 (PANSTARRS) MPEC 2021-N06 - CK20U030 2021 02 6.0002 2.285696 0.966220 124.5156 282.6001 30.1388 20250704 15.0 4.0 C/2020 U3 (Rankin) MPEC 2021-W31 - CK20U040 2022 04 10.0126 5.361889 1.001223 70.1748 120.4059 167.0033 20250704 7.0 4.0 C/2020 U4 (PANSTARRS) MPEC 2024-TD8 - CK20U050 2022 04 28.3828 3.756830 0.999662 75.4662 107.3132 97.3120 20250704 8.0 4.0 C/2020 U5 (PANSTARRS) MPEC 2024-GJ3 - CK20V020 2023 05 8.5256 2.229299 1.001058 162.4581 212.3997 131.6122 20250704 4.9 4.0 C/2020 V2 (ZTF) MPEC 2025-MC0 - PK20V030 2021 02 15.6639 6.239704 0.257885 249.8046 198.2690 23.0210 20250704 8.3 4.0 P/2020 V3 (PANSTARRS) MPEC 2023-D72 - PK20V040 2021 07 20.7006 5.154005 0.451595 257.2525 203.4888 14.2369 20250704 9.0 4.0 P/2020 V4 (Rankin) MPEC 2024-F34 - PK20W010 2020 04 10.3401 5.307780 0.265465 265.3943 124.3860 10.7772 20250704 10.0 4.0 P/2020 W1 (Rankin) MPEC 2021-BE3 - CK20W050 2020 11 30.9310 3.370888 1.002161 24.6067 75.4673 88.6154 20250704 15.0 4.0 C/2020 W5 (Lemmon) MPEC 2021-BE3 - PK20W05J 2021 06 30.5605 4.980074 0.172131 338.0873 177.7635 22.2881 20250704 8.5 4.0 P/2020 WJ5 (Lemmon) MPEC 2024-PC5 - PK20X010 2030 03 18.8489 2.883239 0.364395 323.5276 55.9877 31.6916 20250704 13.0 4.0 P/2020 X1 (ATLAS) MPEC 2024-F34 - CK20X020 2020 11 17.1899 3.832357 0.768324 347.5704 105.3559 18.1866 20250704 10.6 4.0 C/2020 X2 (ATLAS) MPEC 2024-A43 - CK20X040 2020 11 15.4324 5.224026 0.871284 140.2915 161.9550 80.6583 20250704 9.0 4.0 C/2020 X4 (Leonard) MPEC 2021-S45 - CK20Y020 2022 06 17.7716 3.146244 0.997528 266.4145 26.5393 101.2129 20250704 6.5 4.0 C/2020 Y2 (ATLAS) MPEC 2024-YC7 - CK20Y030 2020 12 3.2276 1.990305 0.985526 341.8505 191.3447 83.1438 20250704 13.5 4.0 C/2020 Y3 (ATLAS) MPEC 2021-R75 - CK21A010 2022 01 3.8142 0.615358 1.000244 225.1364 255.9111 132.7537 20250704 8.5 4.0 C/2021 A1 (Leonard) MPEC 2025-A40 - CK21A020 2021 01 21.8720 1.416278 0.993828 338.7999 125.0618 107.0546 20250704 13.5 4.0 C/2021 A2 (NEOWISE) MPEC 2025-A40 - CK21A040 2021 03 19.5786 1.150357 0.972951 204.7541 307.0895 111.6476 20250704 16.0 4.0 C/2021 A4 (NEOWISE) MPEC 2022-ED3 - PK21A050 2026 03 11.2834 2.620511 0.139793 61.5372 328.8096 18.1895 20250704 15.0 4.0 P/2021 A5 (PANSTARRS) MPEC 2021-BE3 - CK21A060 2021 05 3.0775 7.924774 0.999352 351.6259 164.0250 75.5636 20250704 7.0 4.0 C/2021 A6 (PANSTARRS) MPEC 2024-P23 - CK21A070 2021 07 15.1593 1.965197 0.998959 356.0011 154.4016 78.2184 20250704 10.0 4.0 C/2021 A7 (NEOWISE) MPEC 2022-M88 - CK21A090 2023 12 3.9992 7.763845 1.000054 211.6379 314.8536 158.0181 20250704 6.0 4.0 C/2021 A9 (PANSTARRS) MPC182879 - CK21A100 2021 03 14.7158 1.266804 0.985879 82.6460 188.8412 151.9954 20250704 19.0 4.0 C/2021 A10 (NEOWISE) MPEC 2021-N06 - CK21B020 2021 05 4.8499 2.515015 0.993848 335.1197 120.4382 38.0870 20250704 14.0 4.0 C/2021 B2 (PANSTARRS) MPEC 2022-L66 - CK21B030 2021 03 9.2836 2.168354 0.936640 293.6046 67.2827 119.4777 20250704 13.5 4.0 C/2021 B3 (NEOWISE) MPEC 2021-N06 - CK21C010 2020 12 5.7192 3.472904 0.998096 336.0583 186.8266 143.0431 20250704 11.5 4.0 C/2021 C1 (Rankin) MPEC 2023-KD6 - PK21C020 2021 02 24.6427 4.883747 0.488383 78.7235 66.4553 21.9382 20250704 12.0 4.0 P/2021 C2 (PANSTARRS) MPEC 2021-U31 - CK21C030 2021 02 11.0920 2.274153 0.962361 356.9752 181.8517 122.2084 20250704 14.0 4.0 C/2021 C3 (Catalina) MPEC 2024-M41 - CK21C040 2021 01 16.1602 4.493409 0.998805 320.0246 194.2280 132.8314 20250704 9.0 4.0 C/2021 C4 (ATLAS) MPEC 2022-M88 - CK21C050 2023 02 10.9800 3.240329 0.998099 270.8890 323.6736 50.8029 20250704 9.0 4.0 C/2021 C5 (PANSTARRS) MPEC 2024-N80 - CK21C060 2021 11 11.8895 3.284711 0.998782 203.8606 332.3259 164.6092 20250704 12.0 4.0 C/2021 C6 (Lemmon) MPEC 2022-YB4 - CK21D010 2021 02 27.3342 0.908198 0.991099 72.4617 311.1614 31.3554 20250704 13.0 4.0 C/2021 D1 (SWAN) MPEC 2022-F14 - CK21D020 2022 02 3.6408 2.949603 1.001428 125.0680 305.6277 83.7716 20250704 9.0 4.0 C/2021 D2 (ZTF) MPEC 2023-J29 - AK21E020 2020 12 8.9249 2.283019 0.988595 342.2188 190.7499 167.4938 20250704 15.0 2.0 A/2021 E2 MPEC 2022-UY9 - CK21E030 2022 06 11.1215 1.777504 0.999839 228.7998 104.4839 112.5248 20250704 8.5 4.0 C/2021 E3 (ZTF) MPEC 2024-GJ3 - AK21E040 2022 04 24.8287 4.679884 0.990720 48.2831 171.1410 116.3819 20250704 13.5 2.0 A/2021 E4 MPEC 2024-N80 - CK21F010 2022 04 6.7366 0.999262 0.995978 146.9463 203.5500 107.2905 20250704 13.5 4.0 C/2021 F1 (Lemmon-PANSTARRS) MPEC 2022-QD9 - CK21G010 2021 07 20.3378 3.427911 0.951757 107.4352 270.6976 131.5468 20250704 14.0 4.0 C/2021 G1 (Leonard) MPEC 2021-J72 - CK21G020 2024 09 9.1356 4.982275 1.000733 343.2665 221.0945 48.4667 20250704 5.5 4.0 C/2021 G2 (ATLAS) MPEC 2025-MC0 - CK21G030 2021 10 17.8544 5.182610 0.999412 10.5984 147.3452 102.8729 20250704 10.5 4.0 C/2021 G3 (PANSTARRS) MPEC 2022-X67 - PK21H00S 2021 08 4.7430 0.799039 0.809451 46.1180 262.3573 12.1542 20250704 22.0 4.0 P/2021 HS (PANSTARRS) MPEC 2021-Y10 - CK21J010 2021 02 19.4250 1.733825 0.933812 147.1970 88.4324 92.7076 20250704 15.5 4.0 C/2021 J1 (Maury-Attard) MPEC 2022-C56 - CK21J020 2021 09 20.7566 4.701501 0.957931 171.8828 23.3089 156.2116 20250704 12.0 4.0 C/2021 J2 (PANSTARRS) MPEC 2023-XP6 - PK21J030 2019 06 30.3281 4.894588 0.449410 125.6278 110.9981 14.5149 20250704 7.0 4.0 P/2021 J3 (ATLAS) MPEC 2024-F34 - CK21K010 2021 05 2.3406 2.502187 0.801480 184.2229 140.9240 16.2711 20250704 11.0 4.0 C/2021 K1 (ATLAS) MPEC 2022-O08 - CK21K020 2021 09 9.2384 5.463622 1.000445 343.2761 282.3377 100.8713 20250704 8.0 4.0 C/2021 K2 (MASTER) MPEC 2022-O01 - CK21K030 2022 02 3.6382 5.227551 1.004184 182.0124 114.6085 134.7805 20250704 10.0 4.0 C/2021 K3 (Catalina) MPEC 2022-L66 - PK21L020 2021 07 22.8083 1.939405 0.520831 51.4302 266.6527 21.0644 20250704 17.0 4.0 P/2021 L2 (Leonard) MPEC 2021-W31 - CK21L030 2022 02 14.9960 8.460324 1.004544 91.6514 345.0173 78.5377 20250704 6.0 4.0 C/2021 L3 (Borisov) MPEC 2024-H50 - PK21N010 2026 07 27.8469 0.966268 0.675728 21.2255 301.1350 11.4856 20250704 19.0 4.0 P/2021 N1 (ZTF) MPEC 2022-TA0 - PK21N020 2021 11 14.1542 3.805969 0.452131 177.6306 221.7434 13.0601 20250704 9.5 4.0 P/2021 N2 (Fuls) MPEC 2024-GJ3 - CK21N030 2020 08 16.8832 5.711942 0.959308 304.5965 337.5267 26.7638 20250704 8.5 4.0 C/2021 N3 (PANSTARRS) MPEC 2022-YB4 - CK21O010 2021 08 14.7769 0.782739 0.999844 74.4291 41.5402 27.5698 20250704 10.5 4.0 C/2021 O1 (Nishimura) MPEC 2022-A21 - CK21O030 2022 04 21.2907 0.285089 1.000052 300.0216 188.7830 56.8286 20250704 10.5 4.0 C/2021 O3 (PANSTARRS) MPEC 2022-L66 - CK21P010 2022 06 2.5650 4.379761 0.998370 40.5261 359.7121 51.6199 20250704 11.0 4.0 C/2021 P1 (PANSTARRS) MPEC 2024-F34 - CK21P020 2023 01 23.0774 5.067924 0.999623 76.7154 32.0950 150.0547 20250704 9.0 4.0 C/2021 P2 (PANSTARRS) MPEC 2025-MC0 - PK21P030 2021 05 28.2935 2.919152 0.338380 334.0053 358.2478 27.1605 20250704 14.0 4.0 P/2021 P3 (PANSTARRS) MPEC 2024-GJ3 - CK21P040 2022 07 30.4288 1.078600 0.996358 175.8085 348.0064 56.3760 20250704 9.5 4.0 C/2021 P4 (ATLAS) MPEC 2023-A50 - PK21P20E 2028 09 4.4526 1.236194 0.669982 210.4321 99.6248 20.0000 20250704 17.0 4.0 P/2021 PE20 (ATLAS) MPEC 2023-E68 - CK21Q030 2022 01 26.0565 5.208913 0.930604 114.1463 307.9090 77.7158 20250704 8.0 4.0 C/2021 Q3 (ATLAS) MPEC 2023-FK0 - CK21Q040 2023 06 11.0370 7.565011 1.001614 147.0530 183.3298 71.5337 20250704 6.0 4.0 C/2021 Q4 (Fuls) MPEC 2025-A40 - PK21Q050 2027 08 17.0033 1.234035 0.624562 180.9579 239.7553 10.7382 20250704 15.0 4.0 P/2021 Q5 (ATLAS) MPEC 2022-C56 - CK21Q060 2024 03 25.2336 8.707744 1.002838 141.0647 133.5742 161.8260 20250704 6.0 4.0 C/2021 Q6 (PANSTARRS) MPEC 2024-UA9 - CK21Q45M 2022 08 13.6780 2.778247 0.993214 72.9232 354.5961 22.7983 20250704 11.0 4.0 C/2021 QM45 (PANSTARRS) MPEC 2023-FK0 - PK21R010 2021 12 8.5041 4.884597 0.408060 220.0353 143.1025 5.5335 20250704 11.0 4.0 P/2021 R1 (PANSTARRS) MPEC 2022-X67 - CK21R020 2021 12 28.4772 7.316486 0.999346 32.5533 16.3386 134.4820 20250704 7.5 4.0 C/2021 R2 (PANSTARRS) MPEC 2022-X67 - PK21R030 2028 09 17.5750 2.519301 0.331596 2.5866 304.1946 19.9420 20250704 16.0 4.0 P/2021 R3 (PANSTARRS) MPEC 2021-W31 - PK21R040 2021 10 13.3912 2.334057 0.585257 56.7782 321.2812 21.0114 20250704 16.0 4.0 P/2021 R4 (Wierzchos) MPEC 2021-W31 - PK21R050 2022 01 12.3702 3.330204 0.305927 167.6071 219.9623 7.8538 20250704 12.0 4.0 P/2021 R5 (Rankin) MPEC 2024-JU4 - PK21R060 2021 10 31.9129 2.559544 0.593021 220.8822 176.1615 34.8907 20250704 14.5 4.0 P/2021 R6 (Groeller) MPEC 2021-W31 - CK21R070 2021 04 17.3513 5.654716 0.994371 140.4006 170.2027 158.8754 20250704 10.5 4.0 C/2021 R7 (PANSTARRS) MPEC 2022-X67 - PK21R080 2027 01 5.7909 2.136721 0.292540 190.8186 167.0654 2.2027 20250704 18.5 4.0 P/2021 R8 (Sheppard) MPEC 2021-Y10 - CK21S010 2022 03 2.0151 6.125248 1.002903 148.3107 299.8557 52.0377 20250704 7.0 4.0 C/2021 S1 (ATLAS) MPEC 2023-J29 - CK21S030 2024 02 14.6701 1.319744 1.000004 6.8362 215.6070 58.5399 20250704 5.5 4.0 C/2021 S3 (PANSTARRS) MPEC 2025-MC0 - CK21S040 2024 01 3.8416 6.691901 0.957113 73.0460 5.4509 17.4797 20250704 6.5 4.0 C/2021 S4 (Tsuchinshan) MPC184409 - CK21T010 2021 10 14.8778 3.060315 0.998933 51.5822 56.8481 140.3518 20250704 12.5 4.0 C/2021 T1 (Lemmon) MPEC 2022-OB6 - CK21T020 2022 06 8.3358 1.244080 1.000536 263.5264 223.2067 117.5113 20250704 12.0 4.0 C/2021 T2 (Fuls) MPEC 2023-A50 - CK21T040 2023 07 31.5120 1.481465 0.999689 329.7695 257.8896 160.7784 20250704 7.5 4.0 C/2021 T4 (Lemmon) MPC184409 - PK21T81R 2022 04 3.6268 1.464781 0.833043 272.0088 220.1746 36.8139 20250704 15.6 4.0 P/2021 TR81 (Lemmon) MPC184409 - PK21U010 2021 09 30.7382 2.454061 0.712639 145.2383 246.7949 30.5513 20250704 14.5 4.0 P/2021 U1 (Wierzchos) MPEC 2022-ED3 - PK21U030 2021 10 24.8612 1.891208 0.549396 335.3262 75.0942 69.9614 20250704 15.5 4.0 P/2021 U3 (Attard-Maury) MPEC 2022-L66 - CK21U040 2021 12 22.5746 1.787222 0.960719 237.3225 241.8054 152.8822 20250704 17.0 4.0 C/2021 U4 (Leonard) MPEC 2021-W31 - CK21U050 2022 01 26.9976 2.359095 0.989400 321.4625 182.6754 39.0400 20250704 13.0 4.0 C/2021 U5 (Catalina) MPEC 2022-WQ9 - CK21V010 2022 04 30.6121 3.019281 0.995799 195.2172 207.6992 71.4349 20250704 13.0 4.0 C/2021 V1 (Rankin) MPEC 2022-CN4 - PK21V020 2023 01 21.9962 3.497406 0.615277 259.9068 232.2763 12.6927 20250704 10.0 4.0 P/2021 V2 (Fuls) MPEC 2024-JU4 - CK21X010 2023 05 27.2901 3.234628 1.000615 334.6179 10.6165 140.1073 20250704 7.0 4.0 C/2021 X1 (Maury-Attard) MPEC 2024-TD8 - CK21X020 2022 07 8.3851 2.998044 1.001534 193.3872 228.8427 137.1535 20250704 13.0 4.0 C/2021 X2 (Bok) MPEC 2024-E08 - CK21Y010 2023 04 30.9362 2.032478 1.001594 245.8496 244.7667 77.1869 20250704 7.0 4.0 C/2021 Y1 (ATLAS) MPEC 2024-GJ3 - CK22A010 2022 01 31.1418 1.256163 0.996625 201.2838 285.4928 116.5732 20250704 18.0 4.0 C/2022 A1 (Sarneczky) MPEC 2022-YN2 - CK22A020 2023 02 18.1847 1.735350 1.000065 88.3668 171.6052 108.1702 20250704 9.5 4.0 C/2022 A2 (PANSTARRS) MPEC 2024-P23 - CK22A030 2023 09 28.9640 3.704424 0.995876 234.8720 325.4572 88.3503 20250704 8.0 4.0 C/2022 A3 (Lemmon-ATLAS) MPEC 2024-UQ8 - PK22B010 2022 02 26.0285 1.894386 0.653633 148.9388 325.3811 10.9946 20250704 16.5 4.0 P/2022 B1 (Wierzchos) MPEC 2022-K19 - AK22B030 2022 01 16.7065 3.704409 0.994159 150.7201 286.1758 132.0507 20250704 16.5 2.0 A/2022 B3 MPEC 2022-YB4 - CK22B040 2022 01 30.4540 1.375920 0.996618 153.0252 340.5139 20.0576 20250704 21.0 4.0 C/2022 B4 (Bok) MPEC 2022-GA9 - PK22B09V 2029 12 6.0632 3.346234 0.233531 16.3089 337.3083 11.9237 20250704 9.5 4.0 P/2022 BV9 (Lemmon) MPEC 2023-J29 - PK22C010 2021 11 5.5203 3.985170 0.449139 9.4620 113.0992 4.7631 20250704 12.0 4.0 P/2022 C1 (PANSTARRS) MPEC 2023-J29 - PK22C020 2022 08 5.9112 3.366458 0.442000 89.1359 135.2627 9.9847 20250704 12.5 4.0 P/2022 C2 (PANSTARRS) MPEC 2023-VM5 - PK22C030 2022 06 30.2029 4.370405 0.545499 93.8037 139.0408 12.8249 20250704 11.5 4.0 P/2022 C3 (PANSTARRS) MPEC 2023-UR6 - PK22D010 2021 08 28.8099 3.347438 0.548001 88.6639 47.9473 44.0661 20250704 12.5 4.0 P/2022 D1 (PANSTARRS) MPEC 2022-K19 - CK22D020 2022 03 28.0566 1.552663 0.996108 177.8559 312.3593 22.6810 20250704 17.0 4.0 C/2022 D2 (Kowalski) MPEC 2022-K19 - PK22E010 2022 06 9.2835 2.944589 0.220573 114.8949 113.3413 19.0070 20250704 13.5 4.0 P/2022 E1 (Christensen) MPEC 2022-L66 - CK22E020 2024 09 14.1421 3.666511 1.000359 41.7494 125.3976 137.1410 20250704 5.0 4.0 C/2022 E2 (ATLAS) MPEC 2025-MC0 - CK22E030 2023 01 12.5097 1.114248 0.999994 145.8287 302.5074 109.1755 20250704 7.5 4.0 C/2022 E3 (ZTF) MPEC 2024-GJ3 - CK22F010 2022 08 5.9450 5.977908 0.999565 278.3546 350.6349 58.0023 20250704 7.0 4.0 C/2022 F1 (ATLAS) MPEC 2024-PC5 - CK22F020 2022 03 22.3396 1.589422 0.933119 200.5909 58.7818 97.3178 20250704 14.5 4.0 C/2022 F2 (NEOWISE) MPEC 2022-QD9 - CK22H010 2024 01 18.6502 7.689149 0.990981 246.2925 6.3259 49.8602 20250704 6.0 4.0 C/2022 H1 (PANSTARRS) MPEC 2025-MC0 - CK22J010 2022 02 19.3501 1.599969 0.966310 305.6089 280.8034 105.9596 20250704 14.9 4.0 C/2022 J1 (Maury-Attard) MPEC 2022-VC5 - CK22J020 2022 10 26.6965 1.828383 0.979687 133.1518 252.6860 149.1418 20250704 9.0 4.0 C/2022 J2 (Bok) MPEC 2023-M14 - CK22J05K 2023 04 28.9386 2.695676 0.938550 247.3848 59.6520 16.8246 20250704 11.0 4.0 C/2022 JK5 (PANSTARRS) MPEC 2024-YC7 - CK22K010 2021 12 16.5892 3.985805 1.000825 142.5435 136.3604 41.9745 20250704 11.0 4.0 C/2022 K1 (Leonard) MPEC 2022-ST7 - CK22L010 2022 09 27.7105 1.591077 0.996242 59.8023 300.0318 123.4388 20250704 15.8 4.0 C/2022 L1 (Catalina) MPEC 2023-CD7 - CK22L020 2024 03 12.1945 2.693409 1.000833 199.9256 39.2453 129.3124 20250704 6.5 4.0 C/2022 L2 (ATLAS) MPC184409 - PK22L030 2022 10 29.8422 2.424040 0.627436 10.4139 29.8241 21.5373 20250704 16.5 4.0 P/2022 L3 (ATLAS) MPEC 2024-DC6 - CK22L040 2021 12 9.0776 3.008548 0.989321 125.2487 66.0608 141.2435 20250704 14.0 4.0 C/2022 L4 (PANSTARRS) MPEC 2022-N37 - CK22N010 2022 09 9.7444 1.479131 0.959586 40.9945 301.8787 164.7267 20250704 16.9 4.0 C/2022 N1 (Attard-Maury) MPEC 2024-GJ3 - CK22N020 2025 07 31.8046 3.825367 1.003323 75.3989 319.7398 5.5029 20250704 6.0 4.0 C/2022 N2 (PANSTARRS) MPEC 2025-MC0 - CK22O010 2022 02 15.3679 7.434939 1.001276 268.9416 49.9109 71.0515 20250704 6.0 4.0 C/2022 O1 (ATLAS) MPEC 2024-A43 - PK22O020 2023 01 6.7180 1.759469 0.720948 48.6680 330.4913 9.4184 20250704 16.2 4.0 P/2022 O2 (PANSTARRS) MPEC 2023-HD1 - CK22P010 2022 11 28.7085 1.592236 0.913784 249.8733 205.0682 154.5866 20250704 13.0 4.0 C/2022 P1 (NEOWISE) MPEC 2023-N01 - PK22P020 2022 07 11.0347 1.985417 0.557990 137.7754 291.1733 12.4410 20250704 12.5 4.0 P/2022 P2 (ZTF) MPEC 2023-XP6 - CK22P030 2022 07 27.5278 2.566469 0.990270 0.2220 72.2192 59.5161 20250704 9.0 4.0 C/2022 P3 (ZTF) MPEC 2023-HD1 - CK22Q020 2023 01 31.7249 1.641602 0.949925 44.0300 352.9619 151.4579 20250704 13.0 4.0 C/2022 Q2 (ATLAS) MPEC 2023-R20 - CK22Q78E 2025 09 11.6886 5.475887 1.002731 0.5925 119.8879 36.6198 20250704 5.0 4.0 C/2022 QE78 (ATLAS) MPC184410 - PK22R010 2023 10 4.2045 3.565164 0.500915 221.7755 175.6611 7.3786 20250704 11.5 4.0 P/2022 R1 (PANSTARRS) MPEC 2024-M41 - CK22R020 2022 10 25.5632 0.630183 0.998567 78.3206 60.3914 52.8923 20250704 17.0 4.0 C/2022 R2 (ATLAS) MPEC 2022-Y15 - CK22R030 2023 03 5.9260 5.132158 1.001528 72.9347 8.2596 43.0714 20250704 9.0 4.0 C/2022 R3 (Leonard) MPC184410 - PK22R040 2022 07 9.8620 1.959824 0.489444 197.4956 176.6351 21.0089 20250704 16.5 4.0 P/2022 R4 (PANSTARRS) MPEC 2022-X67 - PK22R050 2027 10 12.0640 2.472150 0.194724 240.5381 115.0427 15.2923 20250704 16.0 4.0 P/2022 R5 (PANSTARRS) MPEC 2022-WQ9 - CK22R060 2025 08 26.2396 6.565529 1.005046 319.9189 150.7851 57.0196 20250704 5.0 4.0 C/2022 R6 (PANSTARRS) MPEC 2025-MC0 - PK22S010 2022 08 19.0045 3.155652 0.507605 262.8470 136.0898 34.5668 20250704 15.1 4.0 P/2022 S1 (PANSTARRS) MPEC 2023-HD1 - CK22S030 2023 01 21.6194 0.838803 1.000382 267.9876 157.2489 78.4810 20250704 17.0 4.0 C/2022 S3 (PANSTARRS) MPEC 2022-VC5 - CK22S040 2024 07 18.7856 2.761849 0.998034 268.5624 220.1786 101.2149 20250704 8.0 4.0 C/2022 S4 (Lemmon) MPEC 2025-MC0 - CK22S050 2022 11 27.7907 2.177875 0.893860 232.7987 214.8653 136.5106 20250704 16.3 4.0 C/2022 S5 (PANSTARRS) MPEC 2023-HD1 - CK22T010 2024 02 17.4425 3.444267 1.000378 324.2927 236.9153 22.5420 20250704 9.0 4.0 C/2022 T1 (Lemmon) MPEC 2024-O39 - CK22U010 2024 03 26.1000 4.202267 1.000241 78.6136 72.5280 128.1479 20250704 8.5 4.0 C/2022 U1 (Leonard) MPEC 2025-MC0 - CK22U020 2023 01 14.2728 1.329705 0.986477 148.0124 304.4029 48.2500 20250704 16.0 4.0 C/2022 U2 (ATLAS) MPEC 2023-VM5 - CK22U030 2024 07 28.6603 4.826863 1.000109 189.1335 272.7881 33.6617 20250704 7.5 4.0 C/2022 U3 (Bok) MPC182880 - CK22U040 2023 08 3.6443 2.897266 0.998997 88.9847 132.9163 52.0532 20250704 10.5 4.0 C/2022 U4 (Bok) MPEC 2023-W26 - CK22V020 2023 11 1.8509 2.064243 0.943667 168.9549 332.8539 98.9023 20250704 12.0 4.0 C/2022 V2 (Lemmon) MPEC 2024-H50 - PK22W010 2022 09 16.1266 3.372906 0.516466 17.9321 38.8300 13.4639 20250704 12.5 4.0 P/2022 W1 (Rankin) MPEC 2023-CD7 - CK22W020 2023 03 8.7352 3.124942 0.990880 123.3162 320.4358 63.5016 20250704 11.5 4.0 C/2022 W2 (ATLAS) MPEC 2024-EF7 - CK22W030 2023 06 22.8265 1.396841 0.994974 116.5117 132.3045 103.5819 20250704 13.0 4.0 C/2022 W3 (Leonard) MPEC 2024-C04 - CK22Y010 2022 11 27.6883 2.960617 0.765318 174.8843 285.8762 18.8559 20250704 9.0 4.0 C/2022 Y1 (Hogan) MPEC 2023-M14 - CK22Y020 2023 03 22.4395 2.542229 0.871155 105.4842 216.3761 165.8929 20250704 13.5 4.0 C/2022 Y2 (Lemmon) MPEC 2023-TM6 - CK23A010 2023 03 18.5831 1.836136 0.991701 159.2648 318.2648 94.7417 20250704 14.5 4.0 C/2023 A1 (Leonard) MPEC 2024-GJ3 - CK23A020 2023 01 20.3637 0.944940 0.997672 142.4921 94.5091 94.7061 20250704 13.5 4.0 C/2023 A2 (SWAN) MPEC 2023-J95 - CK23A030 2024 09 27.7435 0.391520 1.000125 308.5099 21.5757 139.1111 20250704 6.5 3.2 C/2023 A3 (Tsuchinshan-ATLAS) MPEC 2025-MC0 - PK23B010 2023 05 3.9468 6.140676 0.130968 81.7191 78.5602 14.5883 20250704 5.5 4.0 P/2023 B1 (PANSTARRS) MPEC 2024-F34 - CK23B020 2023 03 10.6140 1.740561 0.997084 317.3632 218.0888 40.7667 20250704 14.5 4.0 C/2023 B2 (ATLAS) MPEC 2023-XP6 - PK23B030 2020 09 5.8992 3.993706 0.122346 240.3829 153.9850 9.1565 20250704 10.5 4.0 P/2023 B3 (PANSTARRS) MPEC 2023-F81 - CK23C020 2024 11 16.7815 2.368525 0.999018 357.4459 301.0046 48.3218 20250704 7.0 4.0 C/2023 C2 (ATLAS) MPEC 2025-MC0 - CK23E010 2023 06 30.8505 1.027485 0.946621 105.9480 164.5198 38.2815 20250704 15.5 4.0 C/2023 E1 (ATLAS) MPEC 2024-D33 - CK23F010 2023 06 28.0793 1.710270 0.993014 216.7324 25.3070 131.6949 20250704 16.0 4.0 C/2023 F1 (PANSTARRS) MPEC 2023-N01 - CK23F030 2025 02 2.6219 5.190795 1.003373 265.5327 109.4658 145.9635 20250704 6.0 4.0 C/2023 F3 (ATLAS) MPEC 2025-MC0 - CK23H010 2024 11 28.6296 4.447566 0.994127 333.7505 292.6468 21.7829 20250704 8.5 4.0 C/2023 H1 (PANSTARRS) MPEC 2025-MC0 - CK23H020 2023 10 29.1587 0.895309 0.996384 150.6892 217.0742 113.7470 20250704 14.0 4.0 C/2023 H2 (Lemmon) MPEC 2024-GJ3 - CK23H030 2024 02 18.2418 5.231467 0.615815 193.2570 55.0918 2.4885 20250704 10.0 4.0 C/2023 H3 (PANSTARRS) MPEC 2025-MC0 - AK23H040 2023 08 8.6810 2.124150 0.985014 65.0171 230.8265 76.5682 20250704 18.0 2.0 A/2023 H4 MPEC 2023-SQ0 - CK23H050 2025 06 30.2873 4.312581 1.000459 60.1010 159.4783 97.8553 20250704 7.0 4.0 C/2023 H5 (Lemmon) MPEC 2025-MC0 - PK23J16N 2024 12 30.8345 2.299815 0.146984 353.2257 11.8706 3.7020 20250704 14.0 4.0 P/2023 JN16 (Lemmon) MPEC 2024-UA9 - CK23K010 2023 09 7.5638 2.038743 0.996702 337.4181 223.6981 137.9976 20250704 13.0 4.0 C/2023 K1 (ATLAS) MPEC 2024-GJ3 - PK23M010 2023 12 14.3144 2.826759 0.586793 79.7001 216.8599 12.2889 20250704 13.5 4.0 P/2023 M1 (PANSTARRS) MPEC 2023-N01 - PK23M020 2023 07 27.6464 3.516484 0.369977 243.5049 83.2510 19.7267 20250704 12.5 4.0 P/2023 M2 (PANSTARRS) MPEC 2024-TD8 - PK23M040 2022 04 13.5970 3.927093 0.278931 320.5126 296.2831 7.5919 20250704 7.5 4.0 P/2023 M4 (ATLAS) MPEC 2024-TP3 - CK23P010 2023 09 17.6162 0.224383 0.996021 116.2496 66.8303 132.4780 20250704 10.0 4.0 C/2023 P1 (Nishimura) MPEC 2024-MB8 - CK23Q010 2024 12 1.1250 2.575812 1.004959 84.4184 7.1238 36.6450 20250704 10.0 4.0 C/2023 Q1 (PANSTARRS) MPEC 2025-MC0 - CK23Q020 2024 06 23.9401 3.209063 0.990664 171.6897 92.6798 104.0619 20250704 11.5 4.0 C/2023 Q2 (PANSTARRS) MPEC 2024-N80 - CK23R010 2026 04 13.4748 3.569846 1.002235 144.2726 62.5627 149.3169 20250704 6.0 4.0 C/2023 R1 (PANSTARRS) MPEC 2025-MC0 - CK23R020 2024 08 12.1612 0.905076 1.000285 337.3140 188.8979 30.6895 20250704 10.5 4.0 C/2023 R2 (PANSTARRS) MPEC 2024-L77 - AK23R030 2023 12 18.1786 1.358744 0.998114 86.9456 347.3401 12.0804 20250704 20.0 2.0 A/2023 R3 MPEC 2023-UR6 - CK23R03N 2023 01 20.5247 5.180711 0.490550 130.6148 207.0639 10.3514 20250704 7.5 4.0 C/2023 RN3 (ATLAS) MPEC 2024-YC7 - CK23R61S 2028 12 1.2479 7.997890 0.327853 119.4134 347.0210 19.9448 20250704 6.8 4.0 C/2023 RS61 MPC184411 - PK23S010 2025 02 24.1785 2.619723 0.318462 180.3069 317.2904 9.1578 20250704 11.5 4.0 P/2023 S1 (PANSTARRS) MPEC 2025-MC0 - CK23S020 2023 10 15.3170 1.061662 0.993569 78.9549 229.4610 19.6554 20250704 15.0 4.0 C/2023 S2 (ATLAS) MPEC 2023-XP6 - CK23S030 2024 01 19.6494 0.829273 0.970824 281.5307 233.8227 140.4932 20250704 16.0 4.0 C/2023 S3 (Lemmon) MPEC 2024-P23 - PK23T010 2024 05 22.8586 2.817654 0.333217 202.8646 249.5763 6.6123 20250704 14.0 4.0 P/2023 T1 (PANSTARRS) MPEC 2024-BE0 - CK23T020 2023 12 22.7441 1.996315 0.991083 111.2166 317.5267 48.5907 20250704 14.5 4.0 C/2023 T2 (Borisov) MPEC 2024-GJ3 - CK23T030 2025 01 25.3560 3.548321 0.995876 302.8478 246.0019 27.2214 20250704 8.5 4.0 C/2023 T3 (Fuls) MPEC 2025-MC0 - CK23T22D 2024 09 16.3033 2.356669 0.951261 32.5416 5.5646 170.4898 20250704 12.5 4.0 C/2023 TD22 (Lemmon) MPEC 2025-MC0 - CK23U010 2024 10 12.9333 4.973112 0.998107 255.6457 305.8038 108.1460 20250704 8.0 4.0 C/2023 U1 (Fuls) MPEC 2025-MC0 - CK23V010 2025 07 13.0449 5.092583 1.000395 103.3153 15.0427 102.0137 20250704 8.5 4.0 C/2023 V1 (Lemmon) MPEC 2025-MC0 - PK23V020 2024 02 3.6618 3.104158 0.570036 330.5171 95.4744 9.8884 20250704 13.5 4.0 P/2023 V2 (PANSTARRS) MPC184411 - CK23V030 2023 08 3.5835 4.489587 0.650531 291.8380 91.2919 40.6995 20250704 11.5 4.0 C/2023 V3 (PANSTARRS) MPEC 2024-A43 - CK23V040 2024 05 30.3932 1.121906 1.001166 50.8702 66.3270 67.1252 20250704 12.0 4.0 C/2023 V4 (Camarasa-Duszanowicz) MPEC 2025-MC0 - CK23V050 2023 12 13.9085 0.846315 1.009427 56.9688 31.5150 73.5490 20250704 21.5 4.0 C/2023 V5 (Leonard) MPEC 2024-GJ3 - PK23V060 2022 12 1.3660 4.365112 0.175486 192.4431 189.6363 3.9726 20250704 11.5 4.0 P/2023 V6 (PANSTARRS) MPEC 2025-A40 - CK23X010 2023 10 17.9681 0.951114 0.993894 321.4685 136.9915 110.5886 20250704 13.5 3.2 C/2023 X1 (Leonard) MPEC 2024-GJ3 - CK23X020 2025 12 28.1995 5.088735 1.000073 64.7680 66.3029 76.9821 20250704 8.5 3.2 C/2023 X2 (Lemmon) MPEC 2025-MC0 - PK23X030 2024 04 22.1535 3.030764 0.286183 40.8695 62.0138 4.4833 20250704 15.5 4.0 P/2023 X3 (PANSTARRS) MPEC 2024-A43 - CK23X040 2024 05 25.0625 3.658450 0.631282 100.5921 28.7696 11.5934 20250704 12.0 4.0 C/2023 X4 (Hogan) MPC184411 - CK23X070 2025 05 15.2371 4.820348 1.002433 354.4027 119.1981 69.0941 20250704 9.0 4.0 C/2023 X7 (PANSTARRS) MPEC 2024-DA2 - PK23Y010 2023 11 29.9262 2.080083 0.445368 51.4791 78.8561 6.3839 20250704 17.0 4.0 P/2023 Y1 (Gibbs) MPEC 2024-JU4 - PK23Y020 2023 08 10.1120 2.277360 0.392271 16.9037 79.2290 6.9926 20250704 15.5 4.0 P/2023 Y2 (Gibbs) MPEC 2025-A40 - CK24A010 2025 06 13.6656 3.875289 1.002553 353.3035 112.1350 94.4697 20250704 7.0 4.0 C/2024 A1 (ATLAS) MPEC 2025-MC0 - CK24A020 2024 04 28.8033 1.879384 0.941753 295.4930 78.1650 119.1143 20250704 12.5 4.0 C/2024 A2 (ATLAS) MPC182881 - CK24B010 2024 10 7.7209 1.633809 1.001023 66.2176 79.1882 70.9030 20250704 13.0 4.0 C/2024 B1 (Lemmon) MPEC 2025-MC0 - CK24B020 2023 10 5.8262 4.078133 0.997856 130.3353 294.3861 99.8696 20250704 11.5 4.0 C/2024 B2 (Lemmon) MPEC 2025-A40 - CK24C010 2024 08 31.0676 4.412875 0.582998 94.4894 83.8096 14.2269 20250704 11.5 4.0 C/2024 C1 (PANSTARRS) MPEC 2025-MC0 - CK24C020 2025 03 11.2541 8.991384 0.445937 87.5747 66.4458 27.2844 20250704 6.0 4.0 C/2024 C2 (PANSTARRS) MPEC 2024-JU4 - CK24C030 2023 11 8.7619 6.713039 0.424669 159.6907 359.7058 22.4546 20250704 9.0 4.0 C/2024 C3 (PANSTARRS) MPC184412 - CK24C040 2024 01 30.1902 1.470494 0.982375 321.4982 220.6709 79.2830 20250704 14.5 4.0 C/2024 C4 (ATLAS) MPEC 2024-Q20 - CK24D010 2027 12 3.3970 6.693173 0.999291 125.7772 179.6614 132.4498 20250704 7.3 4.0 C/2024 D1 (Lemmon) MPEC 2025-MC0 - CK24E010 2026 01 20.7643 0.565989 1.000067 243.6328 108.0805 75.2391 20250704 7.0 4.0 C/2024 E1 (Wierzchos) MPEC 2025-MC0 - CK24E020 2023 10 25.1763 7.695087 0.850589 358.1382 135.6542 155.6499 20250704 8.0 4.0 C/2024 E2 (Bok) MPEC 2024-JU4 - PK24F010 2023 10 25.7817 1.859839 0.459985 229.5773 251.5413 7.0052 20250704 16.0 4.0 P/2024 F1 (PANSTARRS) MPEC 2024-JU4 - CK24F020 2024 07 29.0422 3.967819 0.601121 112.9006 138.9396 13.7429 20250704 11.0 4.0 C/2024 F2 (PANSTARRS) MPEC 2025-MC0 - PK24F09G 2024 05 20.4047 1.596489 0.509924 245.9339 253.0426 1.7312 20250704 14.0 4.0 P/2024 FG9 (Nanshan-Hahn) MPEC 2024-UA9 - CK24G010 2024 10 21.0726 3.930118 0.967836 128.2238 30.6053 95.3934 20250704 10.0 4.0 C/2024 G1 (Wierzchos) MPC184412 - CK24G020 2025 06 13.5384 5.348241 0.992697 328.7381 171.3969 122.1252 20250704 7.0 4.0 C/2024 G2 (ATLAS) MPEC 2025-MC0 - CK24G030 2025 01 13.4266 0.093553 1.000006 108.1277 220.3456 116.8475 20250704 9.0 4.0 C/2024 G3 (ATLAS) MPC184412 - CK24G040 2026 03 21.6128 4.900424 0.998456 131.4207 152.9814 33.0265 20250704 8.0 4.0 C/2024 G4 (PANSTARRS) MPEC 2025-MC0 - CK24G050 2024 09 7.0565 2.953047 0.994840 209.5801 316.3924 50.3869 20250704 13.0 4.0 C/2024 G5 (Leonard) MPEC 2024-JC6 - CK24G060 2026 02 20.7441 6.429787 1.002164 23.4393 250.9519 120.4554 20250704 5.5 4.0 C/2024 G6 (ATLAS) MPEC 2025-MC0 - CK24G070 2025 02 10.1037 6.027654 1.001913 289.6567 191.9632 131.5151 20250704 7.0 4.0 C/2024 G7 (ATLAS) MPC184412 - AK24G080 2024 06 15.5823 1.172469 0.991717 249.1571 11.2486 97.4139 20250704 20.0 2.0 A/2024 G8 MPEC 2024-Q05 - PK24J010 2023 11 11.3130 2.636629 0.307731 200.3655 321.9380 13.1592 20250704 14.5 4.0 P/2024 J1 (PANSTARRS) MPEC 2024-JU4 - CK24J020 2025 03 19.7848 1.810903 0.987699 143.1611 189.0592 79.2970 20250704 11.5 4.0 C/2024 J2 (Wierzchos) MPC182882 - CK24J030 2026 11 25.3330 3.865184 1.000726 74.0887 285.9612 75.6402 20250704 5.0 4.0 C/2024 J3 (ATLAS) MPEC 2025-MC0 - CK24J040 2025 04 26.0055 5.695121 0.999102 127.8587 19.3065 117.5295 20250704 8.0 4.0 C/2024 J4 (Lemmon) MPEC 2025-MC0 - PK24K010 2024 05 8.9354 3.455449 0.495175 351.9259 251.6891 1.7862 20250704 13.5 4.0 P/2024 K1 (PANSTARRS) MPEC 2024-LB4 - CK24L010 2025 04 23.1477 5.348103 0.533542 171.7950 45.1395 99.1652 20250704 10.0 4.0 C/2024 L1 (PANSTARRS) MPEC 2025-MC0 - CK24L020 2025 06 12.7885 8.326290 0.982376 345.6169 266.2859 139.4875 20250704 7.5 3.2 C/2024 L2 (PANSTARRS) MPEC 2024-P23 - CK24L030 2023 11 24.1478 6.857936 1.003832 59.0764 294.9953 111.5922 20250704 9.5 4.0 C/2024 L3 (PANSTARRS) MPEC 2024-RQ6 - CK24L050 2025 03 10.3956 3.432420 1.037115 290.5155 139.1774 166.5729 20250704 9.0 4.0 C/2024 L5 (ATLAS) MPEC 2025-MC0 - CK24M010 2024 11 19.9944 1.703227 0.942836 345.5840 76.2144 73.7095 20250704 12.0 4.0 C/2024 M1 (ATLAS) MPC184413 - CK24N010 2025 10 18.8662 4.398220 1.001168 91.2538 323.0214 88.7814 20250704 10.5 4.0 C/2024 N1 (PANSTARRS) MPEC 2025-MC0 - CK24N030 2025 04 11.4476 5.014579 1.001405 86.8863 82.6088 88.7289 20250704 8.0 4.0 C/2024 N3 (Sarneczky) MPEC 2025-MC0 - CK24N040 2025 01 10.2090 5.397813 1.004378 116.7081 339.6568 49.7747 20250704 7.5 4.0 C/2024 N4 (Sarneczky) MPEC 2025-MC0 - CK24O010 2023 01 28.5176 6.606783 1.000621 349.8875 303.3417 59.0792 20250704 8.5 4.0 C/2024 O1 (PANSTARRS) MPEC 2024-PC5 - PK24O020 2024 04 20.1507 3.697695 0.499084 310.7853 6.8056 28.9768 20250704 12.0 4.0 P/2024 O2 (PANSTARRS) MPEC 2024-UA9 - PK24O02C 2024 10 9.3143 0.592885 0.774180 258.5383 136.6166 7.6712 20250704 20.5 4.0 P/2024 OC2 (PANSTARRS) MPEC 2025-A40 - CK24P07N 2024 12 6.4342 1.524571 0.977341 74.2736 358.5842 101.2093 20250704 15.2 4.0 C/2024 PN7 (PANSTARRS) MPEC 2025-MC0 - PK24Q010 2024 06 14.6500 1.637859 0.534868 284.5326 23.1101 5.0117 20250704 17.0 4.0 P/2024 Q1 (PANSTARRS) MPEC 2024-UQ8 - CK24Q030 2025 03 5.2193 2.091560 1.001489 70.1277 337.2874 121.3780 20250704 15.0 4.0 C/2024 Q3 (PANSTARRS) MPEC 2025-MC0 - CK24Q040 2024 11 12.1859 5.419116 0.992006 133.0515 324.2723 3.3150 20250704 10.0 4.0 C/2024 Q4 (PANSTARRS) MPC182882 - PK24R010 2024 06 15.8715 1.751282 0.493126 230.6951 84.9830 12.7356 20250704 18.0 4.0 P/2024 R1 (PANSTARRS) MPEC 2024-TP3 - PK24R020 2024 10 1.7093 2.302955 0.268704 203.9302 193.0085 15.1157 20250704 15.5 4.0 P/2024 R2 (PANSTARRS) MPC182883 - PK24R030 2024 05 8.4426 2.345775 0.267288 309.3203 33.2378 14.7167 20250704 15.0 4.0 P/2024 R3 (PANSTARRS) MPEC 2024-YC7 - CK24R040 2027 10 26.6555 4.409159 1.002594 108.9929 345.9351 95.3627 20250704 6.5 4.0 C/2024 R4 (PANSTARRS) MPEC 2025-MC0 - CK24S010 2024 10 28.4785 0.007984 0.999908 69.5348 347.6063 142.0308 20250704 15.5 4.0 C/2024 S1 (ATLAS) MPC182883 - PK24S020 2024 09 16.2890 2.047610 0.593576 49.1659 8.3377 7.5258 20250704 15.0 4.0 P/2024 S2 (Rankin) MPEC 2025-A40 - PK24T010 2024 09 30.3866 2.287002 0.653432 164.8639 279.7108 17.6202 20250704 14.5 4.0 P/2024 T1 (Rankin) MPC182883 - PK24T020 2024 12 8.3276 1.972300 0.680413 343.8265 113.0614 12.9290 20250704 16.0 4.0 P/2024 T2 (Rankin) MPC184413 - CK24T030 2025 03 15.2477 3.716150 0.957210 336.8858 74.8336 53.4719 20250704 11.5 4.0 C/2024 T3 (PANSTARRS) MPC182883 - CK24T050 2027 05 6.1779 3.841459 1.002275 352.4375 100.6799 52.3868 20250704 5.5 4.0 C/2024 T5 (ATLAS) MPEC 2025-MC0 - CK24U010 2024 06 30.4371 4.836220 0.990032 188.0816 270.2639 128.7552 20250704 10.0 4.0 C/2024 U1 (PANSTARRS) MPC182883 - AK24U020 2026 01 14.4478 8.180816 1.003452 29.7740 56.0700 120.6714 20250704 12.1 2.0 A/2024 U2 MPC182883 - CK24V010 2025 04 4.1128 2.318471 0.990033 168.6684 328.1947 54.6259 20250704 14.8 4.0 C/2024 V1 (Borisov) MPEC 2025-MC0 - CK24V020 2024 11 3.8247 1.243082 0.968366 13.7239 102.2017 95.9719 20250704 19.0 4.0 C/2024 V2 (Sarneczky) MPEC 2024-YC7 - CK24W010 2025 03 19.1058 2.560730 0.942939 256.7394 310.7272 83.2005 20250704 15.0 4.0 C/2024 W1 (PANSTARRS) MPC182883 - AK24W020 2025 02 27.4162 3.720673 1.002574 168.0033 241.9381 116.6152 20250704 15.6 2.0 A/2024 W2 MPC182883 - CK24X010 2025 08 3.4799 3.816668 0.596739 124.3601 351.9961 6.4640 20250704 11.3 4.0 C/2024 X1 (Fazekas) MPC182884 - CK24X020 2025 07 7.8837 3.676298 0.927286 315.7822 122.5229 109.2212 20250704 9.6 4.0 C/2024 X2 (ATLAS) MPEC 2025-MC0 - PK24X030 2024 09 5.7835 2.614247 0.626188 352.9470 113.3647 2.9723 20250704 14.6 4.0 P/2024 X3 (PANSTARRS) MPEC 2025-MC0 - CK24X040 2025 09 1.9108 3.604754 0.641780 153.2910 258.9434 34.6689 20250704 12.6 4.0 C/2024 X4 (PANSTARRS) MPEC 2025-A40 - CK24Y010 2024 11 26.8817 0.822209 0.986815 238.1411 112.5424 64.7686 20250704 17.6 4.0 C/2024 Y1 (Masek) MPC182884 - AK25A010 2027 03 12.3570 5.341782 1.004226 68.0760 101.3305 33.4400 20250704 11.8 2.0 A/2025 A1 MPC182884 - PK25A020 2024 10 5.6454 3.446392 0.322091 278.0450 189.3191 20.7342 20250704 13.2 4.0 P/2025 A2 (PANSTARRS) MPC184414 - CK25A030 2026 03 15.0573 5.792284 0.431759 222.3086 322.4332 9.9766 20250704 9.0 4.0 C/2025 A3 (Tsuchinshan) MPC184414 - CK25A040 2025 01 13.1655 3.824237 0.653988 102.7978 69.9136 32.0254 20250704 12.4 4.0 C/2025 A4 (PANSTARRS) MPEC 2025-MC0 - CK25A060 2025 11 8.5393 0.529987 0.995712 132.9604 108.0968 143.6638 20250704 13.2 4.0 C/2025 A6 (Lemmon) MPC184414 - AK25A070 2025 03 28.1140 2.883453 0.999361 195.5695 348.8453 133.6505 20250704 14.0 2.0 A/2025 A7 MPC184414 - CK25B010 2025 06 26.7709 3.530889 1.000796 23.5263 102.8413 39.6804 20250704 12.0 4.0 C/2025 B1 (PANSTARRS) MPC182885 - CK25B020 2026 09 10.0158 8.244800 1.000116 78.7304 84.8733 91.7517 20250704 6.2 4.0 C/2025 B2 (Borisov) MPC184414 - PK25C010 2025 02 6.5736 2.746063 0.345489 186.8033 9.1025 7.5170 20250704 10.8 4.0 P/2025 C1 (ATLAS) MPEC 2025-MC0 - CK25D010 2028 05 20.1813 14.118679 1.002964 185.8961 312.8990 84.4633 20250704 1.2 4.0 C/2025 D1 (Groeller) MPEC 2025-MC0 - PK25D020 2028 11 5.3292 7.326666 0.178790 314.0521 256.7339 5.3344 20250704 8.2 4.0 P/2025 D2 (PANSTARRS) MPC182885 - PK25D030 2024 07 25.7577 2.965576 0.252445 294.4749 186.6360 9.6439 20250704 14.7 4.0 P/2025 D3 (PANSTARRS) MPEC 2025-MC0 - PK25D040 2025 02 14.2846 3.254936 0.634437 332.8888 233.1200 15.9404 20250704 13.2 4.0 P/2025 D4 (ATLAS) MPEC 2025-MC0 - CK25D050 2025 05 13.2919 2.012173 0.999397 211.4931 0.7378 73.3810 20250704 17.6 4.0 C/2025 D5 (PANSTARRS) MPC184415 - CK25D060 2024 12 11.3854 2.503939 0.998421 285.4050 151.4874 145.7902 20250704 13.2 4.0 C/2025 D6 (ATLAS) MPC184415 - CK25E010 2026 09 23.7429 3.998169 0.997239 274.4212 344.5967 69.0653 20250704 9.7 4.0 C/2025 E1 (PANSTARRS) MPC184415 - CK25F010 2025 04 20.4730 1.069953 0.996315 334.2289 122.7051 109.2370 20250704 18.0 4.0 C/2025 F1 (ATLAS) MPEC 2025-MC0 - CK25F020 2025 05 1.1613 0.333494 1.000101 153.8370 329.8408 90.3649 20250704 11.2 4.0 C/2025 F2 (SWAN) MPC184415 - CK25J010 2026 06 11.6719 3.582168 0.997316 166.5786 273.9822 95.4429 20250704 9.1 4.0 C/2025 J1 (Borisov) MPEC 2025-MC0 - CK25K010 2025 10 8.4448 0.334140 1.000204 271.0342 97.5572 147.8644 20250704 12.2 4.0 C/2025 K1 (ATLAS) MPEC 2025-MC0 - CK25K020 2025 10 25.2197 2.864107 0.889281 232.4536 113.8362 113.9939 20250704 13.7 4.0 C/2025 K2 (PANSTARRS) MPEC 2025-MC0 - CK25K030 2028 12 13.7710 3.468841 1.001671 188.5952 350.6201 104.9334 20250704 6.4 4.0 C/2025 K3 (PANSTARRS) MPEC 2025-L43 - CK25K040 2025 07 27.8793 2.536762 0.941660 326.7628 297.0703 38.5749 20250704 14.1 4.0 C/2025 K4 (Siverd) MPEC 2025-L55 - CK25L010 2026 01 12.7456 1.679467 1.001385 341.2587 208.1062 114.1371 20250704 11.4 4.0 C/2025 L1 (ATLAS) MPEC 2025-MC0 - CK25L020 2025 12 20.5925 2.833819 0.996459 232.6394 134.9896 86.5959 20250704 11.7 4.0 C/2025 L2 MPEC 2025-MC0 - CK25M010 2029 08 3.2258 10.829066 0.998192 230.4263 66.9586 64.9012 20250704 2.9 4.0 C/2025 M1 (PANSTARRS) MPEC 2025-MD2 - CK25M020 2027 11 14.5684 2.629391 1.000637 98.0974 305.6139 173.1646 20250704 7.0 3.2 C/2025 M2 (PANSTARRS) MPC xxxxx -0001P 2061 08 29.6127 0.583093 0.967360 112.5257 59.6157 162.2174 20250704 4.0 6.0 1P/Halley 98, 1083 -0002P 2027 02 10.2633 0.339087 0.847131 187.2794 334.0149 11.3444 20250704 11.5 6.0 2P/Encke MPEC 2024-TP3 -0003D a 2024 12 2.1233 0.826876 0.767119 192.1286 276.6829 7.2157 20250704 11.0 6.0 3D-A/Biela 76, 1135 -0003D b 2025 06 28.0738 0.821837 0.767863 192.2545 276.2012 7.8798 20250704 11.0 6.0 3D-B/Biela 76, 1135 -0004P 2029 03 8.7775 1.622758 0.576304 207.1437 192.9104 8.0028 20250704 8.0 6.0 4P/Faye MPEC 2023-FK0 -0005D 2023 04 17.3504 0.512048 0.837880 20.3030 94.9066 18.6309 20250704 10.5 6.0 5D/Brorsen 27, 116 -0006P 2028 04 1.6155 1.357332 0.611934 178.0499 138.9509 19.5000 20250704 7.5 16.0 6P/d'Arrest MPEC 2022-WD2 -0007P 2027 08 29.6587 1.189488 0.648884 172.5839 93.2820 22.5921 20250704 10.0 6.0 7P/Pons-Winnecke MPEC 2023-A50 -0008P 2021 08 28.6170 1.022959 0.820706 207.4761 270.1770 54.9843 20250704 8.0 8.0 8P/Tuttle MPEC 2022-HC2 -0009P 2028 02 6.0856 1.733944 0.472654 184.4588 67.3044 10.6503 20250704 5.5 10.0 9P/Tempel MPEC 2024-YC7 -0010P 2026 08 2.1482 1.417412 0.537383 195.4916 117.8004 12.0274 20250704 5.0 10.0 10P/Tempel MPEC 2025-MC0 -0011P 2026 11 9.8690 1.387322 0.577447 168.0505 238.8628 14.4327 20250704 17.0 4.0 11P/Tempel-Swift-LINEAR MPEC 2024-R10 -0012P 2024 04 21.1414 0.781140 0.954669 199.0084 255.8567 74.1892 20250704 5.0 6.0 12P/Pons-Brooks MPEC 2025-MC0 -0013P 2024 06 30.0791 1.175442 0.930484 64.4224 85.8467 44.6658 20250704 5.0 6.0 13P/Olbers MPEC 2025-MC0 -0014P 2026 09 19.0038 2.738333 0.356667 159.1950 202.0231 27.9180 20250704 5.5 12.0 14P/Wolf MPC184415 -0015P 2028 02 9.7721 0.996755 0.716102 347.8653 13.7488 6.7870 20250704 12.0 4.0 15P/Finlay MPEC 2022-ED3 -0016P 2028 04 20.9298 1.883762 0.485608 245.3744 138.8250 3.0099 20250704 7.5 10.0 16P/Brooks MPEC 2022-X67 -0017P 2028 01 31.7234 2.089144 0.426308 24.6141 326.6081 19.0067 20250704 10.0 6.0 17P/Holmes MPEC 2023-J29 -0018D 2024 08 29.146 1.59300 0.58952 238.206 158.450 17.661 20250704 9.0 4.0 18D/Perrine-Mrkos 19, 80 -0019P 2022 02 2.3429 1.307090 0.637770 352.0078 74.2152 29.3154 20250704 4.5 10.0 19P/Borrelly MPEC 2024-YC7 -0021P 2025 03 25.3587 1.008943 0.711060 172.9355 195.3290 32.0497 20250704 9.0 6.0 21P/Giacobini-Zinner MPEC 2024-YC7 -0022P 2028 07 11.6619 1.505436 0.558795 162.9877 120.1855 4.8273 20250704 3.0 10.4 22P/Kopff MPEC 2024-L77 -0023P 2059 06 1.1288 0.464402 0.972584 129.9929 311.1697 19.4692 20250704 10.0 6.0 23P/Brorsen-Metcalf MPC 14747 -0024P 2026 01 8.2987 1.183885 0.708202 58.3981 78.3676 11.5063 20250704 6.5 14.0 24P/Schaumasse MPC110085 -0025D 2025 05 11.4152 1.448318 0.550410 244.7987 279.9705 2.8087 20250704 12.5 6.0 25D/Neujmin 2 NK 378 -0026P 2023 12 25.3133 1.083401 0.640609 2.1230 211.5314 22.4373 20250704 12.0 16.0 26P/Grigg-Skjellerup MPEC 2024-TP3 -0027P 2039 05 25.7016 0.737566 0.919647 195.8486 250.7045 29.4338 20250704 12.0 8.0 27P/Crommelin MPC 78188 -0028P 2021 03 10.1866 1.586934 0.772665 347.4487 346.4119 14.2925 20250704 8.5 6.0 28P/Neujmin MPEC 2025-A40 -0029P 2019 05 1.5593 5.794829 0.043265 52.0703 312.4036 9.3558 20250704 4.0 4.0 29P/Schwassmann-Wachmann MPEC 2025-MC0 -0030P 2024 08 17.2340 1.813906 0.514403 9.5160 117.2326 8.0533 20250704 9.5 6.0 30P/Reinmuth MPEC 2025-MC0 -0031P 2028 03 18.8331 3.412459 0.193442 17.9158 114.1132 4.5497 20250704 5.0 8.0 31P/Schwassmann-Wachmann MPEC 2025-A40 -0032P 2024 04 20.6923 2.025191 0.555309 54.7087 54.5325 9.9199 20250704 6.5 8.0 32P/ComasSola MPEC 2025-MC0 -0033P 2024 11 10.8792 2.242477 0.451931 20.2550 66.2797 22.2940 20250704 10.0 12.0 33P/Daniel MPC184416 -0034D 2026 08 25.2085 1.213737 0.758104 218.0376 57.8608 10.5825 20250704 9.0 4.0 34D/Gale 9, 314 -0035P 2092 04 9.939 0.73378 0.97429 29.223 356.171 64.511 20250704 9.0 4.0 35P/Herschel-Rigollet 15, 452 -0036P 2028 11 5.0163 3.030952 0.268116 201.2047 181.8261 9.9458 20250704 8.5 6.0 36P/Whipple MPEC 2023-RF3 -0037P 2024 10 11.2356 1.617869 0.532651 330.0631 314.5483 8.9478 20250704 10.5 4.8 37P/Forbes MPC184416 -0038P 2018 11 13.8755 1.579702 0.859770 359.5933 77.8613 18.4142 20250704 3.5 12.0 38P/Stephan-Oterma MPEC 2024-YC7 -0039P 2023 09 11.0440 5.766972 0.171399 115.3411 289.1604 1.7265 20250704 7.0 6.0 39P/Oterma MPEC 2024-AF0 -0040P 2025 11 11.9178 1.823642 0.631500 52.0413 128.8982 11.6404 20250704 5.5 12.0 40P/Vaisala MPC184416 -0041P 2028 02 16.1075 1.050914 0.659652 62.2154 140.9721 9.2162 20250704 10.0 16.0 41P/Tuttle-Giacobini-Kresak MPEC 2023-SQ0 -0042P 2026 01 14.9621 2.029539 0.584069 147.1321 150.1594 3.9883 20250704 13.0 6.0 42P/Neujmin MPC184416 -0043P 2025 08 4.6711 2.442898 0.436224 223.7999 243.9921 9.3315 20250704 8.0 6.0 43P/Wolf-Harrington MPC184416 -0044P 2022 04 22.0371 2.114062 0.426738 57.9917 286.4215 5.8959 20250704 8.3 6.0 44P/Reinmuth MPEC 2024-F34 -0045P 2027 08 31.5046 0.557541 0.817607 327.9503 87.6864 4.3240 20250704 13.5 8.0 45P/Honda-Mrkos-Pajdusakova MPEC 2022-O01 -0046P 2024 05 19.0962 1.055276 0.658716 356.3432 82.1619 11.7497 20250704 14.0 6.0 46P/Wirtanen MPEC 2024-F91 -0047P 2025 10 27.9811 2.807471 0.318177 357.9119 356.8821 13.0386 20250704 1.0 11.2 47P/Ashbrook-Jackson MPEC 2025-MC0 -0048P 2025 03 2.6435 2.006598 0.426542 216.7752 110.0639 12.2017 20250704 10.0 6.0 48P/Johnson MPEC 2025-MC0 -0049P 2025 04 10.6041 1.431324 0.599002 332.9254 118.7912 19.0598 20250704 11.3 4.4 49P/Arend-Rigaux MPEC 2025-MC0 -0050P 2024 05 12.6209 1.921910 0.529687 49.3107 355.1445 19.1008 20250704 9.5 6.0 50P/Arend MPC184417 -0051P 2022 09 30.6419 1.694207 0.542770 269.2322 83.6587 5.4264 20250704 10.0 8.0 51P/Harrington MPEC 2023-J29 -0051P a 2022 10 3.2225 1.694056 0.542963 83.6420 269.2290 5.4262 20250704 10.0 8.0 51P-A/Harrington NK 3014 -0051P d 2022 10 1.0654 1.693886 0.542900 269.2503 83.6470 5.4268 20250704 16.0 8.0 51P-D/Harrington MPEC 2023-J29 -0052P 2021 10 6.2948 1.772256 0.541111 139.6177 336.7529 10.2381 20250704 13.5 6.0 52P/Harrington-Abell MPEC 2023-XP6 -0053P 2028 12 26.1217 2.449547 0.549674 134.3371 148.8518 6.6026 20250704 7.7 4.8 53P/VanBiesbroeck MPEC 2023-TM6 -0054P 2024 09 4.2008 2.171971 0.427174 2.1130 358.7330 6.0619 20250704 10.0 6.0 54P/deVico-Swift-NEAT MPEC 2024-YC7 -0055P 2031 05 22.5950 0.974361 0.905740 172.4948 235.4110 162.4831 20250704 9.0 4.0 55P/Tempel-Tuttle MPC 31070 -0056P 2027 12 19.4764 2.489375 0.508338 44.2215 345.8871 8.1549 20250704 8.5 6.0 56P/Slaughter-Burnham MPEC 2023-TM6 -0057P 2028 03 4.6807 1.715751 0.501352 115.0613 188.7375 2.8533 20250704 12.5 6.0 57P/duToit-Neujmin-Delporte MPEC 2024-DC6 -0058P 2028 09 4.3250 1.384315 0.661640 200.5828 159.0392 13.0873 20250704 15.5 6.0 58P/Jackson-Neujmin MPEC 2024-A43 -0059P 2028 03 15.4677 2.342397 0.477033 127.6713 312.7283 9.3560 20250704 7.0 6.0 59P/Kearns-Kwee MPEC 2023-A50 -0060P 2025 07 20.6098 1.645705 0.533803 216.9139 267.3962 3.5799 20250704 11.5 6.0 60P/Tsuchinshan MPC182887 -0061P 2022 10 23.3883 2.129296 0.423050 221.7095 162.9610 5.9968 20250704 6.0 10.0 61P/Shajn-Schaldach MPEC 2024-JU4 -0062P 2023 12 25.2064 1.265128 0.624715 47.3323 68.6654 4.7369 20250704 8.0 10.0 62P/Tsuchinshan MPC182887 -0063P 2026 07 6.2592 1.973619 0.650811 168.7919 357.7613 19.6188 20250704 10.5 6.0 63P/Wild MPC 84320 -0064P 2028 03 31.0423 1.387221 0.688421 97.3363 299.7713 8.9540 20250704 9.5 12.0 64P/Swift-Gehrels MPEC 2024-A43 -0065P 2025 06 16.4691 2.926255 0.248137 213.6734 61.9753 9.1753 20250704 5.0 6.0 65P/Gunn MPEC 2025-MC0 -0066P 2018 05 12.5516 1.305387 0.784960 257.3817 21.8386 18.6452 20250704 15.0 4.0 66P/duToit MPEC 2021-F20 -0067P 2028 04 9.1123 1.211109 0.649829 22.2127 36.3137 3.8683 20250704 11.0 4.0 67P/Churyumov-Gerasimenko MPEC 2024-C04 -0068P 2030 11 27.2642 1.807969 0.635756 153.2203 175.0920 11.0992 20250704 12.6 4.0 68P/Klemola MPEC 2023-HD1 -0069P 2026 11 12.3530 2.271174 0.414694 343.5001 104.8080 22.0613 20250704 9.5 12.0 69P/Taylor MPEC 2024-C04 -0070P 2028 11 20.8520 2.003782 0.454810 1.7940 119.2353 6.6031 20250704 11.0 6.0 70P/Kojima MPEC 2023-VM5 -0071P 2023 01 21.3011 1.630056 0.486708 210.4411 59.2203 9.2898 20250704 9.8 6.0 71P/Clark MPEC 2024-YC7 -0072P 2023 06 15.5655 0.782586 0.818325 346.7420 26.7216 10.9436 20250704 17.5 10.0 72P/Denning-Fujikawa MPEC 2023-VM5 -0073P 2027 12 13.0154 0.858059 0.716923 208.6546 58.7496 7.1304 20250704 11.5 6.0 73P/Schwassmann-Wachmann MPEC 2023-RF3 -0073P b 2028 01 22.3258 0.934148 0.696050 75.7146 192.6193 10.6596 20250704 9.0 4.0 73P-B/Schwassmann-Wachmann B NK 1613 -0073P c 2028 01 16.9602 0.934218 0.695883 75.5791 192.7911 10.6718 20250704 9.0 4.0 73P-C/Schwassmann-Wachmann NK 2710 -0073P e 2028 02 3.8299 0.934480 0.696344 75.9874 192.3134 10.6282 20250704 9.0 4.0 73P-E/Schwassmann-Wachmann NK 934 -0073P g 2006 06 8.096 0.93920 0.69330 198.772 69.909 11.388 9.0 4.0 73P-G/Schwassmann-Wachmann MPC 56796 -0073P h 2006 06 8.281 0.93918 0.69330 198.778 69.903 11.389 9.0 4.0 73P-H/Schwassmann-Wachmann MPC 56796 -0073P j 2006 06 8.141 0.93966 0.69330 198.673 69.983 11.386 9.0 4.0 73P-J/Schwassmann-Wachmann MPC 56796 -0073P k 2006 06 8.224 0.93903 0.69330 198.809 69.881 11.390 9.0 4.0 73P-K/Schwassmann-Wachmann MPC 56797 -0073P l 2006 06 8.340 0.93914 0.69330 198.772 69.911 11.388 9.0 4.0 73P-L/Schwassmann-Wachmann MPC 56797 -0073P m 2006 06 8.262 0.93912 0.69330 198.787 69.895 11.389 9.0 4.0 73P-M/Schwassmann-Wachmann MPC 56797 -0073P n 2006 06 8.261 0.93920 0.69330 198.754 69.909 11.389 9.0 4.0 73P-N/Schwassmann-Wachmann MPC 56797 -0073P p 2006 06 7.872 0.93917 0.69330 198.783 69.900 11.390 9.0 4.0 73P-P/Schwassmann-Wachmann MPC 56797 -0073P q 2006 06 7.725 0.93941 0.69330 198.717 69.944 11.387 9.0 4.0 73P-Q/Schwassmann-Wachmann MPC 56797 -0073P r 2006 06 8.185 0.93918 0.69330 198.776 69.904 11.388 9.0 4.0 73P-R/Schwassmann-Wachmann MPC 56797 -0073P s 2006 06 8.689 0.98977 0.69330 188.229 77.364 11.127 9.0 4.0 73P-S/Schwassmann-Wachmann MPC 56797 -0073P t 2027 12 11.1414 0.857662 0.716939 208.5764 58.8450 7.1722 20250704 9.0 4.0 73P-T/Schwassmann-Wachmann MPEC 2023-J29 -0073P u 2006 06 9.016 0.93962 0.69330 198.659 69.994 11.384 9.0 4.0 73P-U/Schwassmann-Wachmann MPC 56797 -0073P v 2006 06 8.477 0.91217 0.69330 204.943 65.236 11.651 9.0 4.0 73P-V/Schwassmann-Wachmann MPC 56797 -0073P w 2006 06 8.500 0.93906 0.69330 198.803 69.884 11.390 9.0 4.0 73P-W/Schwassmann-Wachmann MPC 56797 -0073P x 2006 06 8.566 0.93913 0.69330 198.778 69.900 11.388 9.0 4.0 73P-X/Schwassmann-Wachmann MPC 56798 -0073P y 2006 06 8.770 0.93911 0.69330 198.785 69.879 11.391 9.0 4.0 73P-Y/Schwassmann-Wachmann MPC 56798 -0073P z 2006 06 8.309 0.94204 0.69330 198.017 70.493 11.349 9.0 4.0 73P-Z/Schwassmann-Wachmann MPC 56798 -0073P aa 2006 06 9.086 0.93905 0.69330 198.804 69.883 11.390 9.0 4.0 73P-AA/Schwassmann-Wachmann MPC 56798 -0073P ab 2006 06 8.697 0.93906 0.69330 198.792 69.888 11.390 9.0 4.0 73P-AB/Schwassmann-Wachmann MPC 56798 -0073P ac 2006 06 8.693 0.93918 0.69330 198.766 69.914 11.387 9.0 4.0 73P-AC/Schwassmann-Wachmann MPC 56798 -0073P ad 2006 06 8.694 0.94167 0.69330 198.119 70.416 11.355 9.0 4.0 73P-AD/Schwassmann-Wachmann MPC 56798 -0073P ae 2006 06 8.352 0.93910 0.69330 198.790 69.891 11.390 9.0 4.0 73P-AE/Schwassmann-Wachmann MPC 56798 -0073P af 2006 06 6.841 0.94144 0.69330 198.217 70.302 11.356 9.0 4.0 73P-AF/Schwassmann-Wachmann MPC 56798 -0073P ag 2006 06 9.016 0.93921 0.69330 198.724 69.932 11.386 9.0 4.0 73P-AG/Schwassmann-Wachmann MPC 56798 -0073P ah 2006 06 8.628 0.94293 0.69330 197.755 70.695 11.331 9.0 4.0 73P-AH/Schwassmann-Wachmann MPC 56798 -0073P ai 2006 06 8.737 0.93912 0.69330 198.806 69.885 11.392 9.0 4.0 73P-AI/Schwassmann-Wachmann MPC 56798 -0073P aj 2006 06 8.740 0.93930 0.69330 198.663 70.041 11.385 9.0 4.0 73P-AJ/Schwassmann-Wachmann MPC 56799 -0073P ak 2006 06 8.395 0.93924 0.69330 198.822 69.784 11.389 9.0 4.0 73P-AK/Schwassmann-Wachmann MPC 56799 -0073P al 2006 06 8.456 0.93892 0.69330 198.857 69.843 11.395 9.0 4.0 73P-AL/Schwassmann-Wachmann MPC 56799 -0073P am 2006 06 8.266 0.93912 0.69330 198.815 69.876 11.394 9.0 4.0 73P-AM/Schwassmann-Wachmann MPC 56799 -0073P an 2006 06 8.328 0.93906 0.69330 198.820 69.870 11.393 9.0 4.0 73P-AN/Schwassmann-Wachmann MPC 56799 -0073P ao 2006 06 7.808 0.94408 0.69330 197.007 71.286 11.210 9.0 4.0 73P-AO/Schwassmann-Wachmann MPC 56799 -0073P ap 2006 06 6.685 0.93918 0.69330 198.794 69.895 11.393 9.0 4.0 73P-AP/Schwassmann-Wachmann MPC 56799 -0073P aq 2006 06 7.919 0.93920 0.69330 198.770 69.911 11.387 9.0 4.0 73P-AQ/Schwassmann-Wachmann MPC 56799 -0073P ar 2006 06 6.833 0.93937 0.69330 198.722 69.946 11.385 9.0 4.0 73P-AR/Schwassmann-Wachmann MPC 56799 -0073P as 2006 06 6.335 0.93922 0.69330 198.773 69.906 11.392 9.0 4.0 73P-AS/Schwassmann-Wachmann MPC 56799 -0073P at 2006 06 6.228 0.93925 0.69330 198.778 69.901 11.391 9.0 4.0 73P-AT/Schwassmann-Wachmann MPC 56799 -0073P au 2006 06 8.093 0.93929 0.69330 198.744 69.928 11.385 9.0 4.0 73P-AU/Schwassmann-Wachmann MPC 56799 -0073P av 2006 06 6.490 0.93930 0.69330 198.751 69.945 11.388 9.0 4.0 73P-AV/Schwassmann-Wachmann MPC 56800 -0073P aw 2006 06 7.766 0.93947 0.69330 198.673 69.982 11.377 9.0 4.0 73P-AW/Schwassmann-Wachmann MPC 56800 -0073P ax 2006 06 9.533 0.93912 0.69330 198.757 69.915 11.388 9.0 4.0 73P-AX/Schwassmann-Wachmann MPC 56800 -0073P ay 2006 06 8.760 0.93918 0.69330 198.750 69.923 11.385 9.0 4.0 73P-AY/Schwassmann-Wachmann MPC 56800 -0073P az 2006 06 6.515 0.93962 0.69330 198.644 70.002 11.371 9.0 4.0 73P-AZ/Schwassmann-Wachmann MPC 56800 -0073P ba 2006 06 6.436 0.93976 0.69330 198.588 70.042 11.364 9.0 4.0 73P-BA/Schwassmann-Wachmann MPC 56800 -0073P bb 2006 06 7.087 0.93912 0.69330 198.807 69.882 11.395 9.0 4.0 73P-BB/Schwassmann-Wachmann MPC 56800 -0073P bc 2006 06 6.670 0.93922 0.69330 198.778 69.901 11.391 9.0 4.0 73P-BC/Schwassmann-Wachmann MPC 56800 -0073P bd 2006 06 6.417 0.93998 0.69330 198.503 70.085 11.352 9.0 4.0 73P-BD/Schwassmann-Wachmann MPC 56800 -0073P be 2006 06 6.863 0.93902 0.69330 198.861 69.841 11.405 9.0 4.0 73P-BE/Schwassmann-Wachmann MPC 56800 -0073P bf 2006 06 6.992 0.93918 0.69330 198.752 69.908 11.390 9.0 4.0 73P-BF/Schwassmann-Wachmann MPC 56800 -0073P bg 2006 06 8.741 0.93915 0.69330 198.750 69.925 11.384 9.0 4.0 73P-BG/Schwassmann-Wachmann MPC 56800 -0073P bh 2006 06 8.568 0.93874 0.69330 198.947 69.752 11.410 9.0 4.0 73P-BH/Schwassmann-Wachmann MPC 56801 -0073P bi 2006 06 8.639 0.93905 0.69330 198.877 69.819 11.404 9.0 4.0 73P-BI/Schwassmann-Wachmann MPC 56801 -0073P bj 2006 06 8.669 0.93914 0.69330 198.776 69.905 11.389 9.0 4.0 73P-BJ/Schwassmann-Wachmann MPC 56801 -0073P bk 2006 06 8.884 0.93931 0.69330 198.698 69.970 11.379 9.0 4.0 73P-BK/Schwassmann-Wachmann MPC 56801 -0073P bl 2006 06 8.885 0.93923 0.69330 198.739 69.930 11.385 9.0 4.0 73P-BL/Schwassmann-Wachmann MPC 56801 -0073P bm 2006 06 8.938 0.93962 0.69330 198.546 70.086 11.364 9.0 4.0 73P-BM/Schwassmann-Wachmann MPC 56801 -0073P bn 2006 06 8.203 0.93905 0.69330 198.815 69.871 11.398 9.0 4.0 73P-BN/Schwassmann-Wachmann MPC 56801 -0073P bo 2006 06 8.259 0.93913 0.69330 198.765 69.903 11.390 9.0 4.0 73P-BO/Schwassmann-Wachmann MPC 56801 -0073P bp 2006 06 8.302 0.93910 0.69330 198.807 69.881 11.395 9.0 4.0 73P-BP/Schwassmann-Wachmann MPC 56801 -0073P bq 2006 06 8.297 0.93900 0.69330 198.862 69.836 11.404 9.0 4.0 73P-BQ/Schwassmann-Wachmann MPC 56801 -0073P br 2006 06 6.154 0.93921 0.69330 198.774 69.910 11.389 9.0 4.0 73P-BR/Schwassmann-Wachmann MPC 56957 -0073P bs 2006 06 5.831 0.93918 0.69330 198.814 69.885 11.399 9.0 4.0 73P-BS/Schwassmann-Wachmann MPC 56957 -0073P bt 2028 01 20.0437 0.934228 0.696055 75.6345 192.7151 10.6656 20250704 11.5 6.0 73P-BT/Schwassmann-Wachmann MPC106348 -0073P bu 2027 07 2.8937 0.925956 0.676113 73.3795 196.9135 10.8759 20250704 19.0 4.0 73P-BU/Schwassmann-Wachmann MPEC 2022-P18 -0073P bv 2028 01 17.6504 0.872225 0.717211 205.4021 61.0920 7.4427 20250704 19.0 4.0 73P-BV/Schwassmann-Wachmann MPEC 2022-X67 -0073P bw 2022 08 23.7022 0.966786 0.786520 71.6148 193.0940 10.2021 20250704 18.2 4.0 73P-BW/Schwassmann-Wachmann MPEC 2022-R15 -0073P bx 2028 01 3.1157 0.867633 0.716844 206.9266 59.7771 7.2050 20250704 17.5 4.0 73P-BX/Schwassmann-Wachmann MPEC 2023-A50 -0073P by 2027 11 23.1100 0.931091 0.691088 75.2178 193.4173 10.7319 20250704 17.4 4.0 73P-BY/Schwassmann-Wachmann MPEC 2022-R15 -0074P 2026 06 26.6134 4.827587 0.044013 66.2196 52.9044 6.1646 20250704 5.0 6.0 74P/Smirnova-Chernykh MPC184417 -0075D 2027 11 2.4630 1.770001 0.499522 175.5892 269.5528 5.9270 20250704 9.5 6.0 75D/Kohoutek CCO 7 -0076P 2026 04 13.5563 1.596819 0.539456 0.0066 84.1109 30.4884 20250704 8.0 12.0 76P/West-Kohoutek-Ikemura MPEC 2022-K19 -0077P 2023 04 2.8231 2.346711 0.351801 196.6172 14.7496 24.3254 20250704 7.0 8.0 77P/Longmore MPEC 2024-UA9 -0078P 2026 06 25.0315 2.004745 0.463061 192.7588 210.5032 6.2571 20250704 5.5 8.0 78P/Gehrels MPEC 2025-MC0 -0079P 2023 09 30.3319 1.120107 0.619339 281.7545 280.5057 3.1488 20250704 16.0 4.0 79P/duToit-Hartley MPEC 2024-PC5 -0080P 2022 12 8.1731 1.617887 0.597704 339.2723 259.7723 29.9270 20250704 9.0 8.0 80P/Peters-Hartley MPEC 2024-Q20 -0081P 2022 12 15.8130 1.595794 0.537654 41.5497 136.0993 3.2382 20250704 7.0 6.0 81P/Wild MPEC 2024-RQ6 -0082P 2026 11 15.8658 3.624355 0.122885 226.4670 239.2149 1.1294 20250704 15.0 4.0 82P/Gehrels MPC133426 -0083D 2028 12 2.6306 2.146634 0.441455 334.3762 226.2961 17.8312 20250704 9.0 4.0 83D/Russell NK 932 -0084P 2027 02 12.6054 1.719285 0.515714 281.6827 108.1417 7.5528 20250704 9.5 8.0 84P/Giclas MPEC 2020-FB5 -0085D 2020 07 30.3445 1.131083 0.775864 333.0902 65.2975 4.1728 20250704 6.5 8.0 85D/Boethin unp -0086P 2022 02 1.4616 2.325639 0.362419 181.0594 72.0965 15.5021 20250704 11.0 6.0 86P/Wild MPEC 2022-YB4 -0087P 2029 04 1.8369 3.419602 0.216166 51.8743 184.8548 2.6670 20250704 7.2 10.0 87P/Bus MPEC 2020-SI8 -0088P 2026 03 18.7876 1.357670 0.563237 235.8810 56.6687 4.3820 20250704 11.0 6.0 88P/Howell MPEC 2025-MC0 -0089P 2024 03 26.6079 2.222633 0.407457 250.4307 41.3448 12.0710 20250704 11.5 6.0 89P/Russell MPC182887 -0090P 2032 05 17.1128 2.962965 0.510599 29.1902 13.1850 9.6390 20250704 8.5 6.0 90P/Gehrels MPEC 2022-K19 -0091P 2028 10 23.9571 3.079395 0.256367 357.2714 242.3850 16.1618 20250704 7.5 6.0 91P/Russell MPEC 2023-VM5 -0092P 2027 07 15.4050 1.816913 0.660037 163.7793 181.3623 19.4788 20250704 12.0 6.0 92P/Sanguin MPEC 2014-J58 -0093P 2026 05 2.9143 1.688585 0.613954 75.0247 339.5507 12.2094 20250704 9.5 6.0 93P/Lovas MPEC 2025-MC0 -0094P 2023 05 21.1923 2.225312 0.366008 92.3746 70.8473 6.1875 20250704 9.0 6.0 94P/Russell MPEC 2024-R10 -0095P 2046 08 13.2434 8.514205 0.378406 339.3543 209.1924 6.9286 20250704 6.5 2.0 95P/Chiron MPC 75717 -0096P 2023 01 31.3395 0.116069 0.961707 14.7371 93.9629 57.5868 20250704 13.0 4.8 96P/Machholz MPC182887 -0096P b 2023 01 31.1925 0.115937 0.961737 94.0190 14.5836 57.5039 20250704 13.0 4.8 96P-B/Machholz MPC106348 -0096P c 2012 07 14.6812 0.123794 0.958898 15.5380 94.3495 58.5311 9.0 4.0 96P-C/Machholz MPC103849 -0097P 2022 02 15.9639 2.576115 0.459932 230.1996 184.0736 17.9378 20250704 5.5 6.0 97P/Metcalf-Brewington MPEC 2024-GJ3 -0098P 2028 05 13.1408 1.636012 0.567209 157.7360 114.5010 10.6572 20250704 9.0 8.0 98P/Takamizawa MPEC 2021-W31 -0099P 2022 04 9.0245 4.699760 0.228764 174.5343 28.0642 4.3391 20250704 4.5 6.0 99P/Kowal MPEC 2024-R10 -0100P 2022 08 10.1292 2.019270 0.411350 181.9231 37.6857 25.5673 20250704 9.0 8.0 100P/Hartley MPEC 2023-OA6 -0101P 2020 01 12.9860 2.352736 0.595580 277.9848 116.1229 5.0485 20250704 10.0 4.8 101P/Chernykh MPEC 2024-R10 -0101P b 2020 01 30.7551 2.357792 0.595791 115.6047 278.5064 5.0502 20250704 9.0 4.0 101P-B/Chernykh MPC105241 -0102P 2028 07 10.7581 2.078281 0.455980 20.6748 339.3953 25.8538 20250704 6.5 8.0 102P/Shoemaker MPEC 2022-C56 -0103P 2023 10 12.4193 1.065310 0.693496 181.3280 219.7570 13.6077 20250704 8.5 8.0 103P/Hartley MPC184417 -0104P 2027 10 12.8004 1.072016 0.665899 227.3049 207.1827 5.7009 20250704 16.0 4.0 104P/Kowal MPEC 2023-G31 -0105P 2025 01 22.7495 2.052069 0.409152 46.3308 192.3932 9.1672 20250704 11.5 6.0 105P/SingerBrewster MPEC 2025-MC0 -0106P 2028 12 12.0085 1.531754 0.593519 353.7977 48.8660 19.5333 20250704 14.0 4.8 106P/Schuster MPEC 2024-R10 -0107P 2026 11 25.5917 0.969138 0.630953 95.5171 266.7271 2.7986 20250704 9.0 4.0 107P/Wilson-Harrington MPEC 2015-M77 -0108P 2028 12 8.3466 1.663488 0.555675 354.5328 50.3014 11.4322 20250704 8.0 12.0 108P/Ciffreo MPEC 2022-P82 -0109P 1992 12 20.6114 0.972309 0.962893 153.2801 139.7158 113.0987 20250704 4.0 6.0 109P/Swift-Tuttle 105, 420 -0110P 2028 08 22.2438 2.453253 0.319223 167.5620 287.4819 11.7115 20250704 1.0 12.0 110P/Hartley MPEC 2023-KD6 -0111P 2021 06 19.8815 3.707918 0.107170 1.4386 89.8101 4.2262 20250704 5.0 8.0 111P/Helin-Roman-Crockett MPC 75718 -0112P 2026 09 21.8038 1.441242 0.590835 21.5527 31.8117 24.2023 20250704 14.0 6.0 112P/Urata-Niijima MPEC 2021-S45 -0113P 2022 06 1.8063 2.145009 0.419659 115.7391 306.6203 5.2876 20250704 13.5 4.0 113P/Spitaler MPEC 2024-JU4 -0114P 2026 09 14.9536 1.571204 0.556142 172.8123 271.0264 18.3039 20250704 11.5 6.0 114P/Wiseman-Skiff MPEC 2023-A50 -0115P 2029 05 24.6434 2.058989 0.517914 120.9160 175.9789 11.6818 20250704 10.5 6.0 115P/Maury MPEC 2023-J29 -0116P 2022 07 16.7535 2.193704 0.370705 173.1571 20.9595 3.6046 20250704 2.5 10.0 116P/Wild MPEC 2024-RQ6 -0117P 2022 07 12.2057 3.078059 0.252522 224.7270 58.8184 8.6778 20250704 2.5 8.0 117P/Helin-Roman-Alu MPC182887 -0118P 2022 11 24.7596 1.829186 0.453808 314.9526 142.0539 10.0917 20250704 12.0 4.0 118P/Shoemaker-Levy MPEC 2024-MB8 -0119P 2022 08 12.4240 2.330947 0.388099 322.2722 104.5424 7.3929 20250704 3.5 8.0 119P/Parker-Hartley MPEC 2024-R10 -0120P 2029 04 4.7414 2.484643 0.374140 36.7855 358.7043 8.4813 20250704 12.0 4.0 120P/Mueller MPEC 2022-CN4 -0121P 2023 06 30.7425 3.732503 0.186711 11.9715 94.1049 20.1621 20250704 6.5 8.0 121P/Shoemaker-Holt MPEC 2025-MC0 -0122P 1995 10 2.3452 0.659421 0.962604 13.0044 79.7415 86.0264 20250704 7.5 5.2 122P/de Vico MPC 75718 -0123P 2026 09 22.1827 2.157345 0.444545 103.9486 45.9012 15.2795 20250704 12.2 4.0 123P/West-Hartley MPEC 2021-F20 -0124P 2026 06 23.6187 1.734452 0.486416 185.1151 359.9835 31.4034 20250704 13.5 2.8 124P/Mrkos MPEC 2024-UQ8 -0125P 2024 03 7.2231 1.526408 0.511982 87.1077 153.1496 9.9858 20250704 13.0 6.0 125P/Spacewatch MPEC 2024-UA9 -0126P 2023 07 5.0293 1.710657 0.696016 356.5594 357.8571 45.8716 20250704 6.0 8.0 126P/IRAS MPEC 2024-JU4 -0127P 2022 08 9.9949 2.215188 0.358737 6.3398 13.6164 14.2952 20250704 11.0 6.0 127P/Holt-Olmstead MPEC 2024-R10 -0128P 2026 07 16.7815 3.037294 0.322362 210.4964 214.3205 4.3710 20250704 8.5 4.0 128P/Shoemaker-Holt MPC 89014 -0129P 2022 12 3.5303 3.925070 0.085933 307.8813 184.8487 3.4414 20250704 11.0 4.0 129P/Shoemaker-Levy MPEC 2025-MC0 -0130P 2024 04 15.3465 1.825582 0.461263 246.3417 70.1785 6.0587 20250704 10.0 6.0 130P/McNaught-Hughes MPC184417 -0131P 2026 02 15.6317 2.407916 0.344747 179.2448 214.1358 7.3618 20250704 11.0 4.0 131P/Mueller MPEC 2025-A40 -0132P 2021 11 12.9243 1.697074 0.564009 216.5103 173.9780 5.3777 20250704 11.0 6.0 132P/Helin-Roman-Alu MPEC 2024-BE0 -0133P 2024 05 10.1059 2.670753 0.155649 131.8731 160.1009 1.3899 20250704 15.4 2.0 133P/Elst-Pizarro MPC 94676 -0134P 2030 01 8.4700 2.600576 0.585486 18.6537 201.9906 4.3330 20250704 11.5 4.0 134P/Kowal-Vavrova MPC 89012 -0135P 2022 04 6.0474 2.686057 0.293447 22.3728 213.0194 6.0628 20250704 7.0 8.0 135P/Shoemaker-Levy MPEC 2024-C04 -0136P 2025 01 3.4760 2.958513 0.293193 225.3253 137.4193 9.4273 20250704 11.0 4.0 136P/Mueller MPC182888 -0137P 2028 07 29.3561 1.931864 0.572952 141.2168 232.9273 4.8598 20250704 11.0 4.0 137P/Shoemaker-Levy MPEC 2023-J29 -0138P 2026 03 24.3038 1.694414 0.531542 95.6893 309.2718 10.0999 20250704 15.0 6.0 138P/Shoemaker-Levy MPEC 2016-U66 -0139P 2027 07 22.8219 3.392831 0.248302 165.9829 242.1795 2.3374 20250704 9.5 4.0 139P/Vaisala-Oterma MPEC 2020-HN5 -0140P 2031 10 5.4348 1.955197 0.695141 172.1532 343.3716 3.6942 20250704 11.5 6.0 140P/Bowell-Skiff MPEC 2015-E14 -0141P 2026 04 22.9758 0.807397 0.735887 153.6441 241.7760 13.9616 20250704 12.0 12.0 141P/Machholz MPEC 2024-R10 -0141P a 2026 04 23.3402 0.807402 0.735905 241.9288 153.5029 13.9417 20250704 12.0 12.0 141P-A/Machholz MPEC 2015-KD9 -0141P b 2026 04 15.3578 0.807701 0.735666 241.8177 153.5790 13.9857 20250704 9.0 4.0 141P-B/Machholz MPC 24216 -0141P d 2026 05 18.5884 0.806756 0.736850 242.1773 153.2287 13.8335 20250704 9.0 4.0 141P-D/Machholz MPC 37026 -0141P e 1994 09 19.2500 0.752528 0.750233 149.2667 246.1856 12.8152 9.0 4.0 141P-E/Machholz MPEC 2015-R12 -0141P f 1994 09 19.1963 0.752528 0.750009 149.2374 246.1881 12.7898 9.0 4.0 141P-F/Machholz MPEC 2015-R12 -0141P g 1994 09 19.1048 0.752528 0.749643 149.0784 246.3146 12.8259 9.0 4.0 141P-G/Machholz MPEC 2015-R12 -0141P h 2015 08 24.3866 0.761562 0.746822 149.4500 246.0900 12.8431 18.5 4.0 141P-H/Machholz MPC 95735 -0141P i 2026 04 13.6110 0.807234 0.735134 241.9385 153.4577 13.9417 20250704 17.5 4.0 141P-I/Machholz MPEC 2022-SU8 -0142P 2021 05 11.2303 2.522037 0.495941 174.0619 175.9599 12.2446 20250704 8.5 6.0 142P/Ge-Wang MPEC 2024-C04 -0143P 2026 12 26.1908 2.950506 0.382269 304.3600 242.4346 5.4373 20250704 13.5 2.0 143P/Kowal-Mrkos MPC182888 -0144P 2024 01 25.8242 1.399473 0.634966 216.3612 242.9246 3.9317 20250704 8.5 8.0 144P/Kushida MPEC 2024-YC7 -0145P 2026 01 31.9125 1.889814 0.542460 10.4057 26.7695 11.2778 20250704 13.5 4.0 145P/Shoemaker-Levy MPEC 2025-MC0 -0146P 2024 08 5.4151 1.418521 0.647582 317.0406 53.3551 23.1176 20250704 15.0 4.0 146P/Shoemaker-LINEAR MPC184418 -0147P 2023 12 7.4899 3.160568 0.211788 348.6069 91.6675 2.3115 20250704 14.0 4.0 147P/Kushida-Muramatsu MPEC 2024-UQ8 -0148P 2022 06 14.3082 1.627666 0.550392 8.0818 89.1952 3.6589 20250704 16.0 2.0 148P/Anderson-LINEAR MPEC 2024-JU4 -0149P 2026 12 16.4271 2.790296 0.324459 30.2209 143.7534 34.2363 20250704 8.0 8.0 149P/Mueller MPEC 2023-J29 -0150P 2024 03 12.5331 1.745372 0.549227 246.1236 272.0557 18.5485 20250704 13.5 4.0 150P/LONEOS MPEC 2024-NE4 -0151P 2029 08 17.9708 2.465089 0.572518 216.1554 143.1214 4.7253 20250704 10.0 6.0 151P/Helin MPEC 2022-K19 -0152P 2022 01 13.2315 3.109625 0.306807 164.4410 91.7755 9.8798 20250704 11.5 4.0 152P/Helin-Lawrence MPC182888 -0153P 2002 03 12.6696 0.496486 0.990166 34.2176 93.8032 28.5003 20250704 9.0 4.0 153P/Ikeya-Zhang MPC 46101 -0154P 2024 06 13.2071 1.552422 0.676262 47.9283 342.9953 17.6386 20250704 2.5 12.0 154P/Brewington MPC184418 -0155P 2019 11 17.4486 1.789655 0.727682 14.5320 97.1568 6.4107 20250704 10.0 4.8 155P/Shoemaker MPEC 2022-YN2 -0156P 2027 04 30.4989 1.333619 0.614856 0.5267 35.3337 17.2605 20250704 15.5 2.0 156P/Russell-LINEAR MPEC 2023-J29 -0157P 2022 09 10.1748 1.572509 0.556793 155.1797 287.4976 12.4245 20250704 10.0 4.0 157P/Tritton MPEC 2024-D33 -0157P b 2028 02 25.6889 1.551706 0.499892 287.2116 153.8796 12.4254 20250704 15.7 4.0 157P-B/Tritton MPEC 2022-VC5 -0158P 2022 09 10.7123 5.023860 0.117184 229.9077 124.3900 7.4561 20250704 9.0 4.0 158P/Kowal-LINEAR MPC182888 -0159P 2032 07 26.2781 3.615432 0.382529 4.7297 54.9388 23.4831 20250704 10.0 4.0 159P/LONEOS MPEC 2024-DC6 -0160P 2027 04 7.2212 1.795422 0.524993 12.7790 333.3479 15.5947 20250704 15.5 2.0 160P/LINEAR MPEC 2022-K19 -0161P 2026 11 27.9611 1.266711 0.835833 47.0670 1.5129 95.8182 20250704 8.5 6.0 161P/Hartley-IRAS MPC 75721 -0162P 2026 05 17.8245 1.289494 0.582933 357.2382 30.8758 27.5532 20250704 12.0 4.0 162P/SidingSpring MPEC 2025-MC0 -0163P 2026 11 23.9191 2.055426 0.453485 349.6376 102.0724 12.7212 20250704 14.5 4.0 163P/NEAT MPEC 2021-S45 -0164P 2025 05 27.4013 1.675097 0.541362 325.9511 88.2691 16.2773 20250704 11.0 4.0 164P/Christensen MPEC 2024-TD8 -0165P 2000 06 14.5845 6.782479 0.619272 125.8859 0.6705 15.9089 20250704 11.5 2.0 165P/LINEAR MPC 75721 -0166P 2002 06 6.1310 8.543615 0.382801 321.8558 64.4398 15.3775 20250704 5.5 4.0 166P/NEAT MPC 75722 -0167P 2001 03 26.1250 11.898357 0.267839 344.4340 295.8375 19.0747 20250704 9.5 2.0 167P/CINEOS MPEC 2023-J29 -0168P 2026 05 26.2478 1.358433 0.621264 15.1009 355.3875 21.5948 20250704 15.5 4.0 168P/Hergenrother MPEC 2023-J29 -0169P 2026 09 21.3346 0.603951 0.768036 218.1231 176.0566 11.2866 20250704 16.0 2.0 169P/NEAT MPC184418 -0170P 2023 04 15.6178 2.913523 0.305286 224.7164 142.6368 10.1303 20250704 12.0 4.0 170P/Christensen MPC184418 -0171P 2025 09 25.0392 1.766316 0.502806 347.0870 101.6999 21.9508 20250704 13.5 4.0 171P/Spahr MPC102102 -0172P 2025 11 2.5031 3.358156 0.204920 208.8917 30.8826 11.2230 20250704 13.0 4.0 172P/Yeung MPEC 2025-MC0 -0173P 2021 12 17.9105 4.216014 0.262382 29.2958 100.3458 16.4935 20250704 7.5 4.0 173P/Mueller MPEC 2023-N01 -0174P 2015 04 19.6935 5.865876 0.454790 163.4282 173.3407 4.3408 20250704 9.4 2.0 174P/Echeclus MPC 92985 -0175P 2026 09 2.9912 2.304042 0.375877 74.6524 109.8123 4.9280 20250704 14.0 4.0 175P/Hergenrother MPC114608 -0176P 2022 11 19.7924 2.582475 0.191810 34.4730 345.6301 0.2312 20250704 15.1 2.0 176P/LINEAR MPC 89015 -0177P 2006 08 29.8368 1.122283 0.954210 60.7638 271.8601 31.0053 20250704 15.0 4.0 177P/Barnard MPEC 2020-L06 -0178P 2027 06 21.4076 1.880797 0.482273 297.9628 102.7845 11.0926 20250704 13.5 4.0 178P/Hug-Bell MPEC 2024-R10 -0179P 2022 05 31.8329 4.123946 0.305397 297.2174 115.5079 19.8899 20250704 2.5 8.0 179P/Jedicke MPEC 2024-EF7 -0180P 2023 07 12.1454 2.499164 0.353846 94.6023 84.5587 16.8618 20250704 11.0 4.0 180P/NEAT MPEC 2024-F34 -0181P 2022 01 8.2492 1.164643 0.699773 336.2919 35.4415 17.4739 20250704 11.5 4.0 181P/Shoemaker-Levy MPC 89012 -0182P 2027 06 5.3732 0.990915 0.663950 54.2100 72.4538 16.2308 20250704 18.0 4.0 182P/LONEOS MPEC 2024-UQ8 -0183P 2027 09 15.3577 4.225582 0.102699 162.5946 3.5239 18.7253 20250704 12.5 2.0 183P/Korlevic-Juric MPEC 2024-VJ2 -0184P 2028 03 23.8336 1.711222 0.549782 186.5607 173.2671 4.5699 20250704 13.5 4.0 184P/Lovas MPEC 2020-W26 -0185P 2023 07 12.7829 0.931790 0.699397 181.9207 214.1228 14.0095 20250704 15.0 4.0 185P/Petriew MPEC 2024-F91 -0186P 2029 08 24.5729 4.255412 0.123762 268.4439 325.8680 28.6596 20250704 7.5 4.0 186P/Garradd MPEC 2022-X67 -0187P 2028 02 4.2104 3.839204 0.156184 131.6905 109.8457 13.6679 20250704 9.0 4.0 187P/LINEAR MPEC 2020-SI8 -0188P 2026 04 13.2751 2.546183 0.416689 26.8312 358.9133 10.5249 20250704 11.5 4.0 188P/LINEAR-Mueller MPEC 2025-MC0 -0189P 2027 09 13.4489 1.203020 0.590765 16.1825 281.6856 20.1209 20250704 19.0 4.0 189P/NEAT MPEC 2022-QD9 -0190P 2024 12 24.1577 2.019321 0.522754 50.5555 335.4680 2.1748 20250704 13.0 4.0 190P/Mueller MPC182889 -0191P 2028 02 29.6799 2.238772 0.385111 284.2680 98.1787 8.8395 20250704 13.0 4.0 191P/McNaught MPEC 2024-TD8 -0192P 2024 05 24.5009 1.462623 0.773386 313.0363 51.5756 24.5792 20250704 15.0 4.0 192P/Shoemaker-Levy MPC182889 -0193P 2028 06 1.4375 2.174275 0.392591 8.1145 335.1857 10.6789 20250704 14.0 4.0 193P/LINEAR-NEAT MPEC 2024-R10 -0194P 2024 02 4.3256 1.800065 0.563397 128.6209 349.5100 11.8034 20250704 16.0 4.0 194P/LINEAR MPEC 2024-GJ3 -0195P 2025 08 5.6876 4.440554 0.310855 250.6099 243.0968 36.4163 20250704 8.5 4.0 195P/Hill MPEC 2025-MC0 -0196P 2022 10 29.1628 2.179100 0.427506 12.1386 24.1245 19.2946 20250704 13.5 4.0 196P/Tichy MPEC 2024-GJ3 -0197P 2027 11 20.9421 1.108391 0.618901 189.9578 66.1913 25.2995 20250704 16.5 2.0 197P/LINEAR MPEC 2023-UR6 -0198P 2025 10 7.1103 1.994792 0.444686 69.0495 358.4688 1.3400 20250704 12.5 4.0 198P/ODAS MPEC 2024-VJ2 -0199P 2023 08 7.3319 2.910989 0.504383 191.7627 92.3436 24.9393 20250704 10.0 4.0 199P/Shoemaker MPEC 2024-Q20 -0200P 2030 08 6.3435 3.313208 0.331129 134.3839 234.8108 12.0950 20250704 9.0 4.0 200P/Larsen MPEC 2022-C56 -0201P 2027 07 20.1434 1.216036 0.637505 19.8042 41.5242 5.7369 20250704 14.0 4.0 201P/LONEOS MPC 93588 -0202P 2024 05 17.2913 3.069977 0.251062 274.4968 177.3004 2.1418 20250704 13.5 4.0 202P/Scotti MPC182889 -0203P 2030 04 8.8812 3.191416 0.316387 154.9398 290.2213 2.9760 20250704 14.5 2.0 203P/Korlevic MPEC 2025-A40 -0204P 2022 11 17.2977 1.834069 0.488292 356.7299 108.4731 6.5980 20250704 14.0 4.0 204P/LINEAR-NEAT MPEC 2024-JU4 -0205P 2028 09 13.5567 1.533544 0.567180 154.1526 179.6236 15.3003 20250704 13.0 4.0 205P/Giacobini MPEC 2023_O39 -0206P 2027 09 13.0061 1.567234 0.551123 189.5773 202.3409 33.6168 20250704 19.0 4.0 206P/Barnard-Boattini MPC 75725 -0207P 2024 01 31.8744 0.938409 0.758528 273.0301 198.1370 10.1985 20250704 16.0 4.0 207P/NEAT MPEC 2024-NE4 -0208P 2024 08 24.2828 2.529366 0.374178 310.7869 36.3302 4.4108 20250704 12.5 4.0 208P/McMillan MPC182889 -0209P 2024 07 14.4916 0.964145 0.674032 152.4806 62.7640 21.2829 20250704 17.0 2.0 209P/LINEAR MPEC 2024-TD8 -0210P 2025 11 22.7192 0.524444 0.834072 345.9176 93.8249 10.2819 20250704 13.5 4.0 210P/Christensen MPC105242 -0211P 2022 10 5.1877 2.326317 0.344494 4.3518 117.1007 18.9249 20250704 12.5 4.0 211P/Hill MPEC 2024-JU4 -0212P 2024 04 25.1531 1.612922 0.586758 14.0620 97.9717 22.1491 20250704 17.0 2.0 212P/NEAT MPEC 2024-GJ3 -0213P 2023 11 13.6463 1.981395 0.409875 6.5683 310.8808 10.4355 20250704 10.5 4.0 213P/VanNess MPC184418 -0213P b 2023 11 13.5153 1.981746 0.409749 6.5874 310.8773 10.4348 20250704 17.0 4.0 213P-B/Van Ness MPEC 2025-GB9 -0213P c 2023 11 12.5762 1.980779 0.409699 312.1927 5.1779 10.3501 20250704 17.5 4.0 213P-C/Van Ness MPC 76570 -0214P 2022 09 26.3906 1.857820 0.486287 190.1199 348.2118 15.1930 20250704 13.0 4.0 214P/LINEAR MPC 92986 -0215P 2028 11 24.2578 3.620793 0.164925 262.2424 56.6782 10.5763 20250704 11.0 4.0 215P/NEAT MPC184418 -0216P 2024 01 6.9991 2.126944 0.449022 151.7712 359.7802 9.0616 20250704 13.0 4.0 216P/LINEAR MPEC 2024-N80 -0217P 2025 05 24.9453 1.226376 0.689095 247.0372 125.3712 12.8655 20250704 12.0 4.0 217P/LINEAR MPEC 2025-MC0 -0218P 2026 03 3.8753 1.129821 0.630911 61.4250 174.6730 2.7266 20250704 16.0 4.0 218P/LINEAR MPEC 2022-K19 -0219P 2024 02 15.2853 2.355726 0.355968 108.0129 230.8765 11.5112 20250704 11.0 4.0 219P/LINEAR MPC182889 -0220P 2026 06 14.1436 1.558941 0.500389 180.5824 150.0908 8.1208 20250704 15.0 4.0 220P/McNaught MPEC 2024-A43 -0221P 2028 04 1.8321 1.617091 0.522277 42.0290 226.4338 10.8201 20250704 14.5 4.0 221P/LINEAR MPEC 2022-UY9 -0222P 2024 05 12.8881 0.825934 0.714818 346.2739 6.7525 5.0975 20250704 20.0 4.0 222P/LINEAR MPC 92277 -0223P 2027 07 24.7745 2.427427 0.416240 37.9836 346.7040 27.0059 20250704 12.0 4.0 223P/Skiff MPEC 2023-A50 -0224P 2022 09 30.1474 2.049197 0.405551 16.8159 40.0412 13.3012 20250704 15.5 4.0 224P/LINEAR-NEAT MPEC 2024-L77 -0225P 2023 08 7.8450 1.319841 0.638147 3.9062 14.2110 21.3611 20250704 18.0 4.0 225P/LINEAR MPEC 2024-F91 -0226P 2023 12 27.0565 1.774035 0.528848 341.0328 54.0134 44.0448 20250704 12.5 4.0 226P/Pigott-LINEAR-Kowalski MPEC 2024-MB8 -0227P 2024 03 8.3297 1.623582 0.527709 105.5946 36.8014 7.5072 20250704 16.5 2.0 227P/Catalina-LINEAR MPEC 2024-R10 -0228P 2028 09 5.1179 3.423626 0.177427 114.8048 30.9543 7.9158 20250704 14.1 4.0 228P/LINEAR MPEC 2022-HC2 -0229P 2025 03 5.8170 2.440411 0.378057 224.2295 157.8789 26.0963 20250704 13.0 4.0 229P/Gibbs MPC182889 -0230P 2028 08 20.5007 1.570550 0.545441 313.5821 106.9263 15.4722 20250704 13.0 4.0 230P/LINEAR MPEC 2025-MC0 -0231P 2027 08 4.5559 3.087160 0.239995 43.6956 132.7777 12.2726 20250704 14.5 2.0 231P/LINEAR-NEAT MPEC 2023-SQ0 -0232P 2028 09 20.5845 2.967480 0.336127 53.3042 56.0094 14.6429 20250704 11.5 4.0 232P/Hill MPC112394 -0233P 2026 01 8.1358 1.776702 0.412988 27.0242 74.8975 11.2889 20250704 15.0 4.0 233P/La Sagra MPEC 2021-N06 -0234P 2024 10 23.6747 2.820887 0.257304 357.4450 179.5641 11.5336 20250704 12.0 4.0 234P/LINEAR MPEC 2025-MC0 -0235P 2025 12 22.6249 1.978023 0.426068 352.1721 200.1751 9.8127 20250704 12.0 4.0 235P/LINEAR MPC184419 -0236P 2025 02 3.8455 1.828145 0.509338 119.4315 245.5692 16.3550 20250704 14.0 4.0 236P/LINEAR MPEC 2024-P23 -0237P 2023 05 14.3287 1.995993 0.432535 25.5430 245.3584 14.0098 20250704 14.5 2.0 237P/LINEAR MPC182890 -0238P 2028 01 24.0579 2.373822 0.250589 324.2642 51.6491 1.2637 20250704 14.5 4.0 238P/Read MPEC 2024-L77 -0239P 2028 06 17.6590 1.644834 0.631512 220.3855 255.9360 11.3065 20250704 17.5 2.0 239P/LINEAR MPEC 2021-F20 -0240P 2025 12 19.9593 2.121798 0.450292 352.0737 74.9115 23.5372 20250704 11.0 4.0 240P/NEAT MPEC 2025-MC0 -0241P 2021 07 26.1900 1.921260 0.610119 111.6171 305.4164 21.0949 20250704 13.5 4.0 241P/LINEAR MPEC 2022-J42 -0242P 2024 12 23.3963 3.971702 0.282853 244.9893 180.2375 32.4231 20250704 8.0 4.0 242P/Spahr MPEC 2025-MC0 -0243P 2026 02 25.5397 2.448036 0.360294 283.7033 87.6476 7.6441 20250704 12.5 4.0 243P/NEAT MPEC 2022-K19 -0244P 2022 11 20.1527 3.924582 0.199826 93.5160 354.0069 2.2576 20250704 9.0 4.0 244P/Scotti MPEC 2024-L77 -0245P 2026 03 31.1898 2.205485 0.455816 316.5000 316.8849 21.1713 20250704 14.0 4.0 245P/WISE MPEC 2022-CN4 -0246P 2029 10 22.9481 3.360567 0.218847 185.4303 74.1990 17.4513 20250704 10.5 4.0 246P/NEAT MPEC 2024-YC7 -0247P 2026 10 25.9553 1.484088 0.625589 47.5073 53.9858 13.6581 20250704 16.5 2.0 247P/LINEAR MPEC 2021-F20 -0248P 2025 09 14.9260 2.157755 0.639313 209.9910 207.7960 6.3519 20250704 14.0 4.0 248P/Gibbs MPEC 2025-MC0 -0249P 2025 02 1.7001 0.499573 0.819391 65.7558 239.0399 8.3842 20250704 15.5 4.0 249P/LINEAR MPEC 2022-YN2 -0250P 2025 05 16.7224 2.272322 0.398309 45.7039 73.3023 13.1519 20250704 14.5 4.0 250P/Larson MPC182890 -0251P 2024 02 13.1383 1.741164 0.504200 31.1915 219.3372 23.3885 20250704 16.5 2.0 251P/LINEAR MPEC 2024-TD8 -0252P 2026 11 7.7305 1.003688 0.671058 343.3742 190.9063 10.4200 20250704 17.5 4.0 252P/LINEAR MPEC 2021-S45 -0253P 2024 10 21.0338 2.026318 0.415259 230.8501 146.8273 4.9454 20250704 14.5 4.0 253P/PANSTARRS MPC182890 -0254P 2020 09 28.3434 3.148835 0.318451 219.7232 129.1789 32.5383 20250704 11.0 4.0 254P/McNaught MPC184419 -0255P 2027 09 25.5064 0.847190 0.712062 186.0457 275.6367 13.4054 20250704 9.0 4.0 255P/Levy NK 2214 -0256P 2023 03 11.9410 2.697412 0.418027 124.0629 81.3240 27.6233 20250704 14.0 2.0 256P/LINEAR MPEC 2024-L77 -0257P 2028 01 1.6894 2.152451 0.428761 117.7232 207.7291 20.2154 20250704 11.5 4.0 257P/Catalina MPEC 2023-A50 -0258P 2029 08 28.8006 3.468967 0.209575 25.6116 126.2361 6.7512 20250704 13.0 4.0 258P/PANSTARRS MPEC 2021-U31 -0259P 2026 08 12.1552 1.804889 0.338734 257.4858 51.3733 15.8981 20250704 15.5 4.0 259P/Garradd MPC106349 -0260P 2026 08 4.9948 1.417646 0.608779 18.4929 349.3035 15.0429 20250704 13.5 4.0 260P/McNaught MPEC 2022-O01 -0261P 2025 12 27.4041 2.014217 0.422797 67.3632 291.0506 6.0733 20250704 14.0 4.0 261P/Larson MPEC 2025-MC0 -0262P 2030 12 15.1166 1.264261 0.815956 171.0696 217.8862 29.2477 20250704 13.5 4.0 262P/McNaught-Russell MPC 82322 -0263P 2023 01 30.9286 1.234365 0.594070 35.0220 105.5040 11.5267 20250704 18.0 4.0 263P/Gibbs MPEC 2024-L77 -0264P 2027 03 15.6341 2.658271 0.340317 341.1386 219.1267 25.1362 20250704 13.0 4.0 264P/Larsen MPC114608 -0265P 2029 11 26.2074 1.505401 0.646694 33.5653 342.9202 14.3402 20250704 14.5 4.0 265P/LINEAR MPC 79870 -0266P 2026 12 7.3185 2.325054 0.340941 97.7945 4.9464 3.4284 20250704 14.7 4.0 266P/Christensen MPEC 2021-F20 -0267P 2024 04 24.9471 1.235244 0.614944 114.1969 228.5437 6.1396 20250704 19.5 4.0 267P/LONEOS MPC114608 -0268P 2024 12 18.4844 2.412718 0.474487 0.0185 125.6323 15.6615 20250704 14.0 4.0 268P/Bernardi MPEC 2025-MC0 -0269P 2033 07 11.3667 3.998236 0.433539 225.7356 241.7635 7.0838 20250704 10.0 4.0 269P/Jedicke MPEC 2023-J29 -0270P 2030 08 16.7057 3.522712 0.470188 209.9338 223.0239 2.9248 20250704 8.0 4.0 270P/Gehrels MPC 88332 -0271P 2032 03 21.8601 4.248648 0.395855 36.6224 9.2768 6.8665 20250704 11.0 4.0 271P/van Houten-Lemmon MPC 92277 -0272P 2022 07 17.5277 2.429473 0.455520 27.8904 109.4391 18.0824 20250704 16.0 2.0 272P/NEAT MPEC 2023-D41 -0273P 2012 12 21.9005 0.813206 0.974525 20.1221 320.3832 136.3598 20250704 11.5 4.0 273P/Pons-Gambart MPC 82723 -0274P 2022 04 9.1980 2.450851 0.440254 38.4962 81.3175 15.8205 20250704 13.0 4.0 274P/Tombaugh-Tenagra MPEC 2024-GJ3 -0275P 2026 10 27.9799 1.659079 0.713771 173.8936 348.6841 21.2540 20250704 17.0 4.0 275P/Hermann MPC 81862 -0276P 2024 12 11.1289 3.898614 0.273902 199.3872 211.2485 14.7702 20250704 11.5 4.0 276P/Vorobjov MPC184419 -0277P 2028 07 25.8656 1.902158 0.506394 152.4384 276.2600 16.7931 20250704 15.1 4.0 277P/LINEAR MPEC 2021-F20 -0278P 2027 09 14.8445 1.993756 0.451981 240.7326 12.4636 6.6123 20250704 14.0 4.0 278P/McNaught MPEC 2021-S45 -0279P 2023 04 18.7372 2.142600 0.399476 5.6247 346.0984 5.0531 20250704 14.0 4.0 279P/LaSagra MPEC 2024-A43 -0280P 2023 08 4.3863 2.638484 0.416830 104.6342 131.3779 11.7754 20250704 12.5 4.0 280P/Larsen MPEC 2024-RQ6 -0281P 2023 02 4.2954 4.036946 0.173927 27.0207 87.1663 4.7176 20250704 11.0 4.0 281P/MOSS MPEC 2023-D41 -0282P 2021 10 22.5892 3.440623 0.187654 9.0849 217.6071 5.8138 20250704 13.5 2.0 282P MPC133426 -0283P 2021 09 8.3727 2.127735 0.485013 22.1444 161.1238 14.4687 20250704 16.0 2.0 283P/Spacewatch MPEC 2022-K19 -0284P 2028 10 1.6398 2.301953 0.374296 202.4617 144.2639 11.8529 20250704 13.0 4.0 284P/McNaught MPEC 2024-D33 -0285P 2023 01 11.7915 1.720769 0.618056 178.3841 185.5143 25.0325 20250704 15.0 4.0 285P/LINEAR MPEC 2024-L77 -0286P 2022 05 12.7010 2.317809 0.431432 23.9797 283.5766 17.2320 20250704 14.0 4.0 286P/Christensen MPEC 2024-LE0 -0287P 2023 07 10.9780 3.045931 0.272862 190.5453 138.6512 16.3474 20250704 13.5 4.0 287P/Christensen MPEC 2025-A40 -0288P 2027 06 29.0024 2.441705 0.199596 280.2840 83.1063 3.2383 20250704 16.0 2.0 288P MPC133426 -0289P 2025 04 14.3164 0.954323 0.686450 9.8749 68.8907 5.9002 20250704 19.0 4.0 289P/Blanpain MPEC 2024-O39 -0290P 2029 07 22.2060 2.309858 0.628255 181.8614 302.6716 20.0448 20250704 10.5 4.0 290P/Jager MPC 95214 -0291P 2023 05 3.9869 2.567496 0.433851 173.5663 237.6620 6.3096 20250704 13.0 4.0 291P/NEAT MPEC 2024-YC7 -0292P 2029 03 3.7232 2.500057 0.589873 319.6624 90.8953 24.3226 20250704 12.5 4.0 292P/Li MPEC 2022-K19 -0293P 2027 11 29.0349 2.111436 0.419549 40.9890 78.3603 9.0609 20250704 14.5 4.0 293P/Spacewatch MPEC 2022-L66 -0294P 2025 08 11.1921 1.273047 0.600939 237.5853 309.6005 17.7430 20250704 15.5 4.0 294P/LINEAR MPC184419 -0295P 2026 07 22.7323 2.026030 0.617631 73.0443 7.3800 21.0852 20250704 12.0 4.0 295P/LINEAR MPEC 2022-K19 -0296P 2027 03 20.3891 1.782952 0.486240 350.2866 263.5226 25.3713 20250704 14.0 4.0 296P/Garradd MPEC 2021-N06 -0297P 2027 10 19.9504 2.556886 0.283980 142.4030 92.1760 11.2462 20250704 15.0 4.0 297P/Beshore MPC102956 -0298P 2027 06 24.7549 2.199710 0.386942 100.6216 52.7852 7.8724 20250704 15.0 4.0 298P/Christensen MPC114609 -0299P 2024 04 29.9912 3.155735 0.280933 323.6129 271.5804 10.4689 20250704 11.5 4.0 299P/Catalina-PANSTARRS MPEC 2025-MC0 -0300P 2027 09 14.1266 0.830073 0.692139 222.8766 95.6225 5.6766 20250704 16.0 4.0 300P/Catalina MPEC 2023-VM5 -0301P 2028 05 17.0638 2.379936 0.586252 193.4295 351.0621 10.3287 20250704 13.0 4.0 301P/LINEAR-NEAT MPC 89014 -0302P 2025 03 9.3921 3.288629 0.229311 208.6243 121.7158 6.0357 20250704 12.5 4.0 302P/Lemmon-PANSTARRS MPEC 2025-MC0 -0303P 2026 02 19.9179 2.468168 0.510259 357.0308 347.9481 7.0163 20250704 13.5 4.0 303P/NEAT MPC 92278 -0304P 2026 03 18.2008 1.257202 0.600839 335.2807 58.9374 2.6056 20250704 16.5 4.0 304P/Ory MPEC 2022-K19 -0305P 2024 11 17.1334 1.418159 0.694082 147.3992 240.0968 11.6704 20250704 18.0 4.0 305P/Skiff MPC182890 -0306P 2025 08 1.6484 1.272971 0.592565 0.8983 341.3516 8.3030 20250704 19.0 4.0 306P/LINEAR MPC 92278 -0307P 2028 12 2.3094 1.881235 0.674981 222.2557 158.1108 4.4345 20250704 15.0 4.0 307P/LINEAR MPC 92278 -0308P 2032 04 30.7055 4.197750 0.364116 333.7592 63.0996 4.8520 20250704 13.0 2.0 308P/Lagerkvist-Carsenty MPEC 2022-C56 -0309P 2024 03 28.9451 1.670218 0.618207 49.9195 10.1388 17.0196 20250704 15.0 4.0 309P/LINEAR MPC184419 -0310P 2023 10 23.1186 2.416318 0.422057 31.5167 8.8834 13.1202 20250704 13.5 4.0 310P/Hill MPC182891 -0311P 2024 01 1.8952 1.935961 0.115481 144.2951 279.1686 4.9713 20250704 17.0 4.0 311P/PANSTARRS MPC184419 -0312P 2027 03 15.4981 1.990949 0.426654 207.6970 144.6347 19.7459 20250704 16.0 4.0 312P/NEAT MPEC 2024-NE4 -0313P 2025 12 2.7414 2.421607 0.234452 254.9870 105.9254 10.9810 20250704 15.0 4.0 313P/Gibbs MPEC 2024-N80 -0314P 2016 10 13.8324 4.214549 0.418602 213.8673 267.6232 3.9921 20250704 9.5 4.0 314P/Montani MPC105243 -0315P 2027 11 16.5068 2.358899 0.522106 65.9212 68.6363 17.7352 20250704 11.0 4.0 315P/LONEOS MPEC 2023-J29 -0316P 2024 10 3.8536 3.717207 0.156376 186.9300 245.8771 9.8723 20250704 13.5 4.0 316P/LONEOS-Christensen MPC182891 -0317P 2025 10 30.8651 1.266615 0.572019 334.8889 275.4727 11.9747 20250704 17.5 4.0 317P/WISE MPEC 2020-C98 -0318P 2015 10 22.3491 2.455728 0.673223 313.2996 35.6084 17.8638 20250704 8.5 6.0 318P/McNaught-Hartley MPC102103 -0319P 2022 03 30.5522 1.188236 0.666456 203.5916 111.3656 15.0971 20250704 15.0 4.0 319P/Catalina-McNaught MPC184420 -0320P 2026 06 27.8520 0.975490 0.684915 0.7574 295.9406 4.9028 20250704 20.5 4.0 320P/McNaught MPC 96281 -0321P 2023 10 26.4906 0.046006 0.981005 172.7401 165.0263 20.0551 20250704 20.0 4.0 321P/SOHO MPC105243 -0322P 2023 08 21.1682 0.050360 0.979926 57.0856 351.3360 11.4471 20250704 19.0 4.0 322P/SOHO MPC102103 -0323P 2025 03 14.2328 0.040377 0.983454 353.3282 323.9435 5.2123 20250704 20.0 4.0 323P/SOHO MPC182891 -0323P b 2025 12 16.2376 0.040087 0.986129 353.9671 323.4636 5.4613 20250704 26.0 4.0 323P-B/SOHO MPEC 2024-F21 -0323P c 2025 04 7.1016 0.039783 0.984770 353.2140 324.1853 5.3384 20250704 27.0 4.0 323P-C/SOHO MPEC 2024-F21 -0324P 2026 10 14.7439 2.624073 0.152792 57.4120 270.5690 21.3993 20250704 13.0 4.0 324P/LaSagra MPEC 2021-W31 -0325P 2022 03 23.8755 1.465738 0.587080 344.9096 256.8587 16.8458 20250704 14.0 4.0 325P/Yang-Gao MPEC 2024-LE0 -0326P 2023 12 28.2395 2.760625 0.320523 278.0306 99.7611 2.4738 20250704 13.5 4.0 326P/Hill MPEC 2024-LE0 -0327P 2022 09 1.8346 1.558832 0.562502 185.0394 173.9987 36.2302 20250704 16.0 4.0 327P/VanNess MPEC 2024-M41 -0328P 2024 07 27.9277 1.872203 0.553170 30.6717 341.5404 17.6815 20250704 14.5 4.0 328P/LONEOS-Tucker MPEC 2024-YC7 -0329P 2027 09 25.6143 1.664014 0.678880 343.6040 87.6875 21.7189 20250704 13.5 4.0 329P/LINEAR-Catalina MPC101101 -0330P 2033 09 5.4845 2.972771 0.550602 188.8383 293.0840 15.7404 20250704 12.0 4.0 330P/Catalina MPEC 2023-J29 -0331P 2025 12 24.6869 2.878493 0.041441 185.6178 216.7423 9.7408 20250704 12.0 4.0 331P/Gibbs MPEC 2024-Q20 -0332P 2027 01 19.7074 1.574327 0.489860 152.2978 3.7545 9.3859 20250704 18.0 4.0 332P/Ikeya-Murakami MPEC 2016-K18 -0332P a 2027 01 19.7089 1.574294 0.489868 3.7384 152.3148 9.3857 20250704 9.0 4.0 332P-A/Ikeya-Murakami MPEC 2016-K18 -0332P b 2016 03 17.1650 1.572891 0.489707 152.3711 3.8028 9.3805 19.0 4.0 332P-B/Ikeya-Murakami MPEC 2016-EI8 -0332P c 2027 01 19.5985 1.574260 0.489874 3.7389 152.3061 9.3848 20250704 16.5 4.0 332P-C/Ikeya-Murakami MPEC 2016-K18 -0332P d 2016 03 17.2819 1.572064 0.489778 152.4393 3.7923 9.3761 19.0 4.0 332P-D/Ikeya-Murakami MPEC 2016-ED0 -0332P e 2016 03 17.0610 1.573139 0.489220 152.2825 3.8228 9.3774 21.0 4.0 332P-E/Ikeya-Murakami MPEC 2016-ED0 -0332P f 2016 03 17.8554 1.584174 0.499189 152.8203 3.4757 9.5293 21.0 4.0 332P-F/Ikeya-Murakami MPEC 2016-ED0 -0332P g 2016 03 19.5375 1.549652 0.492004 154.4000 3.6955 9.2523 19.0 4.0 332P-G/Ikeya-Murakami MPEC 2016-ED0 -0332P h 2027 01 20.1321 1.574241 0.489910 3.7386 152.3068 9.3853 20250704 19.0 4.0 332P-H/Ikeya-Murakami MPC100285 -0332P i 2016 03 17.3515 1.573073 0.489555 152.3297 3.8048 9.3791 20.5 2.0 332P-I/Ikeya-Murakami MPEC 2016-ED0 -0332P j 2016 03 17.7739 1.575357 0.494294 152.7712 3.6729 9.4296 20.5 2.0 332P-J/Ikeya-Murakami MPEC 2016-EI8 -0333P 2024 11 29.2982 1.113023 0.736284 26.0221 115.7065 132.0225 20250704 15.0 4.0 333P/LINEAR MPEC 2025-MC0 -0334P 2017 06 4.4910 4.422029 0.352011 90.0750 90.3535 20.3641 20250704 10.5 4.0 334P/NEAT MPEC 2023-J29 -0335P 2022 08 12.5548 1.620883 0.546886 162.3229 330.7907 7.2980 20250704 16.8 4.0 335P/Gibbs MPEC 2023-M14 -0336P 2028 05 14.1299 2.786719 0.446463 308.7143 298.1680 17.8784 20250704 13.5 4.0 336P/McNaught MPC105244 -0337P 2022 06 23.2463 1.741228 0.480041 166.2874 102.0418 17.0659 20250704 17.0 4.0 337P/WISE MPEC 2024-A43 -0338P 2024 08 3.3107 2.287463 0.412809 4.6354 9.7361 25.3762 20250704 12.0 4.0 338P/McNaught MPC182891 -0339P 2023 08 30.9891 1.346922 0.635816 172.6740 27.4568 5.7348 20250704 17.0 4.0 339P/Gibbs MPC101101 -0340P 2025 08 29.2588 3.057949 0.279953 36.0646 291.6597 2.0790 20250704 14.3 4.0 340P/Boattini MPC133426 -0341P 2025 04 22.7119 2.506431 0.415035 312.3634 29.9524 3.7965 20250704 12.5 4.0 341P/Gibbs MPEC 2023-J29 -0342P 2027 02 7.7011 0.051745 0.982983 27.6535 73.3066 11.6894 20250704 9.0 4.0 342P/SOHO MPC101101 -0343P 2029 11 4.6914 2.266183 0.584796 137.6085 257.0545 5.5976 20250704 14.0 4.0 343P/NEAT-LONEOS MPEC 2024-PC5 -0344P 2027 07 24.8552 2.797678 0.423733 140.6279 273.1015 3.4997 20250704 13.0 4.0 344P/Read MPEC 2023-J29 -0345P 2024 08 31.1069 3.139905 0.221381 196.7815 154.5045 2.7279 20250704 12.0 4.0 345P/LINEAR MPEC 2024-TP3 -0346P 2026 08 1.2592 2.216384 0.503908 336.0798 102.4578 22.2193 20250704 14.0 4.0 346P/Catalina MPEC 2022-K19 -0347P 2023 07 19.2306 2.206704 0.386985 98.0832 260.9905 11.7659 20250704 15.0 4.0 347P/PANSTARRS MPEC 2024-RQ6 -0348P 2027 09 19.1501 2.182452 0.307504 135.7793 312.9122 17.7430 20250704 14.0 4.0 348P/PANSTARRS MPEC 2022-ED3 -0349P 2024 05 26.9386 2.509589 0.298596 255.7461 331.7386 5.4893 20250704 14.0 4.0 349P/Lemmon MPEC 2024-LE0 -0350P 2026 03 17.4558 3.694318 0.094723 140.0633 65.2953 7.3655 20250704 14.0 4.0 350P/McNaught MPC184420 -0351P 2025 03 26.2430 3.132175 0.294646 352.5823 283.3848 12.7786 20250704 12.5 4.0 351P/Wiegert-PANSTARRS MPEC 2025-MC0 -0352P 2017 06 18.3758 2.556308 0.615924 309.3676 28.0532 21.0030 20250704 13.2 4.0 352P/Skiff MPEC 2023-J29 -0353P 2026 07 1.4712 2.211809 0.469700 230.4851 121.5090 28.4194 20250704 14.5 4.0 353P/McNaught MPEC 2020-AA5 -0354P 2023 10 14.2698 2.005317 0.124451 132.9406 320.0580 5.2508 20250704 15.5 4.0 354P/LINEAR MPEC 2024-EF7 -0355P 2024 04 1.2361 1.705925 0.507953 336.2567 51.4234 11.0460 20250704 15.5 2.0 355P/LINEAR-NEAT MPEC 2023-CD7 -0356P 2026 06 12.3367 2.674633 0.355852 226.2194 160.7909 9.6421 20250704 14.0 4.0 356P/WISE MPEC 2022-F14 -0357P 2027 10 29.6638 2.512567 0.436002 1.5088 44.5668 6.3124 20250704 15.5 4.0 357P/Hill MPC114609 -0358P 2023 11 9.4870 2.392294 0.239479 299.3246 85.6670 11.0668 20250704 18.0 4.0 358P/PANSTARRS MPEC 2024-EF7 -0359P 2027 08 24.4334 3.142588 0.323097 200.2799 149.7441 10.2618 20250704 13.5 4.0 359P/LONEOS MPC110086 -0360P 2024 10 3.8421 1.851747 0.499437 354.3360 2.1484 24.1051 20250704 19.5 6.0 360P/WISE MPEC 2025-A40 -0361P 2029 06 21.6708 2.764816 0.439519 219.1369 203.2270 13.8973 20250704 12.0 4.0 361P/Spacewatch MPEC 2023-CD7 -0363P 2024 11 13.2264 1.721007 0.518568 340.7652 146.7578 5.3938 20250704 17.5 4.0 363P/Lemmon MPC184420 -0364P 2023 05 12.5433 0.820481 0.717228 212.8495 45.8039 11.8768 20250704 17.0 2.0 364P/PANSTARRS MPEC 2024-M41 -0365P 2023 10 9.5245 1.320355 0.581671 67.4148 86.6556 9.8498 20250704 17.0 4.0 365P/PANSTARRS MPC111775 -0366P 2025 01 30.8850 2.279963 0.348655 152.9928 70.7230 8.8567 20250704 15.0 4.0 366P/Spacewatch MPC114610 -0367P 2025 01 11.5156 2.527924 0.280145 172.6798 58.6607 8.4590 20250704 17.5 2.0 367P/Catalina MPC112395 -0368P 2031 09 23.8648 2.072453 0.625593 118.9860 257.8565 15.4825 20250704 14.0 4.0 368P/NEAT MPC114610 -0369P 2027 12 18.9631 1.944533 0.555894 13.2441 47.2830 10.3192 20250704 15.0 4.0 369P/Hill MPC114610 -0370P 2018 06 12.7381 2.478791 0.615119 356.7882 55.0867 19.4163 20250704 13.0 4.0 370P/NEAT MPEC 2021-F20 -0371P 2027 04 25.9905 2.188281 0.476557 308.5662 67.2837 17.3835 20250704 16.0 4.0 371P/LINEAR-Skiff MPC114610 -0372P 2028 05 24.1708 3.830701 0.151190 325.9494 27.5491 9.5036 20250704 13.5 4.0 372P/McNaught MPEC 2020-K19 -0373P 2026 09 4.9576 2.301557 0.393822 221.1442 231.9297 13.7708 20250704 14.5 4.0 373P/Rinner MPEC 2021-F20 -0374P 2030 02 14.3547 2.666606 0.463603 51.5926 7.8626 10.7601 20250704 14.0 4.0 374P/Larson MPC114610 -0375P 2018 12 23.8851 1.883911 0.660275 119.4594 359.8270 17.3754 20250704 16.0 4.0 375P/Hill MPEC 2021-F20 -0376P 2019 09 12.9200 2.798371 0.513755 285.3380 312.8513 1.1662 20250704 12.5 4.0 376P/LONEOS MPEC 2024-RQ6 -0377P 2020 07 9.5692 5.011060 0.251486 354.9021 225.9200 9.0332 20250704 9.5 4.0 377P/Scotti MPEC 2022-N37 -0378P 2020 10 6.0619 3.374142 0.463296 193.2976 93.7911 19.1599 20250704 12.0 4.0 378P/McNaught MPEC 2025-A40 -0379P 2026 02 22.8342 2.263347 0.350177 184.7061 30.4458 12.4367 20250704 15.0 4.0 379P/Spacewatch MPC115889 -0380P 2028 08 8.2670 2.961789 0.333684 87.6558 127.6936 8.0352 20250704 12.5 4.0 380P/PANSTARRS MPEC 2023-C45 -0381P 2019 09 24.9643 2.282917 0.680493 173.8466 173.3230 28.3351 20250704 17.5 2.0 381P/LINEAR-Spacewatch MPEC 2021-J28 -0382P 2021 10 28.3449 4.328461 0.264848 162.4728 170.0054 8.2766 20250704 8.0 4.0 382P/Larson MPC182891 -0383P 2026 07 2.5883 1.425096 0.598465 133.7207 207.8548 12.3165 20250704 18.0 4.0 383P/Christensen MPEC 2022-OB6 -0384P 2024 09 19.1168 1.111854 0.616248 37.6999 354.1876 7.2842 20250704 19.5 4.0 384P/Kowalski MPC182891 -0385P 2028 08 4.9082 2.565649 0.401828 44.4677 357.0314 16.8220 20250704 13.0 4.0 385P/Hill MPEC 2021-F20 -0386P 2028 10 13.7363 2.358364 0.417535 353.1072 134.9160 15.2472 20250704 14.5 4.0 386P/PANSTARRS MPEC 2021-L04 -0387P 2030 03 13.1774 1.261910 0.736965 162.8542 259.2388 8.9379 20250704 15.0 4.0 387P/Boattini MPEC 2021-J28 -0388P 2019 07 26.8715 1.994890 0.619355 42.3753 37.0063 23.8768 20250704 13.0 4.0 388P/Gibbs MPEC 2021-S45 -0389P 2019 12 31.3755 1.656543 0.705757 249.3169 218.8474 160.0788 20250704 16.0 4.0 389P/Siding Spring MPEC 2022-OB6 -0390P 2020 03 22.2975 1.706916 0.706616 232.5635 152.1975 18.5209 20250704 12.0 4.0 390P/Gibbs MPEC 2024-EF7 -0391P 2028 05 11.0622 4.136490 0.118357 186.9076 124.7728 21.2567 20250704 8.0 4.0 391P/Kowalski MPEC 2021-F20 -0392P 2020 04 3.0410 1.941407 0.683942 71.9736 24.7971 4.9282 20250704 14.5 4.0 392P/LINEAR MPEC 2021-J28 -0393P 2030 05 7.1711 4.229249 0.119041 329.1983 36.4023 16.7830 20250704 11.0 4.0 393P/Spacewatch-Hill MPC182892 -0394P 2028 11 30.0892 2.732463 0.368407 54.4586 98.1002 8.5279 20250704 16.0 2.4 394P/PANSTARRS MPEC 2020-KB7 -0395P 2022 02 20.3859 4.241226 0.411221 100.7243 220.9599 3.5690 20250704 10.0 4.0 395P/Catalina-NEAT MPC182892 -0396P 2019 08 29.3234 3.963291 0.417047 8.3097 136.6063 5.4428 20250704 12.0 4.0 396P MPEC 2020-KB7 -0397P 2027 12 21.2048 2.281927 0.404553 14.5889 8.2069 10.9195 20250704 12.0 4.0 397P/Lemmon MPEC 2022-OB6 -0398P 2026 07 7.9257 1.300444 0.583769 127.5535 320.1345 11.0278 20250704 15.5 4.0 398P/Boattini MPEC 2021-L04 -0399P 2028 10 12.5662 2.096881 0.447267 214.4534 207.1150 13.3158 20250704 14.0 4.0 399P/PANSTARRS MPEC 2023-XP6 -0400P 2027 11 3.0442 2.103061 0.409580 238.9571 176.3451 10.9250 20250704 15.5 2.8 400P/PANSTARRS MPEC 2024-TD8 -0401P 2019 12 3.0175 2.435750 0.578335 309.3459 359.9219 12.8005 20250704 12.5 4.0 401P/McNaught MPEC 2022-K19 -0402P 2021 12 16.0692 3.943111 0.440010 327.0029 123.0429 30.8289 20250704 9.0 4.0 402P/LINEAR MPEC 2024-LE0 -0403P 2020 09 17.9188 2.693524 0.504215 163.9749 277.5604 12.3323 20250704 12.0 4.0 403P/Catalina MPEC 2021-J28 -0404P 2023 10 31.4591 4.132390 0.124124 168.9568 260.0406 9.8041 20250704 10.0 4.0 404P/Bressi MPC184420 -0405P 2027 10 29.5753 1.116393 0.690213 3.3107 112.1936 9.3792 20250704 17.5 4.0 405P/Lemmon MPEC 2021-L04 -0406P 2027 06 24.8976 1.642990 0.541005 11.5608 352.3853 1.2098 20250704 17.0 4.0 406P/Gibbs MPEC 2021-F20 -0407P 2026 07 25.5808 2.181073 0.375748 93.0901 80.2447 4.8753 20250704 14.0 4.0 407P/PANSTARRS-Fuls MPEC 2022-YN2 -0408P 2022 10 6.0521 3.472178 0.268385 226.6977 189.4514 19.3513 20250704 11.0 4.0 408P/Novichonok-Gerke MPC184420 -0409P 2021 01 28.7117 1.747916 0.710261 15.0407 143.6400 17.1494 20250704 14.0 4.0 409P/LONEOS-Hill MPEC 2022-ED3 -0410P 2021 06 24.7850 3.249096 0.511716 313.2825 139.9301 9.3881 20250704 12.5 4.0 410P/NEAT-LINEAR MPEC 2022-M21 -0411P 2021 01 25.7754 2.430318 0.581825 46.5726 77.6510 12.3886 20250704 13.5 4.0 411P/Christensen MPC184420 -0412P 2026 05 30.6293 1.621018 0.479060 155.8546 0.8410 8.9293 20250704 17.0 4.0 412P/WISE MPEC 2021-F20 -0413P 2028 10 3.3006 2.175333 0.417724 186.7298 38.9473 15.9586 20250704 14.0 4.0 413P/Larson MPC184420 -0414P 2025 09 26.3283 0.524157 0.812271 210.7110 257.8153 23.4073 20250704 19.0 4.0 414P/STEREO MPEC 2024-JU4 -0415P 2029 06 13.6759 3.304729 0.195555 345.8864 160.2577 31.8104 20250704 12.0 4.0 415P/Tenagra MPEC 2022-J42 -0416P 2029 02 23.8484 2.181460 0.455501 134.4565 355.7301 3.3636 20250704 15.5 4.0 416P/Scotti MPC184420 -0417P 2027 05 13.5670 1.495336 0.553558 126.4785 111.9644 9.9227 20250704 16.5 4.0 417P/NEOWISE MPEC 2021-W31 -0418P 2021 10 16.3547 1.710714 0.663896 307.3328 277.6164 5.7809 20250704 13.0 4.0 418P/LINEAR MPEC 2022-TA0 -0419P 2028 06 15.4757 2.567916 0.273478 187.8389 40.4069 2.7946 20250704 12.5 4.0 419P/PANSTARRS MPEC 2023-UR6 -0420P 2022 05 18.0112 2.766897 0.495100 156.4043 173.5140 14.5028 20250704 11.5 4.0 420P/Hill MPEC 2024-L77 -0421P 2021 01 23.5089 1.652411 0.674382 259.8561 55.3301 10.0757 20250704 14.0 4.0 421P/McNaught MPEC 2021-W31 -0422P 2022 01 10.6723 3.101403 0.505666 304.7566 36.0119 39.5802 20250704 11.0 4.0 422P/Christensen MPEC 2024-N80 -0423P 2021 09 26.8043 5.423284 0.122794 80.9409 33.3020 8.3424 20250704 8.0 4.0 423P/Lemmon MPEC 2023-FK0 -0424P 2021 10 30.8379 1.369022 0.690342 312.5556 51.2130 8.6814 20250704 17.0 4.0 424P/LaSagra MPEC 2022-CN4 -0425P 2021 09 20.9495 2.898435 0.543692 200.9945 210.0873 16.4133 20250704 12.0 4.0 425P/Kowalski MPEC 2024-C04 -0426P 2023 09 10.3078 2.672822 0.161028 118.3888 280.3967 17.7841 20250704 13.5 4.0 426P/PANSTARRS MPEC 2024-N80 -0428P 2027 11 17.9730 1.680833 0.518190 36.8943 299.3103 8.5028 20250704 15.0 4.0 428P/Gibbs MPEC 2023-J29 -0429P 2028 09 16.3443 1.810572 0.490827 75.7380 322.0124 7.5142 20250704 15.5 4.0 429P/LINEAR-Hill MPEC 2024-EF7 -0430P 2027 05 22.4765 1.550671 0.500296 94.4544 54.6457 4.4756 20250704 16.5 4.0 430P/Scotti MPEC 2022-L66 -0431P 2028 08 8.6959 1.817357 0.477330 200.0033 202.8377 22.3797 20250704 14.0 4.0 431P/Scotti MPEC 2025-A40 -0432P 2026 12 15.4230 2.306664 0.240827 105.2680 239.1307 10.0678 20250704 17.0 4.0 432P/PANSTARRS MPEC 2021-U31 -0434P 2021 10 27.1015 3.001544 0.274295 128.4493 288.9126 6.3363 20250704 13.0 4.0 434P/Tenagra MPEC 2024-D33 -0435P 2026 10 26.6485 2.062158 0.317549 244.2068 98.5242 18.8745 20250704 17.0 4.0 435P/PANSTARRS MPEC 2021-W31 -0436P 2021 12 7.7571 1.964867 0.669037 282.7632 87.1564 20.1993 20250704 14.5 4.0 436P/Garradd MPEC 2022-X67 -0437P 2022 08 20.2864 3.403731 0.255049 207.0670 245.8407 3.6890 20250704 13.0 4.0 437P/Lemmon-PANSTARRS MPEC 2023-B57 -0438P 2027 10 25.1379 2.257167 0.414134 58.9835 260.1086 8.2807 20250704 14.5 4.0 438P/Christensen MPEC 2025-A40 -0439P 2028 03 5.7056 1.853907 0.469080 342.1062 56.4378 7.1119 20250704 13.5 4.0 439P/LINEAR MPEC 2022-C56 -0440P 2022 03 30.4039 2.051569 0.760871 183.3017 328.8036 12.3511 20250704 15.5 4.0 440P/Kobayashi MPEC 2024-N80 -0441P 2025 09 9.3825 3.327880 0.194635 178.8667 143.5887 2.5746 20250704 13.5 4.0 441P/PANSTARRS MPEC 2025-MC0 -0442P 2022 08 17.6330 2.315815 0.532577 310.6379 31.9455 6.0574 20250704 13.5 4.0 442P/McNaught MPEC 2024-N80 -0443P 2022 10 9.3952 2.957649 0.282927 145.0726 108.9335 19.8879 20250704 13.5 4.0 443P/PANSTARRS-Christensen MPEC 2024-TD8 -0444P 2022 06 30.0061 1.537705 0.557324 172.8594 88.1848 22.7266 20250704 17.0 4.0 444P/WISE-PANSTARRS MPEC 2023-VM5 -0445P 2022 08 16.1976 2.370166 0.414184 213.2020 126.5907 1.0889 20250704 15.0 4.0 445P/Lemmon-PANSTARRS MPEC 2024-BE0 -0446P 2022 05 28.6713 1.610606 0.646778 344.6227 336.3347 16.6297 20250704 16.5 4.0 446P/McNaught MPEC 2024-NE4 -0447P 2022 08 16.1958 4.628443 0.177251 97.5034 302.6372 7.4413 20250704 12.0 4.0 447P/Sheppard-Tholen MPEC 2022-YB4 -0448P 2022 09 6.1298 2.115873 0.418144 218.8014 161.7540 12.1449 20250704 16.0 4.0 448P/PANSTARRS MPEC 2024-PC5 -0449P 2027 09 25.1263 1.872742 0.479768 176.7668 242.5219 15.4700 20250704 16.0 4.0 449P/Leonard MPEC 2024-DC6 -0450P 2027 02 2.8797 5.440262 0.314302 23.6885 124.2385 10.6927 20250704 6.5 4.0 450P/LONEOS MPC184420 -0451P 2022 11 27.9759 2.798926 0.559236 186.7938 300.8677 26.4850 20250704 15.5 4.0 451P/Christensen MPEC 2023-HD1 -0452P 2023 04 25.9960 4.177814 0.428569 37.0976 123.6653 6.4219 20250704 9.0 4.0 452P/Sheppard-Jewitt MPEC 2024-NE4 -0453P 2023 03 3.3701 2.279125 0.583147 70.8999 42.8920 27.0594 20250704 14.0 4.0 453P/WISE-Lemmon MPEC 2023-RF3 -0454P 2022 07 26.6642 2.689364 0.361422 20.1965 54.5860 19.8093 20250704 14.0 4.0 454P/PANSTARRS MPEC 2023-CD7 -0455P 2023 02 24.9171 2.193396 0.304433 237.5353 146.1801 14.1348 20250704 17.0 4.0 455P/PANSTARRS MPEC 2022-Y14 -0456P 2025 04 14.9040 2.802233 0.115880 233.0004 243.1437 16.9651 20250704 13.5 4.0 456P/PANSTARRS MPC182892 -0457P 2024 08 20.0657 2.332003 0.118384 104.3169 175.9634 5.2257 20250704 15.5 4.0 457P/Lemmon-PANSTARRS MPEC 2025-A40 -0458P 2022 10 30.7909 2.634898 0.317256 104.9360 1.5605 13.6221 20250704 17.3 4.0 458P/Jahn MPEC 2023-HD1 -0459P 2023 02 21.6841 1.367918 0.577859 205.2259 256.9876 7.1737 20250704 15.5 4.0 459P/Catalina MPEC 2024-N80 -0460P 2026 09 21.6425 1.016485 0.664223 351.9346 180.5168 18.9000 20250704 21.0 4.0 460P/PANSTARRS MPEC 2023-G14 -0461P 2027 05 3.0446 1.353454 0.569566 174.8309 194.3770 18.3988 20250704 18.5 4.0 461P/WISE MPEC 2024-GJ3 -0462P 2022 08 1.1450 2.049568 0.578484 4.2195 322.6630 7.0467 20250704 17.0 4.0 462P/LONEOS-PANSTARRS MPEC 2024-BE0 -0463P 2023 03 29.8570 0.517809 0.825895 216.3407 283.2180 29.2960 20250704 18.0 4.0 463P/NEOWISE MPEC 2024-GJ3 -0464P 2023 02 27.3158 3.369707 0.280580 267.5247 309.5782 21.6734 20250704 10.5 4.0 464P/PANSTARRS MPEC 2024-Q20 -0465P 2023 05 8.9350 2.324230 0.613149 140.9833 217.9553 25.8618 20250704 12.5 4.0 465P/Hill MPEC 2024-NE4 -0466P 2023 05 10.8324 2.104153 0.478903 198.0041 117.9041 12.9260 20250704 14.0 4.0 466P/PANSTARRS MPEC 2024-JU4 -0467P 2022 11 26.4597 5.508697 0.054484 267.4698 43.2629 2.4793 20250704 9.0 4.0 467P/LINEAR-Grauer MPEC 2025-A40 -0468P 2023 11 21.0946 3.950404 0.444965 322.5765 356.1260 50.4520 20250704 11.5 4.0 468P/SidingSpring MPEC 2024-O39 -0469P 2025 12 8.4097 3.004998 0.308009 43.4949 178.9673 20.1722 20250704 13.5 4.0 469P/PANSTARRS MPEC 2025-A40 -0470P 2023 12 16.7256 2.725640 0.389370 151.6864 246.1685 8.8441 20250704 15.5 4.0 470P/PANSTARRS MPC182892 -0471P 2023 12 19.8262 2.119676 0.627700 94.7850 283.3125 4.7970 20250704 12.0 4.0 471P/LINEAR-Lemmon MPC182892 -0472P 2024 07 14.1098 3.387337 0.564539 218.8371 205.8446 10.8242 20250704 10.5 4.0 472P/NEAT-LINEAR MPEC 2025-MC0 -0473P 2024 02 26.2364 1.406390 0.823597 42.9374 22.1901 56.8963 20250704 13.5 4.0 473P/NEAT MPEC 2024-MB8 -0474P 2023 07 15.6570 2.541809 0.188053 11.2619 26.7499 1.0969 20250704 15.5 4.0 474P/Hogan MPEC 2024-B74 -0475P 2024 06 1.6594 4.077403 0.442811 40.4092 147.3599 14.5237 20250704 11.0 4.0 475P/Spacewatch-LINEAR MPEC 2025-MC0 -0476P 2024 10 16.4747 3.123423 0.345869 46.7333 57.0497 19.0052 20250704 12.5 4.0 476P/PANSTARRS MPC184421 -0477P 2023 12 26.5239 1.748547 0.417537 305.8757 59.1455 8.9138 20250704 14.5 4.0 477P/PANSTARRS MPEC 2024-GJ3 -0478P 2024 05 2.1691 2.393959 0.343751 13.2438 127.2629 12.5247 20250704 13.5 4.0 478P/ATLAS MPEC 2024-L77 -0479P 2024 05 5.2609 1.243192 0.778907 263.5055 295.8325 15.3997 20250704 15.0 4.0 479P/Elenin MPEC 2024-PC5 -0480P 2023 04 23.7546 3.475067 0.246320 214.4162 229.9817 13.7167 20250704 12.0 4.0 480P/PANSTARRS MPC182893 -0481P 2023 07 9.2969 3.073663 0.343467 356.8024 93.5503 6.0826 20250704 13.5 4.0 481P/Lemmon-PANSTARRS MPEC 2025-A40 -0482P 2023 06 2.1702 1.907115 0.492366 339.7254 126.0773 24.4871 20250704 13.5 4.0 482P/PANSTARRS MPEC 2024-JU4 -0483P a 2027 11 10.8017 2.484875 0.222282 49.1787 199.2558 14.1862 20250704 13.5 4.0 483P-A/PANSTARRS MPEC 2024-R10 -0483P b 2027 11 10.5630 2.485004 0.222223 49.1686 199.2551 14.1870 20250704 17.0 4.0 483P-B/PANSTARRS MPEC 2025-MC0 -0484P 2028 03 10.6196 2.130381 0.432943 240.7993 265.3806 14.4743 20250704 16.0 4.0 484P/Spacewatch MPEC 2024-DD5 -0485P 2023 08 25.2222 3.992865 0.417180 196.1008 261.6446 10.0161 20250704 13.0 4.0 485P/Sheppard-Tholen MPEC 2024-JU4 -0486P 2025 04 3.8511 2.308971 0.363531 93.9465 219.0231 2.2095 20250704 14.5 4.0 486P/Leonard MPEC 2025-MC0 -0487P 2024 10 20.5896 1.814722 0.648449 0.8422 49.2030 39.3660 20250704 13.5 4.0 487P/SidingSpring MPEC 2025-MC0 -0488P 2024 05 19.5308 1.679241 0.551150 1.7356 323.9322 11.3751 20250704 16.5 4.0 488P/NEAT-PANSTARRS MPEC 2024-UA9 -0489P 2025 12 4.3315 1.561205 0.647145 109.4261 20.6089 4.0262 20250704 15.5 4.0 489P/Denning MPEC 2024-Q14 -0490P 2024 09 28.1771 1.069089 0.647169 332.5463 307.5996 12.2664 20250704 21.0 4.0 490P/ATLAS MPEC 2024-YC7 -0491P 2024 09 5.9963 3.716415 0.258693 298.8796 311.6842 9.3663 20250704 9.5 4.0 491P/Spacewatch-PANSTARRS MPEC 2025-MC0 -0492P 2024 07 20.4439 1.781954 0.690614 40.9829 11.3049 11.4011 20250704 15.0 4.0 492P/LINEAR MPEC 2025-MC0 -0493P 2026 01 14.0908 3.823245 0.466559 83.1990 1.1049 24.1114 20250704 12.0 2.0 493P/LONEOS MPC182893 -0494P 2024 05 30.9940 2.440513 0.356827 48.8798 245.0431 7.7900 20250704 16.0 4.0 494P/PANSTARRS MPEC 2024-RQ6 -0495P 2025 10 22.3683 3.459918 0.272564 141.3356 291.6171 26.3550 20250704 11.5 4.0 495P/Christensen MPEC 2025-A40 -0496P 2025 03 10.2745 1.621031 0.734208 42.2448 63.5862 14.8144 20250704 14.0 4.0 496P/Hill MPEC 2025-MC0 -0497P 2025 02 15.3076 2.075032 0.630437 32.4014 40.3711 10.4367 20250704 17.5 4.0 497P/Spacewatch-PANSTARRS MPC184421 -0498P 2024 12 18.9102 1.964332 0.572297 179.0800 279.2308 14.4828 20250704 14.7 4.0 498P/LINEAR MPC184421 -0499P 2025 03 4.3926 0.931058 0.691460 2.5578 139.3085 24.5822 20250704 18.5 4.0 499P/Catalina MPEC 2025-MC0 -0500P 2025 03 31.9455 2.131834 0.375864 46.6895 111.5277 2.3015 20250704 16.0 4.0 500P/PANSTARRS MPEC 2025-MC0 -0501P 2024 04 14.3035 0.671861 0.698452 53.6932 139.7800 10.0469 20250704 21.5 4.0 501P/Rankin MPC182882 -0502P 2025 08 5.0863 4.229499 0.471173 37.7414 264.4848 11.3996 20250704 8.5 4.0 502P/NEAT MPEC 2025-MC0 -0503P 2025 11 5.5669 1.897332 0.481312 17.9514 268.5821 10.5748 20250704 15.0 4.0 503P/PANSTARRS MPEC 2025-MC0 -0001I 2017 09 9.4886 0.255240 1.199252 241.6845 24.5997 122.6778 20170904 23.0 2.0 1I/`Oumuamua MPC107687 -0002I 2019 12 8.5548 2.006548 3.356633 209.1251 308.1480 44.0527 20191223 11.0 4.0 2I/Borisov MPEC 2023-L37 -0003I 2025 10 29.3067 1.368955 6.232602 127.8542 322.2298 175.1151 20250505 11.8 4.0 3I/ATLAS MPEC 2025-N35 From 4efc862ab99785f705a5c9c0736088e942bdb050 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 5 Jul 2025 23:51:26 +0100 Subject: [PATCH 070/253] Fix .gitignore to ignore astro_data/comets.txt --- .gitignore | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.gitignore b/.gitignore index b84121f2b..8e6aaf4e5 100644 --- a/.gitignore +++ b/.gitignore @@ -139,7 +139,7 @@ kicad/PiFinder/PiFinder-backups *.ps? config.json astro_data/hip_main.dat -comets.txt +astro_data/comets.txt # 3d printing business *.3mf From 44961cf80f3977a05b6bdc0c62de5e893d564764 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Sat, 12 Jul 2025 11:42:18 +0200 Subject: [PATCH 071/253] Correct spelling in comments --- python/PiFinder/pointing_model/pointing_model.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/python/PiFinder/pointing_model/pointing_model.py b/python/PiFinder/pointing_model/pointing_model.py index c31fdd438..0edb12d6c 100644 --- a/python/PiFinder/pointing_model/pointing_model.py +++ b/python/PiFinder/pointing_model/pointing_model.py @@ -169,7 +169,7 @@ def update_imu(self, q_x2imu: quaternion.quaternion): """ Update the state with the raw IMU measurement. Does a dead-reckoning - estiamte of the camera and scope pointing. + estimate of the camera and scope pointing. INPUTS: q_x2imu: Quaternion of the IMU orientation w.r.t. an unknown and drifting From 733a3493049f33c0ca84fd528f4d83daaab6a6cc Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Sat, 12 Jul 2025 11:47:09 +0200 Subject: [PATCH 072/253] Update README. Tested and runs OK. Reproduces functionality of the existing system. --- python/PiFinder/pointing_model/README.md | 86 +++++++++++++++++------- 1 file changed, 63 insertions(+), 23 deletions(-) diff --git a/python/PiFinder/pointing_model/README.md b/python/PiFinder/pointing_model/README.md index 5f07ef0f3..0023a1f9a 100644 --- a/python/PiFinder/pointing_model/README.md +++ b/python/PiFinder/pointing_model/README.md @@ -185,16 +185,17 @@ the horizontal frame from the *home* position to the current pointing. ### Plate solving -Plate solving returns the pointing of the PiFinder camera in RA/Dec coordinates -which can be converted to the quaternion rotation $q_{hor2cam}$. Plate solving -also returns the roll but this is less accurate. For this reason, we will will -initially assume a perfect altaz mount and infer the roll from the geometry of -a perfect altaz mount at the given RA/Dec coordinates. +Plate solving returns the pointing of the PiFinder camera in RA/Dec/Roll +coordinates which can be converted to the quaternion rotation $q_{hor2cam}$. -The offset $q_{cam2scope}$ between the PiFinder camera frame and the scope -frame is determined during alignment of the PiFinder with the scope. Assuming -that this offset is constant, we can infer the pointing of the scope at time -step $k$: +Plate solving also returns the roll but this is probably less accurate. For +this reason, we will will initially assume a perfect altaz mount with the +PiFinder mounted upright. + +The alignment offset $q_{cam2scope}$ between the PiFinder camera frame and the +scope frame is determined during alignment of the PiFinder with the scope. +Assuming that this offset is constant, we can infer the pointing of the scope +at time step $k$: $$q_{hor2scope}(k) = q_{hor2cam}(k) \; q_{cam2scope}$$ @@ -224,7 +225,7 @@ Rearranging this gives, $$q_{cam2scope} = q_{hor2cam}^{-1}(k) \; q_{hor2scope}(k)$$ Note that for unit quaternions, we can also use the conjugate $q^*$ instead of -$q^{-1}$, which is slightly faster to compute. +$q^{-1}$, because the conjugate is slightly faster to compute. Some scopes and focusers can be rotated around its axis which also rotates the PiFinder with it. This would currently require a re-alignment. @@ -233,16 +234,20 @@ PiFinder with it. This would currently require a re-alignment. Between plate solving, the IMU extrapolates the scope orientation by dead reckoning. Suppose that at the $k$ th time step, plate solves finds the camera -pointing, $q_{hor2cam}(k)$. It can be related to the IMU measurement by, +pointing, $q_{hor2cam}(k)$. It can be related to the IMU measurement +$q_{x2imu}(k)$ by, $$q_{hor2cam}(k) = q_{hor2x}(k) \; q_{x2imu}(k) \; q_{imu2cam}$$ The IMU outputs its orientation $q_{x2imu}$ relative to a frame $X$ which is similar to the horizontal frame but drifts over time; in particular, it will -drift rotating around the $z_{hor}$ axis because the IMU with just -accelerometer/gyro fusion has no means to determine the bearing. $q_{imu2cam}$ -rotates the IMU frame to the scope frame. It depends on the PiFinder type and -is assumed to be fixed and can be estimated during alignment. +predominantly drift by rotating around the $z_{hor}$ axis because the IMU with +just accelerometer/gyro fusion has no means to determine the bearing. +$q_{imu2cam}$ rotates the IMU frame to the scope frame. It depends on the +PiFinder type and is assumed to be fixed. Because of small errors in the +alignmet of the IMU relative to the camera, there will be errors that will not +be captured by the preset $q_{imu2cam}$. This will introduce errors in the +dead-reckoning. The drift $q_{hor2x}$ is unknown but it drifts slowly enough that we can assume that it will be constant between successive plate solves. @@ -262,17 +267,28 @@ of the scope pointing; $$q_{hor2scope}(k + l) = \hat{q}_{hor2cam}(k + l) \; q_{cam2scope}$$ -### Notable features +## Next steps in the development + +The current implementation reproduces the existing functionality of the +PiFinder. The phase are: + +1. Reproduce PiFinder functionality using quaternion transformaitons for altaz + mounts. [Done] +2. Enable PiFinder to be mounted at any angle, not just upright. +3. Extend to equatorial mount. +4. Enable scopes to be rotated (i.e. rotate the PiFinder around the axis of the + scope). -Because we use full 3D rotation and calibrate the IMU's unknown reference frame -every plate solve, we don't need to set the rotation between the camera and IMU -frame (in the old system, this was done by setting the PiFinder type). +### Approach to support general PiFinder mounting angle -This approach will probably allow us to relax the requirement that the PiFinder -has to be upright. It should work even if it's mounted at an angle but this -hasn't been tested. +Currently, we do not use the roll measurement in the alignment of the PiFinder +with the scope; $q_{cam2scope}$ only rotates in the alt/az directions. By using +the roll measurement, we will also account for rotation of the PiFinder around +the scope axis. This should (probably) enable the PiFinder to be mounted at any +angle rotated around the scope axis. -## Approach for equatorial mounts + +### Approach for equatorial mounts It should be possible to take a similar approach for an equatorial mounts. @@ -280,3 +296,27 @@ One issue is that it's common to rotate EQ-mounteed scopes (particularly Newtoninans) around its axis so that the eyepiece is at a comfortable position. As mentioned in the alignment section, this would require a re-alignment. That would need to be resolved in a future step. + +#### Future improvements + +The next step would be to use a Kalman filter framework to estimate the +pointing. Some of the benefits are: + +* Smoother, filtered pointing estimate. +* Improve the accuracy of the pointing estimate (possibly more beneficial when + using the PiFinder estimate to control driven mounts). +* Potentially enable any generic IMU (with gyro and accelerometer) to be used + without internal fusion FW, which tends to add to the BOM cost. +* If required, could take fewer plate-solving frames by only triggering a plate +solve when the uncertainty of the Kalman filter estimate based on IMU +dead-reckoning exceeds some limit. + +The accuracy improvement will come from the following sources: + +* Filtering benefits from the averaging effects of using multiple measurements. +* The Kalman filter will estimate the accelerometer and gyro bias online. The +calibration will be done in conjunction with the plate-solved measurements so +it will be better than an IMU-only calibration. +* The orientation of the IMU to the camera frame, $q_{imu2cam}$, has errors +because of alignment errors. The Kalman filter will calibrate for this online. +This will improve the accuracy and enable other non-standard form-factors. From 5626e656404758a949ff59614a43f522f3b067db Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Sat, 12 Jul 2025 11:50:45 +0200 Subject: [PATCH 073/253] Add __init__.py to pointing_model/ --- python/PiFinder/pointing_model/__init__.py | 0 1 file changed, 0 insertions(+), 0 deletions(-) create mode 100644 python/PiFinder/pointing_model/__init__.py diff --git a/python/PiFinder/pointing_model/__init__.py b/python/PiFinder/pointing_model/__init__.py new file mode 100644 index 000000000..e69de29bb From e5b5409ba999eadbe6bdb6b6f3b944ed858182b7 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Fri, 18 Jul 2025 21:58:18 +0200 Subject: [PATCH 074/253] Refactor: Define axis_angle2quat() --- .../PiFinder/pointing_model/pointing_model.py | 20 +++++++++++++++++-- 1 file changed, 18 insertions(+), 2 deletions(-) diff --git a/python/PiFinder/pointing_model/pointing_model.py b/python/PiFinder/pointing_model/pointing_model.py index 0edb12d6c..ebdfd2fcc 100644 --- a/python/PiFinder/pointing_model/pointing_model.py +++ b/python/PiFinder/pointing_model/pointing_model.py @@ -22,6 +22,21 @@ import quaternion +def axis_angle2quat(axis, theta): + """ + Convert from axis-angle representation to a quaternion + + INPUTS: + axis: (3,) Axis of rotation (doesn't need to be a unit vector) + angle: Angle of rotation [rad] + """ + assert(len(axis) == 3, 'axis should be a list or numpy array of length 3.') + v = np.linalg.norm(axis) * np.sin(theta / 2) + + return np.quaternion(np.cos(theta / 2), v[0], v[1], v[2]) + + + def get_q_hor2frame(az, alt): """ Returns the quaternion to rotate from the horizontal frame to the frame @@ -31,8 +46,9 @@ def get_q_hor2frame(az, alt): az: [rad] Azimuth of scope axis alt: [rad] Alt of scope axis """ - return np.quaternion(np.cos(-(az + np.pi/2) / 2), 0, 0, np.sin(-(az + np.pi/2) / 2)) \ - * np.quaternion(np.cos((np.pi / 2 - alt) / 2), np.sin((np.pi / 2 - alt) / 2), 0, 0) + q_az = axis_angle2quat([0, 0, 1], -(az + np.pi / 2)) + q_alt = axis_angle2quat([1, 0, 0], (np.pi / 2 - alt)) + return q_az * q_alt def get_azalt_of_q_hor2frame(q_hor2frame): From 6343fddb2107ab0d224623fa411d89ccbe6da4fa Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Sat, 19 Jul 2025 00:02:54 +0200 Subject: [PATCH 075/253] Update README --- python/PiFinder/pointing_model/README.md | 21 +++++++++++++++++++++ 1 file changed, 21 insertions(+) diff --git a/python/PiFinder/pointing_model/README.md b/python/PiFinder/pointing_model/README.md index 0023a1f9a..e8cd2c7c3 100644 --- a/python/PiFinder/pointing_model/README.md +++ b/python/PiFinder/pointing_model/README.md @@ -161,6 +161,22 @@ We define the following reference frames: * $+z$ is the boresight of the camera, $+y$ and $+x$ are respectively the vertical and horizontal (to the left) directions of the camera. +## Roll + +The roll (as given by Tetra3) is defined as the rotation of the north pole +relative to the camera image's "up" direction ($+y$). A positive roll angle +means that the pole is counter-clockwise from image "up". The roll offset is +defined as + +``` +roll_offset = camera_roll - expected_camera_roll +``` + +The `expected_camera_roll` is the roll at the camera center given its +plate-solved RA and Dec for a camera on a perfect horizontal mount (i.e. the +"up" $+y$ direction of the camera always points to the zenith). The camera pose +is rotated by the angle `roll_offset` around its boresight. + ## Telescope coordinate transformations **TO EDIT...** @@ -202,6 +218,11 @@ $$q_{hor2scope}(k) = q_{hor2cam}(k) \; q_{cam2scope}$$ We will use the PiFinder's camera frame as the reference because plate solving is done relative to the camera frame. +The quaternion $q_{hor2cam}$ represents the orientation of the PiFinder camera +relative to the Horizontal frame. Using the axis-angle interpretation, the axis +points along the altaz of the camera center and rotated by the roll offset +(explained above). + ### Alignment As already mentioned, the alignment of the PiFinder determines $q_{cam2scope}$ From 52915eef342cfb8db66449d1d4b26574d0f87a96 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Sat, 19 Jul 2025 00:03:13 +0200 Subject: [PATCH 076/253] First attempt at non-upright support using roll offset --- python/PiFinder/integrator.py | 3 ++- python/PiFinder/pointing_model/pointing_model.py | 14 +++++++++++--- 2 files changed, 13 insertions(+), 4 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index ddfae214b..22df835f1 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -338,6 +338,7 @@ def update_plate_solve_and_imu__degrees(pointing_tracker, solved): # Convert to radians: solved_cam_az = np.deg2rad(solved["camera_center"]["Az"]) solved_cam_alt = np.deg2rad(solved["camera_center"]["Alt"]) + solved_cam_roll_offset = np.deg2rad(solved["Roll_offset"]) # Update: pointing_tracker.update_plate_solve_and_imu( - solved_cam_az, solved_cam_alt, q_x2imu) + solved_cam_az, solved_cam_alt, solved_cam_roll_offset, q_x2imu) diff --git a/python/PiFinder/pointing_model/pointing_model.py b/python/PiFinder/pointing_model/pointing_model.py index ebdfd2fcc..27fdc0021 100644 --- a/python/PiFinder/pointing_model/pointing_model.py +++ b/python/PiFinder/pointing_model/pointing_model.py @@ -152,6 +152,7 @@ def set_alignment(self, def update_plate_solve_and_imu(self, solved_cam_az: Union[float, None], solved_cam_alt: Union[float, None], + solved_cam_roll_offset: Union[float, None], q_x2imu: Union[quaternion.quaternion, None]): """ Update the state with the az/alt measurements from plate solving in the @@ -162,15 +163,22 @@ def update_plate_solve_and_imu(self, INPUTS: solved_cam_az: [rad] Azimuth of the camera pointing from plate solving. solved_cam_alt: [rad] Alt of the camera pointing from plate solving. + solved_cam_roll_offset: [rad] Roll offset of the camera frame +y ("up") + relative to the pole. q_x2imu: [quaternion] Raw IMU measurement quaternions. This is the IMU frame orientation wrt unknown drifting reference frame X. """ - # Currently assumes that the camera is right way up on a perfect - # altaz mount. TODO: Generalize to rotated camera if (solved_cam_az is None) or (solved_cam_alt is None): return # No update else: - self.q_hor2cam = get_q_hor2frame(solved_cam_az, solved_cam_alt).normalized() + # Camera frame relative to the horizontal frame where the +y camera + # frame (i.e. "up") points to zenith: + q_hor2cam_up = get_q_hor2frame(solved_cam_az, solved_cam_alt) + # Account for camera rotation around the +z camera frame + q_cam_rot_z = np.quaternion(np.cos(solved_cam_roll_offset / 2), + 0, 0, np.sin(solved_cam_roll_offset / 2)) + # Combine (intrinsic rotation) + self.q_hor2cam = (q_hor2cam_up * q_cam_rot_z).normalized() self.dead_reckoning = False # Calculate the IMU's unknown reference frame X using the plate solved From 4b6bd1e0d03bc429d5700636649c6e0c3d811a8b Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Fri, 18 Jul 2025 23:20:59 +0100 Subject: [PATCH 077/253] Fix bug -runs on PiFinder in simulation mode --- python/PiFinder/pointing_model/pointing_model.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/python/PiFinder/pointing_model/pointing_model.py b/python/PiFinder/pointing_model/pointing_model.py index 27fdc0021..0cb4668bb 100644 --- a/python/PiFinder/pointing_model/pointing_model.py +++ b/python/PiFinder/pointing_model/pointing_model.py @@ -31,7 +31,8 @@ def axis_angle2quat(axis, theta): angle: Angle of rotation [rad] """ assert(len(axis) == 3, 'axis should be a list or numpy array of length 3.') - v = np.linalg.norm(axis) * np.sin(theta / 2) + # Define the vector part of the quaternion + v = np.array(axis) / np.linalg.norm(axis) * np.sin(theta / 2) return np.quaternion(np.cos(theta / 2), v[0], v[1], v[2]) From fa008f497d4603bfa9a38957cff87b82c40f5c05 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Sun, 10 Aug 2025 13:54:33 +0200 Subject: [PATCH 078/253] Update README with EQ approach --- python/PiFinder/pointing_model/README.md | 49 ++++++++++++++++++++---- 1 file changed, 42 insertions(+), 7 deletions(-) diff --git a/python/PiFinder/pointing_model/README.md b/python/PiFinder/pointing_model/README.md index e8cd2c7c3..18149b96e 100644 --- a/python/PiFinder/pointing_model/README.md +++ b/python/PiFinder/pointing_model/README.md @@ -130,6 +130,12 @@ corresponds to the axis of the scope in the *home* position in the ideal case. We define the following reference frames: + +#### Equatorial coordinate system +* Centered around the center of the Earth with the $xy$ plane running through + the Earths' equator. $+z$ points to the north pole and $+x$ to the Vernal + equinox. + #### Horizontal coordinate system * Centred around the observer. We will use the convention: * $x$ points South, $y$ to East and $z$ to the zenith. @@ -165,8 +171,8 @@ We define the following reference frames: The roll (as given by Tetra3) is defined as the rotation of the north pole relative to the camera image's "up" direction ($+y$). A positive roll angle -means that the pole is counter-clockwise from image "up". The roll offset is -defined as +means that the pole is counter-clockwise from image "up" (i.e. towards West). +The roll offset is defined as ``` roll_offset = camera_roll - expected_camera_roll @@ -177,13 +183,11 @@ plate-solved RA and Dec for a camera on a perfect horizontal mount (i.e. the "up" $+y$ direction of the camera always points to the zenith). The camera pose is rotated by the angle `roll_offset` around its boresight. -## Telescope coordinate transformations - -**TO EDIT...** +## Telescope coordinate transformations and dead-reckoning using the IMU We will use quaternions to rotate between the coordinate frames. For example, the quaternion `q_horiz2mnt` rotates the Horizontal frame to the Mount frame. -The quaternions can be multiplied to apply successive intrinsic rotation from +The quaternions can be multiplied to apply successive *intrinsic* rotation from the Horizontal frame to the Camera; ```python @@ -193,7 +197,7 @@ q_horiz2camera = q_horiz2mnt * q_mnt2gimb * q_gimb2scope * q_scope2camera `q_mnt2gimb` depends on the gimbal angles, which is what we can control to move the scope. -## Coordinate frame transformation for altaz mounts +## Coordinate frame transformation for altaz mounts *(remove functionality?)* During normal operation, we want to find the pointing of the scope, expressed using $q_{hor2scope}$, which is the quaternion that rotates the scope axis in @@ -287,6 +291,37 @@ of the scope pointing; $$q_{hor2scope}(k + l) = \hat{q}_{hor2cam}(k + l) \; q_{cam2scope}$$ +## Coordinate frame transformation using equatorial coordinates + +We can also use the equatorial frame as the reference, using (RA, Dec, Roll) +from the PiFinder camera as the inputs without the need to convert to altaz +coordinates. + +The pointing of the scope at time step `k` using IMU dead-reckoning is given by + +```python +q_eq2scope(k) = q_eq2cam(k-m) * q_cam2imu * q_x2imu(k-m).conj() * q_x2imu(k) * q_imu2cam * q_cam2scope +``` + +Where +1. `k` represents the current time step and `k-m` represents the time step + where we had a last solve. +2. `q_x2imu(k)` is the current IMU measurement quaternion w.r.t its own + drifting reference frame `x`. +3. Note that the quaternion `q_x2imu(k-m).conj() * q_x2imu(k)` rotates the IMU + body from the orientation in the last solve (at time step `k-m`) to to the + current orientation (at time step `k`). +4. `q_cam2imu = q_imu2cam.conj()` is the alignment of the IMU to the camera and +depends on the PiFinder configuration. There will be some error in this which +will propagate to the pointing error when using the IMU. + +We can pre-compute the first three terms after plate solving at time step +`k-m`, which corresponds to the quaternion rotation from the `eq` frame to the +IMU's reference frame `x`. + +```python +q_eq2x(k-m) = q_eq2cam(k-m) * q_cam2imu * q_x2imu(k-m).conj() +``` ## Next steps in the development From e692a454f4c29e57f96efc10075e096b0943c0c8 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Sun, 10 Aug 2025 13:55:08 +0200 Subject: [PATCH 079/253] Move helper functions to quaternion_transforms.py --- .../PiFinder/pointing_model/pointing_model.py | 90 ++----------------- .../pointing_model/quaternion_transforms.py | 90 +++++++++++++++++++ 2 files changed, 99 insertions(+), 81 deletions(-) create mode 100644 python/PiFinder/pointing_model/quaternion_transforms.py diff --git a/python/PiFinder/pointing_model/pointing_model.py b/python/PiFinder/pointing_model/pointing_model.py index 0cb4668bb..a5af60c45 100644 --- a/python/PiFinder/pointing_model/pointing_model.py +++ b/python/PiFinder/pointing_model/pointing_model.py @@ -1,89 +1,17 @@ """ Pointing model functions. -The quaternions use the notation in the form `q_a2b` for a quaternion that -rotates frame `a` to frame `b` using intrinsic rotation (by post-multiplying the -quaternions). For example: +See `quaternion_transforms.py` for explanations and conventions for +quaternions. -q_a2c = q_a2b * q_a2c - -NOTE: - -* All angles are in radians. -* The quaternions use numpy quaternions and are scalar-first. -* Some of the constant quaternion terms can be speeded up by not using -trigonometric functions. -* The methods do not normalize the quaternions because this incurs a small -computational overhead. Normalization should be done manually as and when -necessary. +NOTE: All angles are in radians. """ -from typing import Union # When updated to Python 3.10+, remove and use new type hints + import numpy as np import quaternion +from typing import Union # When updated to Python 3.10+, remove and use new type hints - -def axis_angle2quat(axis, theta): - """ - Convert from axis-angle representation to a quaternion - - INPUTS: - axis: (3,) Axis of rotation (doesn't need to be a unit vector) - angle: Angle of rotation [rad] - """ - assert(len(axis) == 3, 'axis should be a list or numpy array of length 3.') - # Define the vector part of the quaternion - v = np.array(axis) / np.linalg.norm(axis) * np.sin(theta / 2) - - return np.quaternion(np.cos(theta / 2), v[0], v[1], v[2]) - - - -def get_q_hor2frame(az, alt): - """ - Returns the quaternion to rotate from the horizontal frame to the frame - (typically scope) at coordinates (az, alt) for an ideal AltAz mount. - - INPUTS: - az: [rad] Azimuth of scope axis - alt: [rad] Alt of scope axis - """ - q_az = axis_angle2quat([0, 0, 1], -(az + np.pi / 2)) - q_alt = axis_angle2quat([1, 0, 0], (np.pi / 2 - alt)) - return q_az * q_alt - - -def get_azalt_of_q_hor2frame(q_hor2frame): - """ - Returns the (az, alt) pointing of the frame which is defined by the z axis - of the q_hor2frame quaternion. - - RETURNS: - az: [rad] - alt: [rad] - """ - pz = np.quaternion(0, 0, 0, 1) # Vector z represented as a pure quaternion - frame_axis = q_hor2frame * pz * q_hor2frame.conj() # Returns a pure quaternion along scope axis - - alt = np.pi / 2 - np.arccos(frame_axis.z) - az = np.pi - np.arctan2(frame_axis.y, frame_axis.x) - - return az, alt - - -def get_quat_angular_diff(q1, q2): - """ - Calculates the relative rotation between quaternions `q1` and `q2`. - Accounts for the double-cover property of quaternions so that if q1 and q2 - are close, you get small angle d_theta rather than something around 2 * np.pi. - """ - dq = q1.conj() * q2 - d_theta = 2 * np.arctan2(np.linalg.norm(dq.vec), dq.w) # atan2 is more robust than using acos - - # Account for double cover where q2 = -q1 gives d_theta = 2 * pi - if d_theta > np.pi: - d_theta = 2 * np.pi - d_theta - - return d_theta # In radians +import quaternion_transforms as qt class ImuDeadReckoning(): @@ -115,7 +43,7 @@ class ImuDeadReckoning(): # Dead-reckoning using IMU pointing_tracker.update_imu(q_x2imu) q_hor2scope = pointing_tracker.get_q_hor2scope() - az, alt = get_azalt_of_q_hor2frame(q_hor2scope) + az, alt = pointing_tracker.get_cam_azalt() """ def __init__(self, screen_direction): @@ -174,7 +102,7 @@ def update_plate_solve_and_imu(self, else: # Camera frame relative to the horizontal frame where the +y camera # frame (i.e. "up") points to zenith: - q_hor2cam_up = get_q_hor2frame(solved_cam_az, solved_cam_alt) + q_hor2cam_up = qt.get_q_hor2frame(solved_cam_az, solved_cam_alt) # Account for camera rotation around the +z camera frame q_cam_rot_z = np.quaternion(np.cos(solved_cam_roll_offset / 2), 0, 0, np.sin(solved_cam_roll_offset / 2)) @@ -222,7 +150,7 @@ def get_cam_azalt(self): indicate if the estimate is from dead-reckoning (True) or from plate solving (False). """ - az_cam, alt_cam = get_azalt_of_q_hor2frame(self.q_hor2cam) + az_cam, alt_cam = qt.get_azalt_of_q_hor2frame(self.q_hor2cam) return az_cam, alt_cam, self.dead_reckoning # Angles are in radians def get_scope_azalt(self): diff --git a/python/PiFinder/pointing_model/quaternion_transforms.py b/python/PiFinder/pointing_model/quaternion_transforms.py new file mode 100644 index 000000000..2fe81bd3f --- /dev/null +++ b/python/PiFinder/pointing_model/quaternion_transforms.py @@ -0,0 +1,90 @@ +""" +Quaternion transformations + +For quaternions, we use the notation `q_a2b`. This represents a quaternion that +rotates frame `a` to frame `b` using intrinsic rotation (by post-multiplying +the quaternions). This notation makes makes chains of intrinsic rotations +simple and clear. For example, this gives a quaternion `q_a2c` that rotates +from frame `a` to frame `c`: + +q_a2c = q_a2b * q_a2c + +NOTE: + +* All angles are in radians. +* The quaternions use numpy quaternions and are scalar-first. +* Some of the constant quaternion terms can be speeded up by not using +trigonometric functions. +* The methods do not normalize the quaternions because this incurs a small +computational overhead. Normalization should be done manually as and when +necessary. +""" + +from typing import Union # When updated to Python 3.10+, remove and use new type hints +import numpy as np +import quaternion + + +def axis_angle2quat(axis, theta): + """ + Convert from axis-angle representation to a quaternion + + INPUTS: + axis: (3,) Axis of rotation (doesn't need to be a unit vector) + angle: Angle of rotation [rad] + """ + assert len(axis) == 3, 'axis should be a list or numpy array of length 3.' + # Define the vector part of the quaternion + v = np.array(axis) / np.linalg.norm(axis) * np.sin(theta / 2) + + return np.quaternion(np.cos(theta / 2), v[0], v[1], v[2]) + + +def get_quat_angular_diff(q1, q2): + """ + Calculates the relative rotation between quaternions `q1` and `q2`. + Accounts for the double-cover property of quaternions so that if q1 and q2 + are close, you get small angle d_theta rather than something around 2 * np.pi. + """ + dq = q1.conj() * q2 + d_theta = 2 * np.arctan2(np.linalg.norm(dq.vec), dq.w) # atan2 is more robust than using acos + + # Account for double cover where q2 = -q1 gives d_theta = 2 * pi + if d_theta > np.pi: + d_theta = 2 * np.pi - d_theta + + return d_theta # In radians + + +# ========== Horizontal (altaz) frame functions ============================ + +def get_q_hor2frame(az, alt): + """ + Returns the quaternion to rotate from the horizontal frame to the frame + (typically scope) at coordinates (az, alt) for an ideal AltAz mount. + + INPUTS: + az: [rad] Azimuth of scope axis + alt: [rad] Alt of scope axis + """ + q_az = axis_angle2quat([0, 0, 1], -(az + np.pi / 2)) + q_alt = axis_angle2quat([1, 0, 0], (np.pi / 2 - alt)) + return q_az * q_alt + + +def get_azalt_of_q_hor2frame(q_hor2frame): + """ + Returns the (az, alt) pointing of the frame which is defined by the z axis + of the q_hor2frame quaternion. + + RETURNS: + az: [rad] + alt: [rad] + """ + pz = np.quaternion(0, 0, 0, 1) # Vector z represented as a pure quaternion + frame_axis = q_hor2frame * pz * q_hor2frame.conj() # Returns a pure quaternion along scope axis + + alt = np.pi / 2 - np.arccos(frame_axis.z) + az = np.pi - np.arctan2(frame_axis.y, frame_axis.x) + + return az, alt From 9bc3b402633e61679a911e7bbda5058351d9029e Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Sun, 10 Aug 2025 13:55:48 +0200 Subject: [PATCH 080/253] Update name space of quaternion functions --- python/PiFinder/camera_interface.py | 4 ++-- python/PiFinder/integrator.py | 6 ++++-- 2 files changed, 6 insertions(+), 4 deletions(-) diff --git a/python/PiFinder/camera_interface.py b/python/PiFinder/camera_interface.py index c9c973eea..7b40ad71c 100644 --- a/python/PiFinder/camera_interface.py +++ b/python/PiFinder/camera_interface.py @@ -19,7 +19,7 @@ import logging from PiFinder import state_utils, utils -import PiFinder.pointing_model.pointing_model as pointing +import PiFinder.pointing_model.quaternion_transforms as qt logger = logging.getLogger("Camera.Interface") @@ -128,7 +128,7 @@ def get_image_loop( # Returns the pointing difference between successive IMU quaternions as # an angle (radians). Note that this also accounts for rotation around the # scope axis. Returns an angle in radians. - pointing_diff = pointing.get_quat_angular_diff( + pointing_diff = qt.get_quat_angular_diff( imu_start["quat"], imu_end["quat"]) camera_image.paste(base_image) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 22df835f1..ba7d42020 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -19,6 +19,8 @@ import PiFinder.calc_utils as calc_utils from PiFinder.multiproclogging import MultiprocLogging import PiFinder.pointing_model.pointing_model as pointing +import PiFinder.pointing_model.quaternion_transforms as qt + IMU_ALT = 2 IMU_AZ = 0 @@ -203,7 +205,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr # If we have alt, then we have a position/time # TODO: For debugging -- remove later - if prev_imu is None or pointing.get_quat_angular_diff(prev_imu, imu["quat"]) > 1E-4: + if prev_imu is None or qt.get_quat_angular_diff(prev_imu, imu["quat"]) > 1E-4: print("Quat: ", imu["quat"]) prev_imu = imu["quat"].copy() @@ -211,7 +213,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr # When moving, switch to tracking using the IMU #if imu_moved(lis_imu, imu_pos): assert isinstance(imu["quat"] , quaternion.quaternion), "Expecting quaternion.quaternion type" # TODO: Remove later - angle_moved = pointing.get_quat_angular_diff(last_image_solve["imu_quat"], imu["quat"]) + angle_moved = qt.get_quat_angular_diff(last_image_solve["imu_quat"], imu["quat"]) if angle_moved > imu_moved_ang_threshold: # Estimate camera pointing using IMU dead-reckoning logger.debug("Track using IMU. Angle moved since last_image_solve = {:} (> threshold = {:})".format(np.rad2deg(angle_moved), np.rad2deg(imu_moved_ang_threshold))) From c201a761095dd301df0ca75df018a36389ad9a0f Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Sun, 10 Aug 2025 14:04:33 +0200 Subject: [PATCH 081/253] Move ImuDeadReckoning to imu_dead_reckoning.py --- python/PiFinder/integrator.py | 4 ++-- .../{pointing_model.py => imu_dead_reckoning.py} | 10 +++++----- 2 files changed, 7 insertions(+), 7 deletions(-) rename python/PiFinder/pointing_model/{pointing_model.py => imu_dead_reckoning.py} (97%) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index ba7d42020..9c9c22b26 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -18,7 +18,7 @@ from PiFinder import state_utils import PiFinder.calc_utils as calc_utils from PiFinder.multiproclogging import MultiprocLogging -import PiFinder.pointing_model.pointing_model as pointing +from PiFinder.pointing_model.imu_dead_reckoning import ImuDeadReckoningHoriz import PiFinder.pointing_model.quaternion_transforms as qt @@ -99,7 +99,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr imu_moved_ang_threshold = np.deg2rad(0.1) # Use IMU tracking if the angle moved is above this # Set up dead-reckoning tracking by the IMU: - pointing_tracker = pointing.ImuDeadReckoning(cfg.get_option("screen_direction")) + pointing_tracker = ImuDeadReckoningHoriz(cfg.get_option("screen_direction")) #pointing_tracker.set_alignment(q_scope2cam) # TODO: Enable when q_scope2cam is available # This holds the last image solve position info diff --git a/python/PiFinder/pointing_model/pointing_model.py b/python/PiFinder/pointing_model/imu_dead_reckoning.py similarity index 97% rename from python/PiFinder/pointing_model/pointing_model.py rename to python/PiFinder/pointing_model/imu_dead_reckoning.py index a5af60c45..9c4d5582c 100644 --- a/python/PiFinder/pointing_model/pointing_model.py +++ b/python/PiFinder/pointing_model/imu_dead_reckoning.py @@ -1,21 +1,21 @@ """ Pointing model functions. -See `quaternion_transforms.py` for explanations and conventions for -quaternions. +See quaternion_transforms.py for conventions used for quaternions. NOTE: All angles are in radians. """ - +from typing import Union # When updated to Python 3.10+, remove and use new type hints import numpy as np import quaternion -from typing import Union # When updated to Python 3.10+, remove and use new type hints import quaternion_transforms as qt -class ImuDeadReckoning(): +class ImuDeadReckoningHoriz(): """ + Dead reckoning tracking using the IMU - wrt Horizontal frame + Use the plate-solved coordinates and IMU measurements to estimate the pointing using plate solving when available or dead-reckoning using the IMU when plate solving isn't available (e.g. when the scope is moving or From 3c63e708899dc833ab5d27fa82c0293a1f6ef32b Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 10 Aug 2025 13:22:03 +0100 Subject: [PATCH 082/253] Fix import of custome package --- python/PiFinder/pointing_model/imu_dead_reckoning.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/python/PiFinder/pointing_model/imu_dead_reckoning.py b/python/PiFinder/pointing_model/imu_dead_reckoning.py index 9c4d5582c..e31f06110 100644 --- a/python/PiFinder/pointing_model/imu_dead_reckoning.py +++ b/python/PiFinder/pointing_model/imu_dead_reckoning.py @@ -9,7 +9,7 @@ import numpy as np import quaternion -import quaternion_transforms as qt +import PiFinder.pointing_model.quaternion_transforms as qt class ImuDeadReckoningHoriz(): From d4d3cf47ae06c8ebb1b6b690db23850e8edf18b5 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 10 Aug 2025 15:01:06 +0100 Subject: [PATCH 083/253] Add ImuDeadReckoningEq and associated funcs for EQ frame --- .../pointing_model/imu_dead_reckoning.py | 176 ++++++++++++++++++ .../pointing_model/quaternion_transforms.py | 43 +++++ 2 files changed, 219 insertions(+) diff --git a/python/PiFinder/pointing_model/imu_dead_reckoning.py b/python/PiFinder/pointing_model/imu_dead_reckoning.py index e31f06110..0802be049 100644 --- a/python/PiFinder/pointing_model/imu_dead_reckoning.py +++ b/python/PiFinder/pointing_model/imu_dead_reckoning.py @@ -179,3 +179,179 @@ def _set_screen_direction(self, screen_direction: str): self.q_imu2cam = self.q_imu2cam.normalized() self.q_cam2imu = self.q_imu2cam.conj() + + +# ==== Equatorial frame version ==== + + +class ImuDeadReckoningEqFrame(): + """ + Use the plate-solved coordinates and IMU measurements to estimate the + pointing using plate solving when available or dead-reckoning using the IMU + when plate solving isn't available (e.g. when the scope is moving or + between frames). + + This class uses the Equatorial frame as the reference and expect plate-solved + coordinates in (ra, dec). + + All angles are in radians. + + HOW IT WORKS: + + EXAMPLE: + # Set up: + pointing_tracker = ImuDeadReckoningEqFrame('flat') + pointing_tracker.set_alignment(q_scope2cam) + + # Update with plate solved and IMU data: + pointing_tracker.update_plate_solve_and_imu(solved_cam_ra, solved_cam_dec, solved_cam_roll, q_x2imu) + + # Dead-reckoning using IMU + pointing_tracker.update_imu(q_x2imu) + """ + + def __init__(self, screen_direction): + """ """ + # Alignment: + self.q_scope2cam = None # ****Do we need this?? + self.q_cam2scope = None + # IMU orientation: + self.q_imu2cam = None + self.q_cam2imu = None + # IMU-to-camera orientation. Fixed by PiFinder type + self._set_screen_direction(screen_direction) + # Putting them together: + self.q_imu2scope = None + + # The poinging of the camera and scope frames wrt the Equatorial frame. + # These get updated by plate solving and IMU dead-reckoning. + self.q_eq2cam = None # ***Do we need to keep q_eq2cam? + + # True when q_eq2cam is estimated by IMU dead-reckoning. + # False when set by plate solving + self.dead_reckoning = False + + # The IMU's unkonwn drifting reference frame X. This is solved for + # every time we have a simultaneous plate solve and IMU measurement. + self.q_eq2x = None + + def set_alignment(self, + q_scope2cam: quaternion.quaternion): + """ + Set the alignment between the PiFinder camera center and the scope + pointing. + + INPUTS: + q_scope2cam: Quaternion that rotates the scope frame to the camera frame. + """ + self.q_scope2cam = q_scope2cam.normalized() + self.q_cam2scope = self.q_scope2cam.conj() + self.q_imu2scope = self.q_imu2cam * self.q_cam2scope + + def update_plate_solve_and_imu(self, + solved_cam_ra: Union[float, None], + solved_cam_dec: Union[float, None], + solved_cam_roll: Union[float, None], + q_x2imu: Union[quaternion.quaternion, None]): + """ + Update the state with the az/alt measurements from plate solving in the + camera frame. If the IMU measurement (which should be taken at the same + time) is available, q_x2imu (the unknown drifting reference frame) will + be solved for. + + INPUTS: + solved_cam_az: [rad] Azimuth of the camera pointing from plate solving. + solved_cam_alt: [rad] Alt of the camera pointing from plate solving. + solved_cam_roll_offset: [rad] Roll offset of the camera frame +y ("up") + relative to the pole. + q_x2imu: [quaternion] Raw IMU measurement quaternions. This is the IMU + frame orientation wrt unknown drifting reference frame X. + """ + if (solved_cam_ra is None) or (solved_cam_dec is None): + return # No update + else: + # Update plate-solved coord: + # Camera frame relative to the Equatorial frame where the +y camera + # frame (i.e. "up") points to the North Celestial Pole (NCP) -- i.e. + # zero roll offset: + self.q_eq2cam = qt.get_q_eq2cam(solved_cam_ra, solved_cam_dec, solved_cam_roll) + self.dead_reckoning = False + + # Update IMU: + # Calculate the IMU's unknown reference frame X using the plate solved + # coordinates and IMU measurements taken from the same time. If the IMU + # measurement isn't provided (e.g. None or zeros), the existing q_hor2x + # will continue to be used. + if q_x2imu: + self.q_eq2x = self.q_eq2cam * self.q_cam2imu * q_x2imu.conj() + self.q_eq2x = self.q_eq2x.normalized() + + def update_imu(self, + q_x2imu: quaternion.quaternion): + """ + Update the state with the raw IMU measurement. Does a dead-reckoning + estimate of the camera and scope pointing. + + INPUTS: + q_x2imu: Quaternion of the IMU orientation w.r.t. an unknown and drifting + reference frame X used by the IMU. + """ + if self.q_eq2x is not None: + # Dead reckoning estimate by IMU if q_hor2x has been estimated by a + # previous plate solve. + self.q_eq2cam = self.q_eq2x * q_x2imu * self.q_imu2cam + self.q_eq2cam = self.q_eq2cam.normalized() + + self.q_eq2scope = self.q_eq2cam * self.q_cam2scope + self.q_eq2scope = self.q_eq2scope.normalized() + + self.dead_reckoning = True + + def get_q_eq2scope(self): + """ """ + if self.q_eq2cam and self.q_cam2scope: + q_eq2scope = self.q_eq2cam * self.q_cam2scope + return q_eq2scope + else: + None + + def get_cam_radec(self): + """ + Returns the (ra, dec, roll) of the camera and a Boolean dead_reckoning + to indicate if the estimate is from dead-reckoning (True) or from plate + solving (False). + """ + ra, dec, roll = qt.get_radec_of_q_eq2cam(self.q_eq2cam) + return ra, dec, roll, self.dead_reckoning # Angles are in radians + + def get_scope_radec(self): + """ + Returns the (ra, dec, roll) of the scope and a Boolean dead_reckoning + to indicate if the estimate is from dead-reckoning (True) or from plate + solving (False). + """ + ra, dec, roll = qt.get_radec_of_q_eq2cam(self.q_eq2cam) + return ra, dec, roll, self.dead_reckoning # Angles are in radians + + def reset(self): + """ + Resets the internal state. + """ + self.q_eq2x = None + + def _set_screen_direction(self, screen_direction: str): + """ + Sets the screen direction which determines the fixed orientation between + the IMU and camera (q_imu2cam). + """ + if screen_direction == "flat": + # Rotate -90° around y_imu so that z_imu' points along z_camera + q1 = np.quaternion(np.cos(-np.pi / 4), 0, np.sin(-np.pi / 4), 0) + # Rotate -90° around z_imu' to align with the camera cooridnates + q2 = np.quaternion(np.cos(-np.pi / 4), 0, 0, np.sin(-np.pi / 4)) + self.q_imu2cam = q1 * q2 # Intrinsic rotation: q1 followed by q2 + else: + raise ValueError('Unsupported screen_direction') + + self.q_imu2cam = self.q_imu2cam.normalized() + self.q_cam2imu = self.q_imu2cam.conj() diff --git a/python/PiFinder/pointing_model/quaternion_transforms.py b/python/PiFinder/pointing_model/quaternion_transforms.py index 2fe81bd3f..656eca335 100644 --- a/python/PiFinder/pointing_model/quaternion_transforms.py +++ b/python/PiFinder/pointing_model/quaternion_transforms.py @@ -56,6 +56,49 @@ def get_quat_angular_diff(q1, q2): return d_theta # In radians +# ========== Equatorial frame functions ============================ + +def get_q_eq2cam(ra_rad, dec_rad, roll_rad): + """ + Express the coordinates of a camera pointing at RA, Dec, Roll (in radians) + in the relative to the Equatorial frame. + """ + # Intrinsic rotation of q_ra followed by q_dec gives a quaternion rotation + # that points +z towards the boresight of the camera. +y to the left and + # +x down. + q_ra = axis_angle2quat([0, 0, 1], ra_rad) # Rotate frame around z (NCP) + q_dec = axis_angle2quat([0, 1, 0], np.pi / 2 - dec_rad) # Rotate around y' + + # Need to rotate this +90 degrees around z_cam so that +y_cam points up + # and +x_cam points to the left of the Camera frame. In addition, need to + # account for the roll offset of the camera (zero if +y_cam points up along + # the great circle towards the NCP) + q_roll = axis_angle2quat([0, 0, 1], np.pi / 2 + roll_rad) + + # Intrinsic rotation: + q_eq2cam = (q_ra * q_dec * q_roll).normalized() + return q_eq2cam + + +def get_radec_of_q_eq2cam(q_eq2cam): + """ + """ + # Pure quaternion along camera boresight + pz_cam = q_eq2cam * np.quaternion(0, 0, 0, 1) * q_eq2cam.conj() + # Calculate RA, Dec from the camera boresight: + dec = np.arcsin(pz_cam.z) + ra = np.arctan2(pz_cam.y, pz_cam.x) + + # Pure quaternion along y_cam which points to NCP when roll = 0 + py_cam = q_eq2cam * np.quaternion(0, 0, 1, 0) * q_eq2cam.conj() + # Local East and North vectors (roll is the angle between py_cam and the north vector) + vec_east = np.array([-np.sin(ra), np.cos(ra), 0]) + vec_north = np.array([-np.sin(dec) * np.cos(ra), -np.sin(dec) * np.sin(ra), np.cos(dec)]) + roll = -np.arctan2(np.dot(py_cam.vec, vec_east), np.dot(py_cam.vec, vec_north)) + + return ra, dec, roll + + # ========== Horizontal (altaz) frame functions ============================ def get_q_hor2frame(az, alt): From 22975e0967b560274234e5f0afda3f338353dd0a Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 10 Aug 2025 20:11:34 +0100 Subject: [PATCH 084/253] Refactor integrator.py to encapsulate the altaz calculation --- python/PiFinder/integrator.py | 137 +++++++++++++++++++--------------- 1 file changed, 75 insertions(+), 62 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 9c9c22b26..7f9ac567f 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -18,12 +18,13 @@ from PiFinder import state_utils import PiFinder.calc_utils as calc_utils from PiFinder.multiproclogging import MultiprocLogging -from PiFinder.pointing_model.imu_dead_reckoning import ImuDeadReckoningHoriz +from PiFinder.pointing_model.imu_dead_reckoning import ImuDeadReckoningHoriz, ImuDeadReckoningEqFrame import PiFinder.pointing_model.quaternion_transforms as qt - -IMU_ALT = 2 -IMU_AZ = 0 +# *** Unused --> Remove later +#IMU_ALT = 2 +#IMU_AZ = 0 +EQ_DEAD_RECKONING = False # Use the Equatorial frame dead-reckoning logger = logging.getLogger("IMU.Integrator") @@ -58,6 +59,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr logger.debug("Starting Integrator") # TODO: This dict is duplicated in solver.py - Refactor? + # "Alt" and "Az" could be removed once we move to Eq-based dead-reckoning solved = { "RA": None, # RA of scope "Dec": None, @@ -124,67 +126,16 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr location = shared_state.location() dt = shared_state.datetime() - # see if we can calc alt-az - solved["Alt"] = None - solved["Az"] = None - if location and dt: - # We have position and time/date! - calc_utils.sf_utils.set_location( - location.lat, - location.lon, - location.altitude, - ) - alt, az = calc_utils.sf_utils.radec_to_altaz( - solved["RA"], - solved["Dec"], - dt, - ) - solved["Alt"] = alt - solved["Az"] = az - - alt, az = calc_utils.sf_utils.radec_to_altaz( - solved["camera_center"]["RA"], - solved["camera_center"]["Dec"], - dt, - ) - solved["camera_center"]["Alt"] = alt - solved["camera_center"]["Az"] = az - - # Experimental: For monitoring roll offset - # Estimate the roll offset due misalignment of the - # camera sensor with the Pole-to-Source great circle. - solved["Roll_offset"] = estimate_roll_offset(solved, dt) - # Find the roll at the target RA/Dec. Note that this doesn't include the - # roll offset so it's not the roll that the PiFinder cameara sees but the - # roll relative to the celestial pole given the RA and Dec. - roll_target_calculated = calc_utils.sf_utils.radec_to_roll( - solved["RA"], solved["Dec"], dt - ) - # Compensate for the roll offset. This gives the roll at the target - # as seen by the camera. - solved["Roll"] = roll_target_calculated + solved["Roll_offset"] - - # calculate roll for camera center - roll_target_calculated = calc_utils.sf_utils.radec_to_roll( - solved["camera_center"]["RA"], - solved["camera_center"]["Dec"], - dt, - ) - # Compensate for the roll offset. This gives the roll at the target - # as seen by the camera. - solved["camera_center"]["Roll"] = ( - roll_target_calculated + solved["Roll_offset"] - ) - - # Update with plate solved coordinates of camera center & IMU measurement - update_plate_solve_and_imu__degrees(pointing_tracker, solved) - + if EQ_DEAD_RECKONING: + # TODO: Do something similar for EQ mounts here + raise NotImplementedError + else: + update_solve_altaz(solved, location, dt, pointing_tracker) # From the alignment. Add this offset to the camera center to get # the scope altaz coordinates. TODO: This could be calculated once # at alignment? cam2scope_offset_az = solved["Az"] - solved["camera_center"]["Az"] cam2scope_offset_alt = solved["Alt"] - solved["camera_center"]["Alt"] - # TODO: Do something similar for EQ mounts here last_image_solve = copy.deepcopy(solved) solved["solve_source"] = "CAM" @@ -205,8 +156,8 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr # If we have alt, then we have a position/time # TODO: For debugging -- remove later - if prev_imu is None or qt.get_quat_angular_diff(prev_imu, imu["quat"]) > 1E-4: - print("Quat: ", imu["quat"]) + #if prev_imu is None or qt.get_quat_angular_diff(prev_imu, imu["quat"]) > 1E-4: + # print("Quat: ", imu["quat"]) prev_imu = imu["quat"].copy() # calc new alt/az @@ -344,3 +295,65 @@ def update_plate_solve_and_imu__degrees(pointing_tracker, solved): # Update: pointing_tracker.update_plate_solve_and_imu( solved_cam_az, solved_cam_alt, solved_cam_roll_offset, q_x2imu) + + +def update_solve_altaz(solved, location, dt, pointing_tracker): + """ + Updates the solved dic based on the plate-solved coordinates. Uses the + altaz coordinates and horizontal frame for IMU tracking. Moved from the + loop inside integrator integrator + """ + # see if we can calc alt-az + solved["Alt"] = None + solved["Az"] = None + if location and dt: + # We have position and time/date! + calc_utils.sf_utils.set_location( + location.lat, + location.lon, + location.altitude, + ) + alt, az = calc_utils.sf_utils.radec_to_altaz( + solved["RA"], + solved["Dec"], + dt, + ) + solved["Alt"] = alt + solved["Az"] = az + + alt, az = calc_utils.sf_utils.radec_to_altaz( + solved["camera_center"]["RA"], + solved["camera_center"]["Dec"], + dt, + ) + solved["camera_center"]["Alt"] = alt + solved["camera_center"]["Az"] = az + + # Experimental: For monitoring roll offset + # Estimate the roll offset due misalignment of the + # camera sensor with the Pole-to-Source great circle. + solved["Roll_offset"] = estimate_roll_offset(solved, dt) + # Find the roll at the target RA/Dec. Note that this doesn't include the + # roll offset so it's not the roll that the PiFinder cameara sees but the + # roll relative to the celestial pole given the RA and Dec. + roll_target_calculated = calc_utils.sf_utils.radec_to_roll( + solved["RA"], solved["Dec"], dt + ) + # Compensate for the roll offset. This gives the roll at the target + # as seen by the camera. + solved["Roll"] = roll_target_calculated + solved["Roll_offset"] + + # calculate roll for camera center + roll_target_calculated = calc_utils.sf_utils.radec_to_roll( + solved["camera_center"]["RA"], + solved["camera_center"]["Dec"], + dt, + ) + # Compensate for the roll offset. This gives the roll at the target + # as seen by the camera. + solved["camera_center"]["Roll"] = ( + roll_target_calculated + solved["Roll_offset"] + ) + + # Update with plate solved coordinates of camera center & IMU measurement + update_plate_solve_and_imu__degrees(pointing_tracker, solved) From ebdf43f7e26716319ff03c784843786b6dfe6dec Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 10 Aug 2025 20:29:58 +0100 Subject: [PATCH 085/253] Refactor integrator.py - Encapsulate another code block out of the while loop --- python/PiFinder/integrator.py | 203 ++++++++++++++++++---------------- 1 file changed, 109 insertions(+), 94 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 7f9ac567f..553ff765c 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -26,6 +26,9 @@ #IMU_AZ = 0 EQ_DEAD_RECKONING = False # Use the Equatorial frame dead-reckoning +IMU_MOVED_ANG_THRESHOLD = np.deg2rad(0.1) # Use IMU tracking if the angle moved is above this + + logger = logging.getLogger("IMU.Integrator") @@ -97,8 +100,6 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr flip_alt_offset = True else: flip_alt_offset = False - - imu_moved_ang_threshold = np.deg2rad(0.1) # Use IMU tracking if the angle moved is above this # Set up dead-reckoning tracking by the IMU: pointing_tracker = ImuDeadReckoningHoriz(cfg.get_option("screen_direction")) @@ -152,98 +153,12 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr imu = shared_state.imu() if imu: dt = shared_state.datetime() - if last_image_solve and last_image_solve["Alt"]: - # If we have alt, then we have a position/time - - # TODO: For debugging -- remove later - #if prev_imu is None or qt.get_quat_angular_diff(prev_imu, imu["quat"]) > 1E-4: - # print("Quat: ", imu["quat"]) - prev_imu = imu["quat"].copy() - - # calc new alt/az - # When moving, switch to tracking using the IMU - #if imu_moved(lis_imu, imu_pos): - assert isinstance(imu["quat"] , quaternion.quaternion), "Expecting quaternion.quaternion type" # TODO: Remove later - angle_moved = qt.get_quat_angular_diff(last_image_solve["imu_quat"], imu["quat"]) - if angle_moved > imu_moved_ang_threshold: - # Estimate camera pointing using IMU dead-reckoning - logger.debug("Track using IMU. Angle moved since last_image_solve = {:} (> threshold = {:})".format(np.rad2deg(angle_moved), np.rad2deg(imu_moved_ang_threshold))) - - # Dead-reckoning using IMU - pointing_tracker.update_imu(imu["quat"]) # Latest IMU meas - - # Store estimate: - az_cam, alt_cam, dead_reckoning_flag = pointing_tracker.get_cam_azalt() - solved["camera_center"]["Az"] = np.rad2deg(az_cam) - solved["camera_center"]["Alt"] = np.rad2deg(alt_cam) - - # Transform to scope center - # TODO: need to define q_cam2scope - solved["Az"] = solved["camera_center"]["Az"] + cam2scope_offset_az - solved["Alt"] = solved["camera_center"]["Alt"] + cam2scope_offset_alt - - q_x2imu = imu["quat"] - logger.debug(" IMU quat = ({:}, {:}, {:}, {:}".format(q_x2imu.w, q_x2imu.x, q_x2imu.y, q_x2imu.z)) - - """ DISABLE - Use quaternions - # calc new alt/az - OLD method - lis_imu = last_image_solve["imu_pos"] - imu_pos = imu["pos"] - alt_offset = imu_pos[IMU_ALT] - lis_imu[IMU_ALT] - if flip_alt_offset: - alt_offset = ((alt_offset + 180) % 360 - 180) * -1 - else: - alt_offset = (alt_offset + 180) % 360 - 180 - solved["Alt"] = (last_image_solve["Alt"] - alt_offset) % 360 - solved["camera_center"]["Alt"] = ( - last_image_solve["camera_center"]["Alt"] - alt_offset - ) % 360 - - az_offset = imu_pos[IMU_AZ] - lis_imu[IMU_AZ] - az_offset = (az_offset + 180) % 360 - 180 - solved["Az"] = (last_image_solve["Az"] + az_offset) % 360 - solved["camera_center"]["Az"] = ( - last_image_solve["camera_center"]["Az"] + az_offset - ) % 360 - """ - - # N.B. Assumes that location hasn't changed since last solve - # Turn this into RA/DEC - ( - solved["RA"], - solved["Dec"], - ) = calc_utils.sf_utils.altaz_to_radec( - solved["Alt"], solved["Az"], dt - ) - # Calculate the roll at the target RA/Dec and compensate for the offset. - solved["Roll"] = ( - calc_utils.sf_utils.radec_to_roll( - solved["RA"], solved["Dec"], dt - ) - + solved["Roll_offset"] - ) - - # Now for camera centered solve - ( - solved["camera_center"]["RA"], - solved["camera_center"]["Dec"], - ) = calc_utils.sf_utils.altaz_to_radec( - solved["camera_center"]["Alt"], - solved["camera_center"]["Az"], - dt, - ) - # Calculate the roll at the target RA/Dec and compensate for the offset. - solved["camera_center"]["Roll"] = ( - calc_utils.sf_utils.radec_to_roll( - solved["camera_center"]["RA"], - solved["camera_center"]["Dec"], - dt, - ) - + solved["Roll_offset"] - ) - - solved["solve_time"] = time.time() - solved["solve_source"] = "IMU" + if EQ_DEAD_RECKONING: + # TODO: Do something similar for EQ mounts here + raise NotImplementedError + else: + # Use IMU dead-reckoning to estimate pointing + update_imu_altaz(solved, last_image_solve, imu, dt, pointing_tracker) # Is the solution new? if solved["RA"] and solved["solve_time"] > last_solve_time: @@ -357,3 +272,103 @@ def update_solve_altaz(solved, location, dt, pointing_tracker): # Update with plate solved coordinates of camera center & IMU measurement update_plate_solve_and_imu__degrees(pointing_tracker, solved) + + +def update_imu_altaz(solved, last_image_solve, imu, dt, pointing_tracker): + """ + Updates the solved dictionary using IMU dead-reckoning from the last + solved pointing. + """ + if last_image_solve and last_image_solve["Alt"]: + # If we have alt, then we have a position/time + + # TODO: For debugging -- remove later + #if prev_imu is None or qt.get_quat_angular_diff(prev_imu, imu["quat"]) > 1E-4: + # print("Quat: ", imu["quat"]) + prev_imu = imu["quat"].copy() + + # calc new alt/az + # When moving, switch to tracking using the IMU + #if imu_moved(lis_imu, imu_pos): + assert isinstance(imu["quat"] , quaternion.quaternion), "Expecting quaternion.quaternion type" # TODO: Remove later + angle_moved = qt.get_quat_angular_diff(last_image_solve["imu_quat"], imu["quat"]) + if angle_moved > IMU_MOVED_ANG_THRESHOLD: + # Estimate camera pointing using IMU dead-reckoning + logger.debug("Track using IMU. Angle moved since last_image_solve = " + "{:}(> threshold = {:})".format(np.rad2deg(angle_moved), + np.rad2deg(IMU_MOVED_ANG_THRESHOLD))) + + # Dead-reckoning using IMU + pointing_tracker.update_imu(imu["quat"]) # Latest IMU meas + + # Store estimate: + az_cam, alt_cam, dead_reckoning_flag = pointing_tracker.get_cam_azalt() + solved["camera_center"]["Az"] = np.rad2deg(az_cam) + solved["camera_center"]["Alt"] = np.rad2deg(alt_cam) + + # Transform to scope center TODO: need to define q_cam2scope + solved["Az"] = solved["camera_center"]["Az"] + cam2scope_offset_az + solved["Alt"] = solved["camera_center"]["Alt"] + cam2scope_offset_alt + + q_x2imu = imu["quat"] + logger.debug(" IMU quat = ({:}, {:}, {:}, {:}".format(q_x2imu.w, q_x2imu.x, q_x2imu.y, q_x2imu.z)) + + """ DISABLE - Use quaternions + # calc new alt/az - OLD method lis_imu = + last_image_solve["imu_pos"] imu_pos = imu["pos"] alt_offset = + imu_pos[IMU_ALT] - lis_imu[IMU_ALT] if flip_alt_offset: + alt_offset = ((alt_offset + 180) % 360 - 180) * -1 + else: + alt_offset = (alt_offset + 180) % 360 - 180 + solved["Alt"] = (last_image_solve["Alt"] - alt_offset) % 360 + solved["camera_center"]["Alt"] = ( + last_image_solve["camera_center"]["Alt"] - alt_offset + ) % 360 + + az_offset = imu_pos[IMU_AZ] - lis_imu[IMU_AZ] az_offset = + (az_offset + 180) % 360 - 180 solved["Az"] = + (last_image_solve["Az"] + az_offset) % 360 + solved["camera_center"]["Az"] = ( + last_image_solve["camera_center"]["Az"] + az_offset + ) % 360 + """ + + # N.B. Assumes that location hasn't changed since last solve Turn + # this into RA/DEC + ( + solved["RA"], + solved["Dec"], + ) = calc_utils.sf_utils.altaz_to_radec( + solved["Alt"], solved["Az"], dt + ) + # Calculate the roll at the target RA/Dec and compensate for the + # offset. + solved["Roll"] = ( + calc_utils.sf_utils.radec_to_roll( + solved["RA"], solved["Dec"], dt + ) + + solved["Roll_offset"] + ) + + # Now for camera centered solve + ( + solved["camera_center"]["RA"], + solved["camera_center"]["Dec"], + ) = calc_utils.sf_utils.altaz_to_radec( + solved["camera_center"]["Alt"], + solved["camera_center"]["Az"], + dt, + ) + # Calculate the roll at the target RA/Dec and compensate for the + # offset. + solved["camera_center"]["Roll"] = ( + calc_utils.sf_utils.radec_to_roll( + solved["camera_center"]["RA"], + solved["camera_center"]["Dec"], + dt, + ) + + solved["Roll_offset"] + ) + + solved["solve_time"] = time.time() + solved["solve_source"] = "IMU" From e25bc3d4c34905977cdbe1d01c7a5127e1562891 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 10 Aug 2025 20:33:38 +0100 Subject: [PATCH 086/253] Fix - use last_image_solve to calculate cam2scope_offset --- python/PiFinder/integrator.py | 14 ++++++++------ 1 file changed, 8 insertions(+), 6 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 553ff765c..3fbbabcfa 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -132,11 +132,6 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr raise NotImplementedError else: update_solve_altaz(solved, location, dt, pointing_tracker) - # From the alignment. Add this offset to the camera center to get - # the scope altaz coordinates. TODO: This could be calculated once - # at alignment? - cam2scope_offset_az = solved["Az"] - solved["camera_center"]["Az"] - cam2scope_offset_alt = solved["Alt"] - solved["camera_center"]["Alt"] last_image_solve = copy.deepcopy(solved) solved["solve_source"] = "CAM" @@ -193,6 +188,8 @@ def estimate_roll_offset(solved, dt): return roll_offset +# ======== Altaz version - TODO remove and use the EQ version ====== + def update_plate_solve_and_imu__degrees(pointing_tracker, solved): """ Wrapper for ImuDeadReckoning.update_plate_solve_and_imu() to interface @@ -305,7 +302,12 @@ def update_imu_altaz(solved, last_image_solve, imu, dt, pointing_tracker): az_cam, alt_cam, dead_reckoning_flag = pointing_tracker.get_cam_azalt() solved["camera_center"]["Az"] = np.rad2deg(az_cam) solved["camera_center"]["Alt"] = np.rad2deg(alt_cam) - + + # From the alignment. Add this offset to the camera center to get + # the scope altaz coordinates. TODO: This could be calculated once + # at alignment? Or when last solved + cam2scope_offset_az = last_image_solve["Az"] - last_image_solve["camera_center"]["Az"] + cam2scope_offset_alt = last_image_solve["Alt"] - last_image_solve["camera_center"]["Alt"] # Transform to scope center TODO: need to define q_cam2scope solved["Az"] = solved["camera_center"]["Az"] + cam2scope_offset_az solved["Alt"] = solved["camera_center"]["Alt"] + cam2scope_offset_alt From 8a54b1174ff64626d267701344b805f148a82471 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 10 Aug 2025 20:36:47 +0100 Subject: [PATCH 087/253] Refactor --- python/PiFinder/integrator.py | 39 ++++++++++++++++++----------------- 1 file changed, 20 insertions(+), 19 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 3fbbabcfa..1c0ed3ce2 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -190,25 +190,6 @@ def estimate_roll_offset(solved, dt): # ======== Altaz version - TODO remove and use the EQ version ====== -def update_plate_solve_and_imu__degrees(pointing_tracker, solved): - """ - Wrapper for ImuDeadReckoning.update_plate_solve_and_imu() to interface - degrees to radians. - """ - if (solved["Az"] is None) or (solved["Alt"] is None): - return # No update - else: - # Successfully plate solved & camera pointing exists - q_x2imu = solved["imu_quat"] # IMU measurement at the time of plate solving - # Convert to radians: - solved_cam_az = np.deg2rad(solved["camera_center"]["Az"]) - solved_cam_alt = np.deg2rad(solved["camera_center"]["Alt"]) - solved_cam_roll_offset = np.deg2rad(solved["Roll_offset"]) - # Update: - pointing_tracker.update_plate_solve_and_imu( - solved_cam_az, solved_cam_alt, solved_cam_roll_offset, q_x2imu) - - def update_solve_altaz(solved, location, dt, pointing_tracker): """ Updates the solved dic based on the plate-solved coordinates. Uses the @@ -374,3 +355,23 @@ def update_imu_altaz(solved, last_image_solve, imu, dt, pointing_tracker): solved["solve_time"] = time.time() solved["solve_source"] = "IMU" + + +def update_plate_solve_and_imu__degrees(pointing_tracker, solved): + """ + Wrapper for ImuDeadReckoning.update_plate_solve_and_imu() to interface + degrees to radians. + """ + if (solved["Az"] is None) or (solved["Alt"] is None): + return # No update + else: + # Successfully plate solved & camera pointing exists + q_x2imu = solved["imu_quat"] # IMU measurement at the time of plate solving + # Convert to radians: + solved_cam_az = np.deg2rad(solved["camera_center"]["Az"]) + solved_cam_alt = np.deg2rad(solved["camera_center"]["Alt"]) + solved_cam_roll_offset = np.deg2rad(solved["Roll_offset"]) + # Update: + pointing_tracker.update_plate_solve_and_imu( + solved_cam_az, solved_cam_alt, solved_cam_roll_offset, q_x2imu) + From bf081d7aa4f777da3b3bc4b0039967f79e10714c Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 10 Aug 2025 20:41:34 +0100 Subject: [PATCH 088/253] Update comments --- python/PiFinder/integrator.py | 19 +++++++++++-------- 1 file changed, 11 insertions(+), 8 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 1c0ed3ce2..eee2f8c0f 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -121,6 +121,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr pass if type(next_image_solve) is dict: + # We have a new image solve: Use this for RA/Dec solved = next_image_solve # see if we can generate alt/az @@ -137,14 +138,8 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr solved["solve_source"] = "CAM" elif solved["Alt"]: - # Use IMU dead-reckoning from the last camera solve: - # 1) Check we have an alt/az solve, otherwise we can't use the IMU - # If Alt exists: - # 2) Calculate the difference in the IMU measurements since the - # last plage solve. IMU "pos" is stored as Alt/Az. - # 3) Add the relative Alt/Az difference from the IMU to the plate - # -solved Alt/Az to give a dead-reckoning estimate of the current - # position. + # Previous plate-solve exists so use IMU dead-reckoning from + # the last plate solved coordinates. imu = shared_state.imu() if imu: dt = shared_state.datetime() @@ -257,6 +252,14 @@ def update_imu_altaz(solved, last_image_solve, imu, dt, pointing_tracker): Updates the solved dictionary using IMU dead-reckoning from the last solved pointing. """ + # Use IMU dead-reckoning from the last camera solve: + # 1) Check we have an alt/az solve, otherwise we can't use the IMU + # If Alt exists: + # 2) Calculate the difference in the IMU measurements since the + # last plage solve. IMU "pos" is stored as Alt/Az. + # 3) Add the relative Alt/Az difference from the IMU to the plate + # -solved Alt/Az to give a dead-reckoning estimate of the current + # position. if last_image_solve and last_image_solve["Alt"]: # If we have alt, then we have a position/time From f6e6c7cae55ec717031568f3252fc76f9d9db958 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 10 Aug 2025 20:57:36 +0100 Subject: [PATCH 089/253] Use flag in ImuDeadReckoning rather than solved["Alt"] to determine if plate solved coordinate exists --- python/PiFinder/integrator.py | 2 +- python/PiFinder/pointing_model/imu_dead_reckoning.py | 9 ++++++++- 2 files changed, 9 insertions(+), 2 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index eee2f8c0f..b547185b8 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -137,7 +137,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr last_image_solve = copy.deepcopy(solved) solved["solve_source"] = "CAM" - elif solved["Alt"]: + elif pointing_tracker.tracking: # Previous plate-solve exists so use IMU dead-reckoning from # the last plate solved coordinates. imu = shared_state.imu() diff --git a/python/PiFinder/pointing_model/imu_dead_reckoning.py b/python/PiFinder/pointing_model/imu_dead_reckoning.py index 0802be049..efdc929d0 100644 --- a/python/PiFinder/pointing_model/imu_dead_reckoning.py +++ b/python/PiFinder/pointing_model/imu_dead_reckoning.py @@ -58,9 +58,11 @@ def __init__(self, screen_direction): # The poinging of the camera and scope frames wrt the horizontal frame. # These get updated by plate solving and IMU dead-reckoning. self.q_hor2cam = None + # True when q_hor2cam is estimated by IMU dead-reckoning. # False when set by plate solving - self.dead_reckoning = False + self.dead_reckoning = False + self.tracking = False # True when previous plate solve exists and tracking # The IMU's unkonwn drifting reference frame X. This is solved for # every time we have a simultaneous plate solve and IMU measurement. @@ -117,6 +119,7 @@ def update_plate_solve_and_imu(self, if q_x2imu: self.q_hor2x = self.q_hor2cam * self.q_cam2imu * q_x2imu.conj() self.q_hor2x = self.q_hor2x.normalized() + self.tracking = True # We have a plate solve and IMU measurement def update_imu(self, q_x2imu: quaternion.quaternion): @@ -162,6 +165,7 @@ def reset(self): Resets the internal state. """ self.q_hor2x = None + self.tracking = False def _set_screen_direction(self, screen_direction: str): """ @@ -230,6 +234,7 @@ def __init__(self, screen_direction): # True when q_eq2cam is estimated by IMU dead-reckoning. # False when set by plate solving self.dead_reckoning = False + self.tracking = False # True when previous plate solve exists and tracking # The IMU's unkonwn drifting reference frame X. This is solved for # every time we have a simultaneous plate solve and IMU measurement. @@ -285,6 +290,7 @@ def update_plate_solve_and_imu(self, if q_x2imu: self.q_eq2x = self.q_eq2cam * self.q_cam2imu * q_x2imu.conj() self.q_eq2x = self.q_eq2x.normalized() + self.tracking = True # We have a plate solve and IMU measurement def update_imu(self, q_x2imu: quaternion.quaternion): @@ -338,6 +344,7 @@ def reset(self): Resets the internal state. """ self.q_eq2x = None + self.tracking = False def _set_screen_direction(self, screen_direction: str): """ From 2e96a28ed1b23c5573b50ad6bd9885f318f9aaec Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 10 Aug 2025 21:01:56 +0100 Subject: [PATCH 090/253] Add helper functions of the EQ versions (currently just a copy of the altaz version) --- python/PiFinder/integrator.py | 211 ++++++++++++++++++++++++++++++++-- 1 file changed, 202 insertions(+), 9 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index b547185b8..4c2fa8c09 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -124,15 +124,13 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr # We have a new image solve: Use this for RA/Dec solved = next_image_solve - # see if we can generate alt/az location = shared_state.location() dt = shared_state.datetime() if EQ_DEAD_RECKONING: - # TODO: Do something similar for EQ mounts here - raise NotImplementedError + update_solve_eq(solved, location, dt, pointing_tracker) else: - update_solve_altaz(solved, location, dt, pointing_tracker) + update_solve_altaz(solved, location, dt, pointing_tracker) # TODO: Remove later last_image_solve = copy.deepcopy(solved) solved["solve_source"] = "CAM" @@ -144,10 +142,9 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr if imu: dt = shared_state.datetime() if EQ_DEAD_RECKONING: - # TODO: Do something similar for EQ mounts here - raise NotImplementedError + update_imu_eq(solved, last_image_solve, imu, dt, pointing_tracker) else: - # Use IMU dead-reckoning to estimate pointing + # TODO: Remove later update_imu_altaz(solved, last_image_solve, imu, dt, pointing_tracker) # Is the solution new? @@ -183,6 +180,202 @@ def estimate_roll_offset(solved, dt): return roll_offset +# ======== EQ version =============================== + +def update_solve_eq(solved, location, dt, pointing_tracker): + """ + Updates the solved dic based on the plate-solved coordinates. Uses the + altaz coordinates and horizontal frame for IMU tracking. Moved from the + loop inside integrator integrator + """ + # see if we can calc alt-az + solved["Alt"] = None + solved["Az"] = None + if location and dt: + # We have position and time/date! + calc_utils.sf_utils.set_location( + location.lat, + location.lon, + location.altitude, + ) + alt, az = calc_utils.sf_utils.radec_to_altaz( + solved["RA"], + solved["Dec"], + dt, + ) + solved["Alt"] = alt + solved["Az"] = az + + alt, az = calc_utils.sf_utils.radec_to_altaz( + solved["camera_center"]["RA"], + solved["camera_center"]["Dec"], + dt, + ) + solved["camera_center"]["Alt"] = alt + solved["camera_center"]["Az"] = az + + # Experimental: For monitoring roll offset + # Estimate the roll offset due misalignment of the + # camera sensor with the Pole-to-Source great circle. + solved["Roll_offset"] = estimate_roll_offset(solved, dt) + # Find the roll at the target RA/Dec. Note that this doesn't include the + # roll offset so it's not the roll that the PiFinder cameara sees but the + # roll relative to the celestial pole given the RA and Dec. + roll_target_calculated = calc_utils.sf_utils.radec_to_roll( + solved["RA"], solved["Dec"], dt + ) + # Compensate for the roll offset. This gives the roll at the target + # as seen by the camera. + solved["Roll"] = roll_target_calculated + solved["Roll_offset"] + + # calculate roll for camera center + roll_target_calculated = calc_utils.sf_utils.radec_to_roll( + solved["camera_center"]["RA"], + solved["camera_center"]["Dec"], + dt, + ) + # Compensate for the roll offset. This gives the roll at the target + # as seen by the camera. + solved["camera_center"]["Roll"] = ( + roll_target_calculated + solved["Roll_offset"] + ) + + # Update with plate solved coordinates of camera center & IMU measurement + update_plate_solve_and_imu_altaz__degrees(pointing_tracker, solved) + + +def update_imu_eq(solved, last_image_solve, imu, dt, pointing_tracker): + """ + Updates the solved dictionary using IMU dead-reckoning from the last + solved pointing. + """ + # Use IMU dead-reckoning from the last camera solve: + # 1) Check we have an alt/az solve, otherwise we can't use the IMU + # If Alt exists: + # 2) Calculate the difference in the IMU measurements since the + # last plage solve. IMU "pos" is stored as Alt/Az. + # 3) Add the relative Alt/Az difference from the IMU to the plate + # -solved Alt/Az to give a dead-reckoning estimate of the current + # position. + if last_image_solve and last_image_solve["Alt"]: + # If we have alt, then we have a position/time + + # TODO: For debugging -- remove later + #if prev_imu is None or qt.get_quat_angular_diff(prev_imu, imu["quat"]) > 1E-4: + # print("Quat: ", imu["quat"]) + prev_imu = imu["quat"].copy() + + # calc new alt/az + # When moving, switch to tracking using the IMU + #if imu_moved(lis_imu, imu_pos): + assert isinstance(imu["quat"] , quaternion.quaternion), "Expecting quaternion.quaternion type" # TODO: Remove later + angle_moved = qt.get_quat_angular_diff(last_image_solve["imu_quat"], imu["quat"]) + if angle_moved > IMU_MOVED_ANG_THRESHOLD: + # Estimate camera pointing using IMU dead-reckoning + logger.debug("Track using IMU. Angle moved since last_image_solve = " + "{:}(> threshold = {:})".format(np.rad2deg(angle_moved), + np.rad2deg(IMU_MOVED_ANG_THRESHOLD))) + + # Dead-reckoning using IMU + pointing_tracker.update_imu(imu["quat"]) # Latest IMU meas + + # Store estimate: + az_cam, alt_cam, dead_reckoning_flag = pointing_tracker.get_cam_azalt() + solved["camera_center"]["Az"] = np.rad2deg(az_cam) + solved["camera_center"]["Alt"] = np.rad2deg(alt_cam) + + # From the alignment. Add this offset to the camera center to get + # the scope altaz coordinates. TODO: This could be calculated once + # at alignment? Or when last solved + cam2scope_offset_az = last_image_solve["Az"] - last_image_solve["camera_center"]["Az"] + cam2scope_offset_alt = last_image_solve["Alt"] - last_image_solve["camera_center"]["Alt"] + # Transform to scope center TODO: need to define q_cam2scope + solved["Az"] = solved["camera_center"]["Az"] + cam2scope_offset_az + solved["Alt"] = solved["camera_center"]["Alt"] + cam2scope_offset_alt + + q_x2imu = imu["quat"] + logger.debug(" IMU quat = ({:}, {:}, {:}, {:}".format(q_x2imu.w, q_x2imu.x, q_x2imu.y, q_x2imu.z)) + + """ DISABLE - Use quaternions + # calc new alt/az - OLD method lis_imu = + last_image_solve["imu_pos"] imu_pos = imu["pos"] alt_offset = + imu_pos[IMU_ALT] - lis_imu[IMU_ALT] if flip_alt_offset: + alt_offset = ((alt_offset + 180) % 360 - 180) * -1 + else: + alt_offset = (alt_offset + 180) % 360 - 180 + solved["Alt"] = (last_image_solve["Alt"] - alt_offset) % 360 + solved["camera_center"]["Alt"] = ( + last_image_solve["camera_center"]["Alt"] - alt_offset + ) % 360 + + az_offset = imu_pos[IMU_AZ] - lis_imu[IMU_AZ] az_offset = + (az_offset + 180) % 360 - 180 solved["Az"] = + (last_image_solve["Az"] + az_offset) % 360 + solved["camera_center"]["Az"] = ( + last_image_solve["camera_center"]["Az"] + az_offset + ) % 360 + """ + + # N.B. Assumes that location hasn't changed since last solve Turn + # this into RA/DEC + ( + solved["RA"], + solved["Dec"], + ) = calc_utils.sf_utils.altaz_to_radec( + solved["Alt"], solved["Az"], dt + ) + # Calculate the roll at the target RA/Dec and compensate for the + # offset. + solved["Roll"] = ( + calc_utils.sf_utils.radec_to_roll( + solved["RA"], solved["Dec"], dt + ) + + solved["Roll_offset"] + ) + + # Now for camera centered solve + ( + solved["camera_center"]["RA"], + solved["camera_center"]["Dec"], + ) = calc_utils.sf_utils.altaz_to_radec( + solved["camera_center"]["Alt"], + solved["camera_center"]["Az"], + dt, + ) + # Calculate the roll at the target RA/Dec and compensate for the + # offset. + solved["camera_center"]["Roll"] = ( + calc_utils.sf_utils.radec_to_roll( + solved["camera_center"]["RA"], + solved["camera_center"]["Dec"], + dt, + ) + + solved["Roll_offset"] + ) + + solved["solve_time"] = time.time() + solved["solve_source"] = "IMU" + + +def update_plate_solve_and_imu_eq__degrees(pointing_tracker, solved): + """ + Wrapper for ImuDeadReckoning.update_plate_solve_and_imu() to interface + degrees to radians. + """ + if (solved["Az"] is None) or (solved["Alt"] is None): + return # No update + else: + # Successfully plate solved & camera pointing exists + q_x2imu = solved["imu_quat"] # IMU measurement at the time of plate solving + # Convert to radians: + solved_cam_az = np.deg2rad(solved["camera_center"]["Az"]) + solved_cam_alt = np.deg2rad(solved["camera_center"]["Alt"]) + solved_cam_roll_offset = np.deg2rad(solved["Roll_offset"]) + # Update: + pointing_tracker.update_plate_solve_and_imu( + solved_cam_az, solved_cam_alt, solved_cam_roll_offset, q_x2imu) + + # ======== Altaz version - TODO remove and use the EQ version ====== def update_solve_altaz(solved, location, dt, pointing_tracker): @@ -244,7 +437,7 @@ def update_solve_altaz(solved, location, dt, pointing_tracker): ) # Update with plate solved coordinates of camera center & IMU measurement - update_plate_solve_and_imu__degrees(pointing_tracker, solved) + update_plate_solve_and_imu_altaz__degrees(pointing_tracker, solved) def update_imu_altaz(solved, last_image_solve, imu, dt, pointing_tracker): @@ -360,7 +553,7 @@ def update_imu_altaz(solved, last_image_solve, imu, dt, pointing_tracker): solved["solve_source"] = "IMU" -def update_plate_solve_and_imu__degrees(pointing_tracker, solved): +def update_plate_solve_and_imu_altaz__degrees(pointing_tracker, solved): """ Wrapper for ImuDeadReckoning.update_plate_solve_and_imu() to interface degrees to radians. From cc01e650dd10f3f490b02d89195311ac96268bc5 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 10 Aug 2025 21:11:07 +0100 Subject: [PATCH 091/253] Refactor: Move if to where funcs are called --- python/PiFinder/integrator.py | 217 +++++++++++++++++----------------- 1 file changed, 109 insertions(+), 108 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 4c2fa8c09..c6b611d4b 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -127,10 +127,12 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr location = shared_state.location() dt = shared_state.datetime() - if EQ_DEAD_RECKONING: - update_solve_eq(solved, location, dt, pointing_tracker) - else: - update_solve_altaz(solved, location, dt, pointing_tracker) # TODO: Remove later + if location and dt: + # We have position and time/date! + if EQ_DEAD_RECKONING: + update_solve_eq(solved, location, dt, pointing_tracker) + else: + update_solve_altaz(solved, location, dt, pointing_tracker) # TODO: Remove later last_image_solve = copy.deepcopy(solved) solved["solve_source"] = "CAM" @@ -188,60 +190,60 @@ def update_solve_eq(solved, location, dt, pointing_tracker): altaz coordinates and horizontal frame for IMU tracking. Moved from the loop inside integrator integrator """ - # see if we can calc alt-az + assert location and dt, "Need location and time" + solved["Alt"] = None solved["Az"] = None - if location and dt: - # We have position and time/date! - calc_utils.sf_utils.set_location( - location.lat, - location.lon, - location.altitude, - ) - alt, az = calc_utils.sf_utils.radec_to_altaz( - solved["RA"], - solved["Dec"], - dt, - ) - solved["Alt"] = alt - solved["Az"] = az - - alt, az = calc_utils.sf_utils.radec_to_altaz( - solved["camera_center"]["RA"], - solved["camera_center"]["Dec"], - dt, - ) - solved["camera_center"]["Alt"] = alt - solved["camera_center"]["Az"] = az - - # Experimental: For monitoring roll offset - # Estimate the roll offset due misalignment of the - # camera sensor with the Pole-to-Source great circle. - solved["Roll_offset"] = estimate_roll_offset(solved, dt) - # Find the roll at the target RA/Dec. Note that this doesn't include the - # roll offset so it's not the roll that the PiFinder cameara sees but the - # roll relative to the celestial pole given the RA and Dec. - roll_target_calculated = calc_utils.sf_utils.radec_to_roll( - solved["RA"], solved["Dec"], dt - ) - # Compensate for the roll offset. This gives the roll at the target - # as seen by the camera. - solved["Roll"] = roll_target_calculated + solved["Roll_offset"] - - # calculate roll for camera center - roll_target_calculated = calc_utils.sf_utils.radec_to_roll( - solved["camera_center"]["RA"], - solved["camera_center"]["Dec"], - dt, - ) - # Compensate for the roll offset. This gives the roll at the target - # as seen by the camera. - solved["camera_center"]["Roll"] = ( - roll_target_calculated + solved["Roll_offset"] - ) - - # Update with plate solved coordinates of camera center & IMU measurement - update_plate_solve_and_imu_altaz__degrees(pointing_tracker, solved) + + calc_utils.sf_utils.set_location( + location.lat, + location.lon, + location.altitude, + ) + alt, az = calc_utils.sf_utils.radec_to_altaz( + solved["RA"], + solved["Dec"], + dt, + ) + solved["Alt"] = alt + solved["Az"] = az + + alt, az = calc_utils.sf_utils.radec_to_altaz( + solved["camera_center"]["RA"], + solved["camera_center"]["Dec"], + dt, + ) + solved["camera_center"]["Alt"] = alt + solved["camera_center"]["Az"] = az + + # Experimental: For monitoring roll offset + # Estimate the roll offset due misalignment of the + # camera sensor with the Pole-to-Source great circle. + solved["Roll_offset"] = estimate_roll_offset(solved, dt) + # Find the roll at the target RA/Dec. Note that this doesn't include the + # roll offset so it's not the roll that the PiFinder cameara sees but the + # roll relative to the celestial pole given the RA and Dec. + roll_target_calculated = calc_utils.sf_utils.radec_to_roll( + solved["RA"], solved["Dec"], dt + ) + # Compensate for the roll offset. This gives the roll at the target + # as seen by the camera. + solved["Roll"] = roll_target_calculated + solved["Roll_offset"] + + # calculate roll for camera center + roll_target_calculated = calc_utils.sf_utils.radec_to_roll( + solved["camera_center"]["RA"], + solved["camera_center"]["Dec"], + dt, + ) + # Compensate for the roll offset. This gives the roll at the target + # as seen by the camera. + solved["camera_center"]["Roll"] = ( + roll_target_calculated + solved["Roll_offset"] + ) + + # Update with plate solved coordinates of camera center & IMU measurement + update_plate_solve_and_imu_altaz__degrees(pointing_tracker, solved) def update_imu_eq(solved, last_image_solve, imu, dt, pointing_tracker): @@ -384,60 +386,59 @@ def update_solve_altaz(solved, location, dt, pointing_tracker): altaz coordinates and horizontal frame for IMU tracking. Moved from the loop inside integrator integrator """ - # see if we can calc alt-az + assert location and dt, "Need location and time" + solved["Alt"] = None solved["Az"] = None - if location and dt: - # We have position and time/date! - calc_utils.sf_utils.set_location( - location.lat, - location.lon, - location.altitude, - ) - alt, az = calc_utils.sf_utils.radec_to_altaz( - solved["RA"], - solved["Dec"], - dt, - ) - solved["Alt"] = alt - solved["Az"] = az - - alt, az = calc_utils.sf_utils.radec_to_altaz( - solved["camera_center"]["RA"], - solved["camera_center"]["Dec"], - dt, - ) - solved["camera_center"]["Alt"] = alt - solved["camera_center"]["Az"] = az - - # Experimental: For monitoring roll offset - # Estimate the roll offset due misalignment of the - # camera sensor with the Pole-to-Source great circle. - solved["Roll_offset"] = estimate_roll_offset(solved, dt) - # Find the roll at the target RA/Dec. Note that this doesn't include the - # roll offset so it's not the roll that the PiFinder cameara sees but the - # roll relative to the celestial pole given the RA and Dec. - roll_target_calculated = calc_utils.sf_utils.radec_to_roll( - solved["RA"], solved["Dec"], dt - ) - # Compensate for the roll offset. This gives the roll at the target - # as seen by the camera. - solved["Roll"] = roll_target_calculated + solved["Roll_offset"] - - # calculate roll for camera center - roll_target_calculated = calc_utils.sf_utils.radec_to_roll( - solved["camera_center"]["RA"], - solved["camera_center"]["Dec"], - dt, - ) - # Compensate for the roll offset. This gives the roll at the target - # as seen by the camera. - solved["camera_center"]["Roll"] = ( - roll_target_calculated + solved["Roll_offset"] - ) - - # Update with plate solved coordinates of camera center & IMU measurement - update_plate_solve_and_imu_altaz__degrees(pointing_tracker, solved) + calc_utils.sf_utils.set_location( + location.lat, + location.lon, + location.altitude, + ) + alt, az = calc_utils.sf_utils.radec_to_altaz( + solved["RA"], + solved["Dec"], + dt, + ) + solved["Alt"] = alt + solved["Az"] = az + + alt, az = calc_utils.sf_utils.radec_to_altaz( + solved["camera_center"]["RA"], + solved["camera_center"]["Dec"], + dt, + ) + solved["camera_center"]["Alt"] = alt + solved["camera_center"]["Az"] = az + + # Experimental: For monitoring roll offset + # Estimate the roll offset due misalignment of the + # camera sensor with the Pole-to-Source great circle. + solved["Roll_offset"] = estimate_roll_offset(solved, dt) + # Find the roll at the target RA/Dec. Note that this doesn't include the + # roll offset so it's not the roll that the PiFinder cameara sees but the + # roll relative to the celestial pole given the RA and Dec. + roll_target_calculated = calc_utils.sf_utils.radec_to_roll( + solved["RA"], solved["Dec"], dt + ) + # Compensate for the roll offset. This gives the roll at the target + # as seen by the camera. + solved["Roll"] = roll_target_calculated + solved["Roll_offset"] + + # calculate roll for camera center + roll_target_calculated = calc_utils.sf_utils.radec_to_roll( + solved["camera_center"]["RA"], + solved["camera_center"]["Dec"], + dt, + ) + # Compensate for the roll offset. This gives the roll at the target + # as seen by the camera. + solved["camera_center"]["Roll"] = ( + roll_target_calculated + solved["Roll_offset"] + ) + + # Update with plate solved coordinates of camera center & IMU measurement + update_plate_solve_and_imu_altaz__degrees(pointing_tracker, solved) def update_imu_altaz(solved, last_image_solve, imu, dt, pointing_tracker): From 3185cb34ca24a63ad847da061ba69505d0b7e696 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 10 Aug 2025 21:45:25 +0100 Subject: [PATCH 092/253] integrator.py: Modify the EQ version --- python/PiFinder/integrator.py | 171 +++++++++++----------------------- 1 file changed, 56 insertions(+), 115 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index c6b611d4b..26f6fed76 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -71,7 +71,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr "RA": None, "Dec": None, "Roll": None, - "Alt": None, + "Alt": None, # TODO: Remove Alt, Az keys later? "Az": None, }, "camera_solve": { # camera_solve is NOT updated by IMU dead-reckoning @@ -109,7 +109,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr # so we can delta for IMU updates last_image_solve = None last_solve_time = time.time() - prev_imu = None # TODO: For debugging - remove later + #prev_imu = None # TODO: For debugging - remove later while True: state_utils.sleep_for_framerate(shared_state) @@ -192,14 +192,18 @@ def update_solve_eq(solved, location, dt, pointing_tracker): """ assert location and dt, "Need location and time" + # Commented out Altaz coords which are not needed TODO: Remove these later + """ solved["Alt"] = None solved["Az"] = None - + """ + # TODO: May be able to remove this later calc_utils.sf_utils.set_location( location.lat, location.lon, location.altitude, ) + """ alt, az = calc_utils.sf_utils.radec_to_altaz( solved["RA"], solved["Dec"], @@ -215,11 +219,12 @@ def update_solve_eq(solved, location, dt, pointing_tracker): ) solved["camera_center"]["Alt"] = alt solved["camera_center"]["Az"] = az + """ # Experimental: For monitoring roll offset # Estimate the roll offset due misalignment of the # camera sensor with the Pole-to-Source great circle. - solved["Roll_offset"] = estimate_roll_offset(solved, dt) + solved["Roll_offset"] = estimate_roll_offset(solved, dt) # TODO: Remove later? # Find the roll at the target RA/Dec. Note that this doesn't include the # roll offset so it's not the roll that the PiFinder cameara sees but the # roll relative to the celestial pole given the RA and Dec. @@ -243,7 +248,7 @@ def update_solve_eq(solved, location, dt, pointing_tracker): ) # Update with plate solved coordinates of camera center & IMU measurement - update_plate_solve_and_imu_altaz__degrees(pointing_tracker, solved) + update_plate_solve_and_imu_eq__degrees(pointing_tracker, solved) def update_imu_eq(solved, last_image_solve, imu, dt, pointing_tracker): @@ -251,118 +256,54 @@ def update_imu_eq(solved, last_image_solve, imu, dt, pointing_tracker): Updates the solved dictionary using IMU dead-reckoning from the last solved pointing. """ - # Use IMU dead-reckoning from the last camera solve: - # 1) Check we have an alt/az solve, otherwise we can't use the IMU - # If Alt exists: - # 2) Calculate the difference in the IMU measurements since the - # last plage solve. IMU "pos" is stored as Alt/Az. - # 3) Add the relative Alt/Az difference from the IMU to the plate - # -solved Alt/Az to give a dead-reckoning estimate of the current - # position. - if last_image_solve and last_image_solve["Alt"]: - # If we have alt, then we have a position/time - - # TODO: For debugging -- remove later - #if prev_imu is None or qt.get_quat_angular_diff(prev_imu, imu["quat"]) > 1E-4: - # print("Quat: ", imu["quat"]) - prev_imu = imu["quat"].copy() - - # calc new alt/az - # When moving, switch to tracking using the IMU - #if imu_moved(lis_imu, imu_pos): - assert isinstance(imu["quat"] , quaternion.quaternion), "Expecting quaternion.quaternion type" # TODO: Remove later - angle_moved = qt.get_quat_angular_diff(last_image_solve["imu_quat"], imu["quat"]) - if angle_moved > IMU_MOVED_ANG_THRESHOLD: - # Estimate camera pointing using IMU dead-reckoning - logger.debug("Track using IMU. Angle moved since last_image_solve = " - "{:}(> threshold = {:})".format(np.rad2deg(angle_moved), - np.rad2deg(IMU_MOVED_ANG_THRESHOLD))) - - # Dead-reckoning using IMU - pointing_tracker.update_imu(imu["quat"]) # Latest IMU meas + if not(last_image_solve and pointing_tracker.tracking and dt): + return # Need all of these to do IMU dead-reckoning + + # TODO: For debugging -- remove later + #if prev_imu is None or qt.get_quat_angular_diff(prev_imu, imu["quat"]) > 1E-4: + # print("Quat: ", imu["quat"]) + #prev_imu = imu["quat"].copy() + + # When moving, switch to tracking using the IMU + #if imu_moved(lis_imu, imu_pos): + assert isinstance(imu["quat"] , quaternion.quaternion), "Expecting quaternion.quaternion type" # TODO: Remove later + angle_moved = qt.get_quat_angular_diff(last_image_solve["imu_quat"], imu["quat"]) + if angle_moved > IMU_MOVED_ANG_THRESHOLD: + # Estimate camera pointing using IMU dead-reckoning + logger.debug("Track using IMU. Angle moved since last_image_solve = " + "{:}(> threshold = {:})".format(np.rad2deg(angle_moved), + np.rad2deg(IMU_MOVED_ANG_THRESHOLD))) - # Store estimate: - az_cam, alt_cam, dead_reckoning_flag = pointing_tracker.get_cam_azalt() - solved["camera_center"]["Az"] = np.rad2deg(az_cam) - solved["camera_center"]["Alt"] = np.rad2deg(alt_cam) - - # From the alignment. Add this offset to the camera center to get - # the scope altaz coordinates. TODO: This could be calculated once - # at alignment? Or when last solved - cam2scope_offset_az = last_image_solve["Az"] - last_image_solve["camera_center"]["Az"] - cam2scope_offset_alt = last_image_solve["Alt"] - last_image_solve["camera_center"]["Alt"] - # Transform to scope center TODO: need to define q_cam2scope - solved["Az"] = solved["camera_center"]["Az"] + cam2scope_offset_az - solved["Alt"] = solved["camera_center"]["Alt"] + cam2scope_offset_alt - - q_x2imu = imu["quat"] - logger.debug(" IMU quat = ({:}, {:}, {:}, {:}".format(q_x2imu.w, q_x2imu.x, q_x2imu.y, q_x2imu.z)) - - """ DISABLE - Use quaternions - # calc new alt/az - OLD method lis_imu = - last_image_solve["imu_pos"] imu_pos = imu["pos"] alt_offset = - imu_pos[IMU_ALT] - lis_imu[IMU_ALT] if flip_alt_offset: - alt_offset = ((alt_offset + 180) % 360 - 180) * -1 - else: - alt_offset = (alt_offset + 180) % 360 - 180 - solved["Alt"] = (last_image_solve["Alt"] - alt_offset) % 360 - solved["camera_center"]["Alt"] = ( - last_image_solve["camera_center"]["Alt"] - alt_offset - ) % 360 - - az_offset = imu_pos[IMU_AZ] - lis_imu[IMU_AZ] az_offset = - (az_offset + 180) % 360 - 180 solved["Az"] = - (last_image_solve["Az"] + az_offset) % 360 - solved["camera_center"]["Az"] = ( - last_image_solve["camera_center"]["Az"] + az_offset - ) % 360 - """ - - # N.B. Assumes that location hasn't changed since last solve Turn - # this into RA/DEC - ( - solved["RA"], - solved["Dec"], - ) = calc_utils.sf_utils.altaz_to_radec( - solved["Alt"], solved["Az"], dt - ) - # Calculate the roll at the target RA/Dec and compensate for the - # offset. - solved["Roll"] = ( - calc_utils.sf_utils.radec_to_roll( - solved["RA"], solved["Dec"], dt - ) - + solved["Roll_offset"] - ) + # Dead-reckoning using IMU + pointing_tracker.update_imu(imu["quat"]) # Latest IMU meas + + # Store estimate: + ra_cam, dec_cam, roll_cam, dead_reckoning_flag = pointing_tracker.get_cam_radec() + solved["camera_center"]["RA"] = np.rad2deg(ra_cam) + solved["camera_center"]["Dec"] = np.rad2deg(dec_cam) + solved["camera_center"]["Roll"] = np.rad2deg(roll_cam) + + # TODO: This part for cam2scope will probably be an issue for Altaz mounts + # From the alignment. Add this offset to the camera center to get + # the scope altaz coordinates. TODO: This could be calculated once + # at alignment? Or when last solved + cam2scope_offset_az = last_image_solve["Az"] - last_image_solve["camera_center"]["Az"] + cam2scope_offset_alt = last_image_solve["Alt"] - last_image_solve["camera_center"]["Alt"] + # Transform to scope center TODO: need to define q_cam2scope + solved["Az"] = solved["camera_center"]["Az"] + cam2scope_offset_az + solved["Alt"] = solved["camera_center"]["Alt"] + cam2scope_offset_alt - # Now for camera centered solve - ( - solved["camera_center"]["RA"], - solved["camera_center"]["Dec"], - ) = calc_utils.sf_utils.altaz_to_radec( - solved["camera_center"]["Alt"], - solved["camera_center"]["Az"], - dt, - ) - # Calculate the roll at the target RA/Dec and compensate for the - # offset. - solved["camera_center"]["Roll"] = ( - calc_utils.sf_utils.radec_to_roll( - solved["camera_center"]["RA"], - solved["camera_center"]["Dec"], - dt, - ) - + solved["Roll_offset"] - ) + q_x2imu = imu["quat"] + logger.debug(" IMU quat = ({:}, {:}, {:}, {:}".format(q_x2imu.w, q_x2imu.x, q_x2imu.y, q_x2imu.z)) - solved["solve_time"] = time.time() - solved["solve_source"] = "IMU" + solved["solve_time"] = time.time() + solved["solve_source"] = "IMU" def update_plate_solve_and_imu_eq__degrees(pointing_tracker, solved): """ - Wrapper for ImuDeadReckoning.update_plate_solve_and_imu() to interface - degrees to radians. + Wrapper for ImuDeadReckoningEqFrame.update_plate_solve_and_imu() to + interface degrees to radians. """ if (solved["Az"] is None) or (solved["Alt"] is None): return # No update @@ -370,12 +311,12 @@ def update_plate_solve_and_imu_eq__degrees(pointing_tracker, solved): # Successfully plate solved & camera pointing exists q_x2imu = solved["imu_quat"] # IMU measurement at the time of plate solving # Convert to radians: - solved_cam_az = np.deg2rad(solved["camera_center"]["Az"]) - solved_cam_alt = np.deg2rad(solved["camera_center"]["Alt"]) - solved_cam_roll_offset = np.deg2rad(solved["Roll_offset"]) + solved_cam_ra = np.deg2rad(solved["camera_center"]["RA"]) + solved_cam_dec = np.deg2rad(solved["camera_center"]["Dec"]) + solved_cam_roll = np.deg2rad(solved["Roll"]) # Update: pointing_tracker.update_plate_solve_and_imu( - solved_cam_az, solved_cam_alt, solved_cam_roll_offset, q_x2imu) + solved_cam_ra, solved_cam_dec, solved_cam_roll, q_x2imu) # ======== Altaz version - TODO remove and use the EQ version ====== @@ -460,7 +401,7 @@ def update_imu_altaz(solved, last_image_solve, imu, dt, pointing_tracker): # TODO: For debugging -- remove later #if prev_imu is None or qt.get_quat_angular_diff(prev_imu, imu["quat"]) > 1E-4: # print("Quat: ", imu["quat"]) - prev_imu = imu["quat"].copy() + #prev_imu = imu["quat"].copy() # calc new alt/az # When moving, switch to tracking using the IMU From 90585e000b3fadffbe4d4ee9b474ac210a759ef9 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 10 Aug 2025 22:43:49 +0100 Subject: [PATCH 093/253] Init commit of RaDecRoll data class --- .../PiFinder/pointing_model/astro_coords.py | 37 +++++++++++++++++++ 1 file changed, 37 insertions(+) create mode 100644 python/PiFinder/pointing_model/astro_coords.py diff --git a/python/PiFinder/pointing_model/astro_coords.py b/python/PiFinder/pointing_model/astro_coords.py new file mode 100644 index 000000000..d522f553e --- /dev/null +++ b/python/PiFinder/pointing_model/astro_coords.py @@ -0,0 +1,37 @@ +""" +Various astronomical coordinates functions +""" + +import numpy as np +from typing import Union # When updated to Python 3.10+, remove and use new type hints + + +class RaDecRoll(): + """ + Data class for equatorial coordinates defined by (RA, Dec, Roll). + + NOTE: All angles are in radians. + """ + + def __init__(self): + """ """ + self.ra = None + self.dec = None + self.roll = None + + def set(self, ra: float, dec:float, roll: Union[float, None]): + """ """ + self.ra = ra + self.dec = dec + self.roll = roll + + def set_from_deg(self, ra_deg, dec_deg, roll_deg): + """ """ + if roll_deg is None: + roll = None + else: + roll = np.deg2rad(roll_deg) + + self.set(np.deg2rad(ra_deg), np.deg2rad(dec_deg), roll) + + From 9a0a4ff0b9a24a433755ec4087184a653493988a Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 10 Aug 2025 22:52:31 +0100 Subject: [PATCH 094/253] Draft: calculating q_cam2scope (alignment) --- .../PiFinder/pointing_model/imu_dead_reckoning.py | 1 + .../pointing_model/quaternion_transforms.py | 14 ++++++++++++++ 2 files changed, 15 insertions(+) diff --git a/python/PiFinder/pointing_model/imu_dead_reckoning.py b/python/PiFinder/pointing_model/imu_dead_reckoning.py index efdc929d0..32a799b24 100644 --- a/python/PiFinder/pointing_model/imu_dead_reckoning.py +++ b/python/PiFinder/pointing_model/imu_dead_reckoning.py @@ -249,6 +249,7 @@ def set_alignment(self, INPUTS: q_scope2cam: Quaternion that rotates the scope frame to the camera frame. """ + # TODO: Use qt.get_q_scope2cam(target_eq, cam_eq) self.q_scope2cam = q_scope2cam.normalized() self.q_cam2scope = self.q_scope2cam.conj() self.q_imu2scope = self.q_imu2cam * self.q_cam2scope diff --git a/python/PiFinder/pointing_model/quaternion_transforms.py b/python/PiFinder/pointing_model/quaternion_transforms.py index 656eca335..d4f6eaa51 100644 --- a/python/PiFinder/pointing_model/quaternion_transforms.py +++ b/python/PiFinder/pointing_model/quaternion_transforms.py @@ -24,6 +24,8 @@ import numpy as np import quaternion +from PiFinder.pointing_model.astro_coords import RaDecRoll + def axis_angle2quat(axis, theta): """ @@ -99,6 +101,18 @@ def get_radec_of_q_eq2cam(q_eq2cam): return ra, dec, roll +def get_q_scope2cam(target_eq: RaDecRoll, cam_eq: RaDecRoll): + """ + Returns the quaternion that rotates from the scope frame to the camera frame. + """ + q_eq2cam = get_q_eq2cam(cam_eq.ra, cam_eq.dec, cam_eq.roll) + q_eq2scope = get_q_eq2cam(target_eq.ra, target_eq.dec, target_eq.roll) # This assumes an EQ mount - We don't know the roll of the scope frame + q_scope2cam = q_eq2scope.conj() * q_eq2cam + NotImplementedError # Needs more workk + + return q_scope2cam + + # ========== Horizontal (altaz) frame functions ============================ def get_q_hor2frame(az, alt): From 1433995f51875146147af46b246547e9f0662b40 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Mon, 11 Aug 2025 21:24:32 +0100 Subject: [PATCH 095/253] Reorder --- python/PiFinder/integrator.py | 77 +++++++++++++++++------------------ 1 file changed, 38 insertions(+), 39 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 26f6fed76..2925599de 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -251,6 +251,25 @@ def update_solve_eq(solved, location, dt, pointing_tracker): update_plate_solve_and_imu_eq__degrees(pointing_tracker, solved) +def update_plate_solve_and_imu_eq__degrees(pointing_tracker, solved): + """ + Wrapper for ImuDeadReckoningEqFrame.update_plate_solve_and_imu() to + interface degrees to radians. + """ + if (solved["Az"] is None) or (solved["Alt"] is None): + return # No update + else: + # Successfully plate solved & camera pointing exists + q_x2imu = solved["imu_quat"] # IMU measurement at the time of plate solving + # Convert to radians: + solved_cam_ra = np.deg2rad(solved["camera_center"]["RA"]) + solved_cam_dec = np.deg2rad(solved["camera_center"]["Dec"]) + solved_cam_roll = np.deg2rad(solved["Roll"]) + # Update: + pointing_tracker.update_plate_solve_and_imu( + solved_cam_ra, solved_cam_dec, solved_cam_roll, q_x2imu) + + def update_imu_eq(solved, last_image_solve, imu, dt, pointing_tracker): """ Updates the solved dictionary using IMU dead-reckoning from the last @@ -300,25 +319,6 @@ def update_imu_eq(solved, last_image_solve, imu, dt, pointing_tracker): solved["solve_source"] = "IMU" -def update_plate_solve_and_imu_eq__degrees(pointing_tracker, solved): - """ - Wrapper for ImuDeadReckoningEqFrame.update_plate_solve_and_imu() to - interface degrees to radians. - """ - if (solved["Az"] is None) or (solved["Alt"] is None): - return # No update - else: - # Successfully plate solved & camera pointing exists - q_x2imu = solved["imu_quat"] # IMU measurement at the time of plate solving - # Convert to radians: - solved_cam_ra = np.deg2rad(solved["camera_center"]["RA"]) - solved_cam_dec = np.deg2rad(solved["camera_center"]["Dec"]) - solved_cam_roll = np.deg2rad(solved["Roll"]) - # Update: - pointing_tracker.update_plate_solve_and_imu( - solved_cam_ra, solved_cam_dec, solved_cam_roll, q_x2imu) - - # ======== Altaz version - TODO remove and use the EQ version ====== def update_solve_altaz(solved, location, dt, pointing_tracker): @@ -382,6 +382,25 @@ def update_solve_altaz(solved, location, dt, pointing_tracker): update_plate_solve_and_imu_altaz__degrees(pointing_tracker, solved) +def update_plate_solve_and_imu_altaz__degrees(pointing_tracker, solved): + """ + Wrapper for ImuDeadReckoning.update_plate_solve_and_imu() to interface + degrees to radians. + """ + if (solved["Az"] is None) or (solved["Alt"] is None): + return # No update + else: + # Successfully plate solved & camera pointing exists + q_x2imu = solved["imu_quat"] # IMU measurement at the time of plate solving + # Convert to radians: + solved_cam_az = np.deg2rad(solved["camera_center"]["Az"]) + solved_cam_alt = np.deg2rad(solved["camera_center"]["Alt"]) + solved_cam_roll_offset = np.deg2rad(solved["Roll_offset"]) + # Update: + pointing_tracker.update_plate_solve_and_imu( + solved_cam_az, solved_cam_alt, solved_cam_roll_offset, q_x2imu) + + def update_imu_altaz(solved, last_image_solve, imu, dt, pointing_tracker): """ Updates the solved dictionary using IMU dead-reckoning from the last @@ -493,23 +512,3 @@ def update_imu_altaz(solved, last_image_solve, imu, dt, pointing_tracker): solved["solve_time"] = time.time() solved["solve_source"] = "IMU" - - -def update_plate_solve_and_imu_altaz__degrees(pointing_tracker, solved): - """ - Wrapper for ImuDeadReckoning.update_plate_solve_and_imu() to interface - degrees to radians. - """ - if (solved["Az"] is None) or (solved["Alt"] is None): - return # No update - else: - # Successfully plate solved & camera pointing exists - q_x2imu = solved["imu_quat"] # IMU measurement at the time of plate solving - # Convert to radians: - solved_cam_az = np.deg2rad(solved["camera_center"]["Az"]) - solved_cam_alt = np.deg2rad(solved["camera_center"]["Alt"]) - solved_cam_roll_offset = np.deg2rad(solved["Roll_offset"]) - # Update: - pointing_tracker.update_plate_solve_and_imu( - solved_cam_az, solved_cam_alt, solved_cam_roll_offset, q_x2imu) - From c11dfa47cb0f20494c34820c3dc3e32375675cd5 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Mon, 11 Aug 2025 21:30:05 +0100 Subject: [PATCH 096/253] Fix --- python/PiFinder/integrator.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 2925599de..136ab14a9 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -264,7 +264,7 @@ def update_plate_solve_and_imu_eq__degrees(pointing_tracker, solved): # Convert to radians: solved_cam_ra = np.deg2rad(solved["camera_center"]["RA"]) solved_cam_dec = np.deg2rad(solved["camera_center"]["Dec"]) - solved_cam_roll = np.deg2rad(solved["Roll"]) + solved_cam_roll = np.deg2rad(solved["camera_center"]["Roll"]) # Update: pointing_tracker.update_plate_solve_and_imu( solved_cam_ra, solved_cam_dec, solved_cam_roll, q_x2imu) From 2358dce725e6a9029cb82e0688b5874fcb7a0870 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Mon, 11 Aug 2025 22:22:33 +0100 Subject: [PATCH 097/253] Fix: was not returning ra, dec of scope --- python/PiFinder/pointing_model/imu_dead_reckoning.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/python/PiFinder/pointing_model/imu_dead_reckoning.py b/python/PiFinder/pointing_model/imu_dead_reckoning.py index 32a799b24..d9d6fb6c0 100644 --- a/python/PiFinder/pointing_model/imu_dead_reckoning.py +++ b/python/PiFinder/pointing_model/imu_dead_reckoning.py @@ -337,7 +337,8 @@ def get_scope_radec(self): to indicate if the estimate is from dead-reckoning (True) or from plate solving (False). """ - ra, dec, roll = qt.get_radec_of_q_eq2cam(self.q_eq2cam) + q_eq2scope = self.get_q_eq2scope() + ra, dec, roll = qt.get_radec_of_q_eq2cam(self.q_eq2scope) return ra, dec, roll, self.dead_reckoning # Angles are in radians def reset(self): From 28e9065c6a704e34235b755c42f1a5b4fcc82f80 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Mon, 11 Aug 2025 22:38:48 +0100 Subject: [PATCH 098/253] Set alignment between scope and camera --- python/PiFinder/integrator.py | 25 +++++++++++++++++++++++-- 1 file changed, 23 insertions(+), 2 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 136ab14a9..9389cb723 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -219,7 +219,6 @@ def update_solve_eq(solved, location, dt, pointing_tracker): ) solved["camera_center"]["Alt"] = alt solved["camera_center"]["Az"] = az - """ # Experimental: For monitoring roll offset # Estimate the roll offset due misalignment of the @@ -246,6 +245,7 @@ def update_solve_eq(solved, location, dt, pointing_tracker): solved["camera_center"]["Roll"] = ( roll_target_calculated + solved["Roll_offset"] ) + """ # Update with plate solved coordinates of camera center & IMU measurement update_plate_solve_and_imu_eq__degrees(pointing_tracker, solved) @@ -261,14 +261,27 @@ def update_plate_solve_and_imu_eq__degrees(pointing_tracker, solved): else: # Successfully plate solved & camera pointing exists q_x2imu = solved["imu_quat"] # IMU measurement at the time of plate solving + # Convert to radians: solved_cam_ra = np.deg2rad(solved["camera_center"]["RA"]) solved_cam_dec = np.deg2rad(solved["camera_center"]["Dec"]) solved_cam_roll = np.deg2rad(solved["camera_center"]["Roll"]) + # Convert to radians: + target_ra = np.deg2rad(solved["RA"]) + target_dec = np.deg2rad(solved["Dec"]) + solved["Roll"] = 0 # TODO: Target roll isn't calculated by Tetra3. Set to zero here + target_roll = np.deg2rad(solved["Roll"]) + # Update: pointing_tracker.update_plate_solve_and_imu( solved_cam_ra, solved_cam_dec, solved_cam_roll, q_x2imu) + # Set alignment: TODO: Do this once at alignment + q_eq2cam = qt.get_q_eq2cam(solved_cam_ra, solved_cam_dec, solved_cam_roll) + q_eq2scope = qt.get_q_eq2cam(rtarget_ra, target_dec, target_roll) + q_scope2cam = q_eq2scope.conjugate() * q_eq2cam + pointing_tracker.set_alignment(q_scope2cam) + def update_imu_eq(solved, last_image_solve, imu, dt, pointing_tracker): """ @@ -296,12 +309,19 @@ def update_imu_eq(solved, last_image_solve, imu, dt, pointing_tracker): # Dead-reckoning using IMU pointing_tracker.update_imu(imu["quat"]) # Latest IMU meas - # Store estimate: + # Store current camera pointing estimate: ra_cam, dec_cam, roll_cam, dead_reckoning_flag = pointing_tracker.get_cam_radec() solved["camera_center"]["RA"] = np.rad2deg(ra_cam) solved["camera_center"]["Dec"] = np.rad2deg(dec_cam) solved["camera_center"]["Roll"] = np.rad2deg(roll_cam) + # Store the current scope pointing estimate + ra_target, dec_target, roll_target, dead_reckoning_flag = pointing_tracker.get_scope_radec() + solved["RA"] = np.rad2deg(ra_target) + solved["Dec"] = np.rad2deg(dec_target) + solved["Roll"] = np.rad2deg(roll_target) + + """ # TODO: This part for cam2scope will probably be an issue for Altaz mounts # From the alignment. Add this offset to the camera center to get # the scope altaz coordinates. TODO: This could be calculated once @@ -311,6 +331,7 @@ def update_imu_eq(solved, last_image_solve, imu, dt, pointing_tracker): # Transform to scope center TODO: need to define q_cam2scope solved["Az"] = solved["camera_center"]["Az"] + cam2scope_offset_az solved["Alt"] = solved["camera_center"]["Alt"] + cam2scope_offset_alt + """ q_x2imu = imu["quat"] logger.debug(" IMU quat = ({:}, {:}, {:}, {:}".format(q_x2imu.w, q_x2imu.x, q_x2imu.y, q_x2imu.z)) From 71bb9f1c5d2222684472e6e1241a9fb388505740 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Mon, 11 Aug 2025 22:38:58 +0100 Subject: [PATCH 099/253] Add comments --- python/PiFinder/pointing_model/imu_dead_reckoning.py | 2 +- python/PiFinder/pointing_model/quaternion_transforms.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/python/PiFinder/pointing_model/imu_dead_reckoning.py b/python/PiFinder/pointing_model/imu_dead_reckoning.py index d9d6fb6c0..772a8b7e5 100644 --- a/python/PiFinder/pointing_model/imu_dead_reckoning.py +++ b/python/PiFinder/pointing_model/imu_dead_reckoning.py @@ -241,7 +241,7 @@ def __init__(self, screen_direction): self.q_eq2x = None def set_alignment(self, - q_scope2cam: quaternion.quaternion): + q_scope2cam: quaternion.quaternion): # TODO: Setting cam2scope might be more natural? """ Set the alignment between the PiFinder camera center and the scope pointing. diff --git a/python/PiFinder/pointing_model/quaternion_transforms.py b/python/PiFinder/pointing_model/quaternion_transforms.py index d4f6eaa51..1574cbf0e 100644 --- a/python/PiFinder/pointing_model/quaternion_transforms.py +++ b/python/PiFinder/pointing_model/quaternion_transforms.py @@ -60,7 +60,7 @@ def get_quat_angular_diff(q1, q2): # ========== Equatorial frame functions ============================ -def get_q_eq2cam(ra_rad, dec_rad, roll_rad): +def get_q_eq2cam(ra_rad, dec_rad, roll_rad): # TODO: Rename to q_eq2frame? """ Express the coordinates of a camera pointing at RA, Dec, Roll (in radians) in the relative to the Equatorial frame. From 81a43824d875726d76eb1043c62ffc4ce16753fc Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 16 Aug 2025 12:50:27 +0100 Subject: [PATCH 100/253] Remove Horiz version --- python/PiFinder/integrator.py | 227 +----------------- .../pointing_model/imu_dead_reckoning.py | 176 -------------- .../pointing_model/quaternion_transforms.py | 34 --- 3 files changed, 12 insertions(+), 425 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 9389cb723..4f1dca2ed 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -18,19 +18,15 @@ from PiFinder import state_utils import PiFinder.calc_utils as calc_utils from PiFinder.multiproclogging import MultiprocLogging -from PiFinder.pointing_model.imu_dead_reckoning import ImuDeadReckoningHoriz, ImuDeadReckoningEqFrame +from PiFinder.pointing_model.imu_dead_reckoning import ImuDeadReckoningEqFrame import PiFinder.pointing_model.quaternion_transforms as qt -# *** Unused --> Remove later -#IMU_ALT = 2 -#IMU_AZ = 0 -EQ_DEAD_RECKONING = False # Use the Equatorial frame dead-reckoning - -IMU_MOVED_ANG_THRESHOLD = np.deg2rad(0.1) # Use IMU tracking if the angle moved is above this - logger = logging.getLogger("IMU.Integrator") +# Constants: +IMU_MOVED_ANG_THRESHOLD = np.deg2rad(0.1) # Use IMU tracking if the angle moved is above this + # TODO: Remove this after migrating to quaternion def imu_moved(imu_a, imu_b): @@ -102,7 +98,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr flip_alt_offset = False # Set up dead-reckoning tracking by the IMU: - pointing_tracker = ImuDeadReckoningHoriz(cfg.get_option("screen_direction")) + pointing_tracker = ImuDeadReckoningEqFrame(cfg.get_option("screen_direction")) #pointing_tracker.set_alignment(q_scope2cam) # TODO: Enable when q_scope2cam is available # This holds the last image solve position info @@ -128,11 +124,8 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr dt = shared_state.datetime() if location and dt: - # We have position and time/date! - if EQ_DEAD_RECKONING: - update_solve_eq(solved, location, dt, pointing_tracker) - else: - update_solve_altaz(solved, location, dt, pointing_tracker) # TODO: Remove later + # We have position and time/date! TODO: Check if this dt is needed + update_solve_eq(solved, location, dt, pointing_tracker) last_image_solve = copy.deepcopy(solved) solved["solve_source"] = "CAM" @@ -143,11 +136,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr imu = shared_state.imu() if imu: dt = shared_state.datetime() - if EQ_DEAD_RECKONING: - update_imu_eq(solved, last_image_solve, imu, dt, pointing_tracker) - else: - # TODO: Remove later - update_imu_altaz(solved, last_image_solve, imu, dt, pointing_tracker) + update_imu_eq(solved, last_image_solve, imu, dt, pointing_tracker) # Is the solution new? if solved["RA"] and solved["solve_time"] > last_solve_time: @@ -254,7 +243,10 @@ def update_solve_eq(solved, location, dt, pointing_tracker): def update_plate_solve_and_imu_eq__degrees(pointing_tracker, solved): """ Wrapper for ImuDeadReckoningEqFrame.update_plate_solve_and_imu() to - interface degrees to radians. + interface angles in degrees to radians. + + This updates the pointing model with the plate-solved coordinates and the + IMU measurements which are assumed to have been taken at the same time. """ if (solved["Az"] is None) or (solved["Alt"] is None): return # No update @@ -338,198 +330,3 @@ def update_imu_eq(solved, last_image_solve, imu, dt, pointing_tracker): solved["solve_time"] = time.time() solved["solve_source"] = "IMU" - - -# ======== Altaz version - TODO remove and use the EQ version ====== - -def update_solve_altaz(solved, location, dt, pointing_tracker): - """ - Updates the solved dic based on the plate-solved coordinates. Uses the - altaz coordinates and horizontal frame for IMU tracking. Moved from the - loop inside integrator integrator - """ - assert location and dt, "Need location and time" - - solved["Alt"] = None - solved["Az"] = None - calc_utils.sf_utils.set_location( - location.lat, - location.lon, - location.altitude, - ) - alt, az = calc_utils.sf_utils.radec_to_altaz( - solved["RA"], - solved["Dec"], - dt, - ) - solved["Alt"] = alt - solved["Az"] = az - - alt, az = calc_utils.sf_utils.radec_to_altaz( - solved["camera_center"]["RA"], - solved["camera_center"]["Dec"], - dt, - ) - solved["camera_center"]["Alt"] = alt - solved["camera_center"]["Az"] = az - - # Experimental: For monitoring roll offset - # Estimate the roll offset due misalignment of the - # camera sensor with the Pole-to-Source great circle. - solved["Roll_offset"] = estimate_roll_offset(solved, dt) - # Find the roll at the target RA/Dec. Note that this doesn't include the - # roll offset so it's not the roll that the PiFinder cameara sees but the - # roll relative to the celestial pole given the RA and Dec. - roll_target_calculated = calc_utils.sf_utils.radec_to_roll( - solved["RA"], solved["Dec"], dt - ) - # Compensate for the roll offset. This gives the roll at the target - # as seen by the camera. - solved["Roll"] = roll_target_calculated + solved["Roll_offset"] - - # calculate roll for camera center - roll_target_calculated = calc_utils.sf_utils.radec_to_roll( - solved["camera_center"]["RA"], - solved["camera_center"]["Dec"], - dt, - ) - # Compensate for the roll offset. This gives the roll at the target - # as seen by the camera. - solved["camera_center"]["Roll"] = ( - roll_target_calculated + solved["Roll_offset"] - ) - - # Update with plate solved coordinates of camera center & IMU measurement - update_plate_solve_and_imu_altaz__degrees(pointing_tracker, solved) - - -def update_plate_solve_and_imu_altaz__degrees(pointing_tracker, solved): - """ - Wrapper for ImuDeadReckoning.update_plate_solve_and_imu() to interface - degrees to radians. - """ - if (solved["Az"] is None) or (solved["Alt"] is None): - return # No update - else: - # Successfully plate solved & camera pointing exists - q_x2imu = solved["imu_quat"] # IMU measurement at the time of plate solving - # Convert to radians: - solved_cam_az = np.deg2rad(solved["camera_center"]["Az"]) - solved_cam_alt = np.deg2rad(solved["camera_center"]["Alt"]) - solved_cam_roll_offset = np.deg2rad(solved["Roll_offset"]) - # Update: - pointing_tracker.update_plate_solve_and_imu( - solved_cam_az, solved_cam_alt, solved_cam_roll_offset, q_x2imu) - - -def update_imu_altaz(solved, last_image_solve, imu, dt, pointing_tracker): - """ - Updates the solved dictionary using IMU dead-reckoning from the last - solved pointing. - """ - # Use IMU dead-reckoning from the last camera solve: - # 1) Check we have an alt/az solve, otherwise we can't use the IMU - # If Alt exists: - # 2) Calculate the difference in the IMU measurements since the - # last plage solve. IMU "pos" is stored as Alt/Az. - # 3) Add the relative Alt/Az difference from the IMU to the plate - # -solved Alt/Az to give a dead-reckoning estimate of the current - # position. - if last_image_solve and last_image_solve["Alt"]: - # If we have alt, then we have a position/time - - # TODO: For debugging -- remove later - #if prev_imu is None or qt.get_quat_angular_diff(prev_imu, imu["quat"]) > 1E-4: - # print("Quat: ", imu["quat"]) - #prev_imu = imu["quat"].copy() - - # calc new alt/az - # When moving, switch to tracking using the IMU - #if imu_moved(lis_imu, imu_pos): - assert isinstance(imu["quat"] , quaternion.quaternion), "Expecting quaternion.quaternion type" # TODO: Remove later - angle_moved = qt.get_quat_angular_diff(last_image_solve["imu_quat"], imu["quat"]) - if angle_moved > IMU_MOVED_ANG_THRESHOLD: - # Estimate camera pointing using IMU dead-reckoning - logger.debug("Track using IMU. Angle moved since last_image_solve = " - "{:}(> threshold = {:})".format(np.rad2deg(angle_moved), - np.rad2deg(IMU_MOVED_ANG_THRESHOLD))) - - # Dead-reckoning using IMU - pointing_tracker.update_imu(imu["quat"]) # Latest IMU meas - - # Store estimate: - az_cam, alt_cam, dead_reckoning_flag = pointing_tracker.get_cam_azalt() - solved["camera_center"]["Az"] = np.rad2deg(az_cam) - solved["camera_center"]["Alt"] = np.rad2deg(alt_cam) - - # From the alignment. Add this offset to the camera center to get - # the scope altaz coordinates. TODO: This could be calculated once - # at alignment? Or when last solved - cam2scope_offset_az = last_image_solve["Az"] - last_image_solve["camera_center"]["Az"] - cam2scope_offset_alt = last_image_solve["Alt"] - last_image_solve["camera_center"]["Alt"] - # Transform to scope center TODO: need to define q_cam2scope - solved["Az"] = solved["camera_center"]["Az"] + cam2scope_offset_az - solved["Alt"] = solved["camera_center"]["Alt"] + cam2scope_offset_alt - - q_x2imu = imu["quat"] - logger.debug(" IMU quat = ({:}, {:}, {:}, {:}".format(q_x2imu.w, q_x2imu.x, q_x2imu.y, q_x2imu.z)) - - """ DISABLE - Use quaternions - # calc new alt/az - OLD method lis_imu = - last_image_solve["imu_pos"] imu_pos = imu["pos"] alt_offset = - imu_pos[IMU_ALT] - lis_imu[IMU_ALT] if flip_alt_offset: - alt_offset = ((alt_offset + 180) % 360 - 180) * -1 - else: - alt_offset = (alt_offset + 180) % 360 - 180 - solved["Alt"] = (last_image_solve["Alt"] - alt_offset) % 360 - solved["camera_center"]["Alt"] = ( - last_image_solve["camera_center"]["Alt"] - alt_offset - ) % 360 - - az_offset = imu_pos[IMU_AZ] - lis_imu[IMU_AZ] az_offset = - (az_offset + 180) % 360 - 180 solved["Az"] = - (last_image_solve["Az"] + az_offset) % 360 - solved["camera_center"]["Az"] = ( - last_image_solve["camera_center"]["Az"] + az_offset - ) % 360 - """ - - # N.B. Assumes that location hasn't changed since last solve Turn - # this into RA/DEC - ( - solved["RA"], - solved["Dec"], - ) = calc_utils.sf_utils.altaz_to_radec( - solved["Alt"], solved["Az"], dt - ) - # Calculate the roll at the target RA/Dec and compensate for the - # offset. - solved["Roll"] = ( - calc_utils.sf_utils.radec_to_roll( - solved["RA"], solved["Dec"], dt - ) - + solved["Roll_offset"] - ) - - # Now for camera centered solve - ( - solved["camera_center"]["RA"], - solved["camera_center"]["Dec"], - ) = calc_utils.sf_utils.altaz_to_radec( - solved["camera_center"]["Alt"], - solved["camera_center"]["Az"], - dt, - ) - # Calculate the roll at the target RA/Dec and compensate for the - # offset. - solved["camera_center"]["Roll"] = ( - calc_utils.sf_utils.radec_to_roll( - solved["camera_center"]["RA"], - solved["camera_center"]["Dec"], - dt, - ) - + solved["Roll_offset"] - ) - - solved["solve_time"] = time.time() - solved["solve_source"] = "IMU" diff --git a/python/PiFinder/pointing_model/imu_dead_reckoning.py b/python/PiFinder/pointing_model/imu_dead_reckoning.py index 772a8b7e5..078ea650d 100644 --- a/python/PiFinder/pointing_model/imu_dead_reckoning.py +++ b/python/PiFinder/pointing_model/imu_dead_reckoning.py @@ -12,182 +12,6 @@ import PiFinder.pointing_model.quaternion_transforms as qt -class ImuDeadReckoningHoriz(): - """ - Dead reckoning tracking using the IMU - wrt Horizontal frame - - Use the plate-solved coordinates and IMU measurements to estimate the - pointing using plate solving when available or dead-reckoning using the IMU - when plate solving isn't available (e.g. when the scope is moving or - between frames). - - All angles are in radians. - - HOW IT WORKS: - The IMU quaternion measurements, q_x2imu, are relative to some arbitrary - drifting frame X. This uses the latest plate solved coordinate with the - latest IMU measurement to solve for the IMU's reference frame X. The frame - X is expressed by the quaternion rotation q_hor2x from the Horizontal frame - to X. Once we know q_hor2x, we can infer the camera pointing using the IMU - data by dead reckoning: q_hor2cam = q_hor2x * q_x2imu * q_imu2cam - - EXAMPLE: - # Set up: - pointing_tracker = ImuDeadReckoning('flat') - pointing_tracker.set_alignment(q_scope2cam) - - # Update with plate solved and IMU data: - pointing_tracker.update_plate_solve_and_imu(solved_cam_az, solved_cam_alt, q_x2imu) - q_hor2scope = pointing_tracker.get_q_hor2scope() - - # Dead-reckoning using IMU - pointing_tracker.update_imu(q_x2imu) - q_hor2scope = pointing_tracker.get_q_hor2scope() - az, alt = pointing_tracker.get_cam_azalt() - """ - - def __init__(self, screen_direction): - """ """ - # IMU-to-camera orientation. Fixed by PiFinder type - self._set_screen_direction(screen_direction) - - # Alignment: - self.q_scope2cam = None - self.q_cam2scope = None - - # The poinging of the camera and scope frames wrt the horizontal frame. - # These get updated by plate solving and IMU dead-reckoning. - self.q_hor2cam = None - - # True when q_hor2cam is estimated by IMU dead-reckoning. - # False when set by plate solving - self.dead_reckoning = False - self.tracking = False # True when previous plate solve exists and tracking - - # The IMU's unkonwn drifting reference frame X. This is solved for - # every time we have a simultaneous plate solve and IMU measurement. - self.q_hor2x = None - - def set_alignment(self, - q_scope2cam: quaternion.quaternion): - """ - Set the alignment between the PiFinder camera center and the scope - pointing. - - INPUTS: - q_scope2cam: Quaternion that rotates the scope frame to the camera frame. - """ - self.q_scope2cam = q_scope2cam.normalized() - self.q_cam2scope = self.q_scope2cam.conj() - - def update_plate_solve_and_imu(self, - solved_cam_az: Union[float, None], - solved_cam_alt: Union[float, None], - solved_cam_roll_offset: Union[float, None], - q_x2imu: Union[quaternion.quaternion, None]): - """ - Update the state with the az/alt measurements from plate solving in the - camera frame. If the IMU measurement (which should be taken at the same - time) is available, q_x2imu (the unknown drifting reference frame) will - be solved for. - - INPUTS: - solved_cam_az: [rad] Azimuth of the camera pointing from plate solving. - solved_cam_alt: [rad] Alt of the camera pointing from plate solving. - solved_cam_roll_offset: [rad] Roll offset of the camera frame +y ("up") - relative to the pole. - q_x2imu: [quaternion] Raw IMU measurement quaternions. This is the IMU - frame orientation wrt unknown drifting reference frame X. - """ - if (solved_cam_az is None) or (solved_cam_alt is None): - return # No update - else: - # Camera frame relative to the horizontal frame where the +y camera - # frame (i.e. "up") points to zenith: - q_hor2cam_up = qt.get_q_hor2frame(solved_cam_az, solved_cam_alt) - # Account for camera rotation around the +z camera frame - q_cam_rot_z = np.quaternion(np.cos(solved_cam_roll_offset / 2), - 0, 0, np.sin(solved_cam_roll_offset / 2)) - # Combine (intrinsic rotation) - self.q_hor2cam = (q_hor2cam_up * q_cam_rot_z).normalized() - self.dead_reckoning = False - - # Calculate the IMU's unknown reference frame X using the plate solved - # coordinates and IMU measurements taken from the same time. If the IMU - # measurement isn't provided (e.g. None or zeros), the existing q_hor2x - # will continue to be used. - if q_x2imu: - self.q_hor2x = self.q_hor2cam * self.q_cam2imu * q_x2imu.conj() - self.q_hor2x = self.q_hor2x.normalized() - self.tracking = True # We have a plate solve and IMU measurement - - def update_imu(self, - q_x2imu: quaternion.quaternion): - """ - Update the state with the raw IMU measurement. Does a dead-reckoning - estimate of the camera and scope pointing. - - INPUTS: - q_x2imu: Quaternion of the IMU orientation w.r.t. an unknown and drifting - reference frame X used by the IMU. - """ - if self.q_hor2x is not None: - # Dead reckoning estimate by IMU if q_hor2x has been estimated by a - # previous plate solve. - self.q_hor2cam = self.q_hor2x * q_x2imu * self.q_imu2cam - self.q_hor2cam = self.q_hor2cam.normalized() - - self.dead_reckoning = True - - def get_q_hor2scope(self): - """ """ - if self.q_hor2cam and self.q_cam2scope: - q_hor2scope = self.q_hor2cam * self.q_cam2scope - return q_hor2scope - else: - None - - def get_cam_azalt(self): - """ - Returns the (az, alt) of the camera and a Boolean dead_reckoning to - indicate if the estimate is from dead-reckoning (True) or from plate - solving (False). - """ - az_cam, alt_cam = qt.get_azalt_of_q_hor2frame(self.q_hor2cam) - return az_cam, alt_cam, self.dead_reckoning # Angles are in radians - - def get_scope_azalt(self): - """ """ - NotImplementedError() - - def reset(self): - """ - Resets the internal state. - """ - self.q_hor2x = None - self.tracking = False - - def _set_screen_direction(self, screen_direction: str): - """ - Sets the screen direction which determines the fixed orientation between - the IMU and camera (q_imu2cam). - """ - if screen_direction == "flat": - # Rotate -90° around y_imu so that z_imu' points along z_camera - q1 = np.quaternion(np.cos(-np.pi / 4), 0, np.sin(-np.pi / 4), 0) - # Rotate -90° around z_imu' to align with the camera cooridnates - q2 = np.quaternion(np.cos(-np.pi / 4), 0, 0, np.sin(-np.pi / 4)) - self.q_imu2cam = q1 * q2 # Intrinsic rotation: q1 followed by q2 - else: - raise ValueError('Unsupported screen_direction') - - self.q_imu2cam = self.q_imu2cam.normalized() - self.q_cam2imu = self.q_imu2cam.conj() - - -# ==== Equatorial frame version ==== - - class ImuDeadReckoningEqFrame(): """ Use the plate-solved coordinates and IMU measurements to estimate the diff --git a/python/PiFinder/pointing_model/quaternion_transforms.py b/python/PiFinder/pointing_model/quaternion_transforms.py index 1574cbf0e..21cc400f5 100644 --- a/python/PiFinder/pointing_model/quaternion_transforms.py +++ b/python/PiFinder/pointing_model/quaternion_transforms.py @@ -111,37 +111,3 @@ def get_q_scope2cam(target_eq: RaDecRoll, cam_eq: RaDecRoll): NotImplementedError # Needs more workk return q_scope2cam - - -# ========== Horizontal (altaz) frame functions ============================ - -def get_q_hor2frame(az, alt): - """ - Returns the quaternion to rotate from the horizontal frame to the frame - (typically scope) at coordinates (az, alt) for an ideal AltAz mount. - - INPUTS: - az: [rad] Azimuth of scope axis - alt: [rad] Alt of scope axis - """ - q_az = axis_angle2quat([0, 0, 1], -(az + np.pi / 2)) - q_alt = axis_angle2quat([1, 0, 0], (np.pi / 2 - alt)) - return q_az * q_alt - - -def get_azalt_of_q_hor2frame(q_hor2frame): - """ - Returns the (az, alt) pointing of the frame which is defined by the z axis - of the q_hor2frame quaternion. - - RETURNS: - az: [rad] - alt: [rad] - """ - pz = np.quaternion(0, 0, 0, 1) # Vector z represented as a pure quaternion - frame_axis = q_hor2frame * pz * q_hor2frame.conj() # Returns a pure quaternion along scope axis - - alt = np.pi / 2 - np.arccos(frame_axis.z) - az = np.pi - np.arctan2(frame_axis.y, frame_axis.x) - - return az, alt From 360144f535d9d12e9d5d38489589340c8757b248 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 16 Aug 2025 12:52:30 +0100 Subject: [PATCH 101/253] integrator.py: Fix to get it working for EQ version --- python/PiFinder/integrator.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 4f1dca2ed..25b178236 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -248,7 +248,7 @@ def update_plate_solve_and_imu_eq__degrees(pointing_tracker, solved): This updates the pointing model with the plate-solved coordinates and the IMU measurements which are assumed to have been taken at the same time. """ - if (solved["Az"] is None) or (solved["Alt"] is None): + if (solved["RA"] is None) or (solved["Dec"] is None): return # No update else: # Successfully plate solved & camera pointing exists @@ -270,7 +270,7 @@ def update_plate_solve_and_imu_eq__degrees(pointing_tracker, solved): # Set alignment: TODO: Do this once at alignment q_eq2cam = qt.get_q_eq2cam(solved_cam_ra, solved_cam_dec, solved_cam_roll) - q_eq2scope = qt.get_q_eq2cam(rtarget_ra, target_dec, target_roll) + q_eq2scope = qt.get_q_eq2cam(target_ra, target_dec, target_roll) q_scope2cam = q_eq2scope.conjugate() * q_eq2cam pointing_tracker.set_alignment(q_scope2cam) From f3cf177037d977bcc5f3600506178a0cf6cfb3f0 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 16 Aug 2025 15:03:43 +0100 Subject: [PATCH 102/253] Remove unused code block --- python/PiFinder/integrator.py | 101 +--------------------------------- 1 file changed, 3 insertions(+), 98 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 25b178236..9ba92d64d 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -28,28 +28,6 @@ IMU_MOVED_ANG_THRESHOLD = np.deg2rad(0.1) # Use IMU tracking if the angle moved is above this -# TODO: Remove this after migrating to quaternion -def imu_moved(imu_a, imu_b): - """ - Compares two IMU states to determine if they are the 'same' - if either is none, returns False - - **TODO: This imu_a and imu_b used to be pos. They are now quaternions** - """ - if imu_a is None: - return False - if imu_b is None: - return False - - # figure out the abs difference - diff = ( - abs(imu_a[0] - imu_b[0]) + abs(imu_a[1] - imu_b[1]) + abs(imu_a[2] - imu_b[2]) - ) - if diff > 0.001: - return True - return False - - def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=True): # TODO: Change back is_debug=False MultiprocLogging.configurer(log_queue) try: @@ -125,7 +103,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr if location and dt: # We have position and time/date! TODO: Check if this dt is needed - update_solve_eq(solved, location, dt, pointing_tracker) + update_plate_solve_and_imu_eq(pointing_tracker, solved) last_image_solve = copy.deepcopy(solved) solved["solve_source"] = "CAM" @@ -171,76 +149,9 @@ def estimate_roll_offset(solved, dt): return roll_offset -# ======== EQ version =============================== - -def update_solve_eq(solved, location, dt, pointing_tracker): - """ - Updates the solved dic based on the plate-solved coordinates. Uses the - altaz coordinates and horizontal frame for IMU tracking. Moved from the - loop inside integrator integrator - """ - assert location and dt, "Need location and time" - - # Commented out Altaz coords which are not needed TODO: Remove these later - """ - solved["Alt"] = None - solved["Az"] = None - """ - # TODO: May be able to remove this later - calc_utils.sf_utils.set_location( - location.lat, - location.lon, - location.altitude, - ) - """ - alt, az = calc_utils.sf_utils.radec_to_altaz( - solved["RA"], - solved["Dec"], - dt, - ) - solved["Alt"] = alt - solved["Az"] = az - - alt, az = calc_utils.sf_utils.radec_to_altaz( - solved["camera_center"]["RA"], - solved["camera_center"]["Dec"], - dt, - ) - solved["camera_center"]["Alt"] = alt - solved["camera_center"]["Az"] = az - - # Experimental: For monitoring roll offset - # Estimate the roll offset due misalignment of the - # camera sensor with the Pole-to-Source great circle. - solved["Roll_offset"] = estimate_roll_offset(solved, dt) # TODO: Remove later? - # Find the roll at the target RA/Dec. Note that this doesn't include the - # roll offset so it's not the roll that the PiFinder cameara sees but the - # roll relative to the celestial pole given the RA and Dec. - roll_target_calculated = calc_utils.sf_utils.radec_to_roll( - solved["RA"], solved["Dec"], dt - ) - # Compensate for the roll offset. This gives the roll at the target - # as seen by the camera. - solved["Roll"] = roll_target_calculated + solved["Roll_offset"] - - # calculate roll for camera center - roll_target_calculated = calc_utils.sf_utils.radec_to_roll( - solved["camera_center"]["RA"], - solved["camera_center"]["Dec"], - dt, - ) - # Compensate for the roll offset. This gives the roll at the target - # as seen by the camera. - solved["camera_center"]["Roll"] = ( - roll_target_calculated + solved["Roll_offset"] - ) - """ - - # Update with plate solved coordinates of camera center & IMU measurement - update_plate_solve_and_imu_eq__degrees(pointing_tracker, solved) +# ======== Wrapper and helper functions =============================== - -def update_plate_solve_and_imu_eq__degrees(pointing_tracker, solved): +def update_plate_solve_and_imu_eq(pointing_tracker, solved): """ Wrapper for ImuDeadReckoningEqFrame.update_plate_solve_and_imu() to interface angles in degrees to radians. @@ -283,13 +194,7 @@ def update_imu_eq(solved, last_image_solve, imu, dt, pointing_tracker): if not(last_image_solve and pointing_tracker.tracking and dt): return # Need all of these to do IMU dead-reckoning - # TODO: For debugging -- remove later - #if prev_imu is None or qt.get_quat_angular_diff(prev_imu, imu["quat"]) > 1E-4: - # print("Quat: ", imu["quat"]) - #prev_imu = imu["quat"].copy() - # When moving, switch to tracking using the IMU - #if imu_moved(lis_imu, imu_pos): assert isinstance(imu["quat"] , quaternion.quaternion), "Expecting quaternion.quaternion type" # TODO: Remove later angle_moved = qt.get_quat_angular_diff(last_image_solve["imu_quat"], imu["quat"]) if angle_moved > IMU_MOVED_ANG_THRESHOLD: From e27e62b5f516e9676eb2f0dee00312056c47a836 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 16 Aug 2025 15:35:24 +0100 Subject: [PATCH 103/253] Move initialization of logger to outside try: --- python/PiFinder/integrator.py | 15 +++++++++------ 1 file changed, 9 insertions(+), 6 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 9ba92d64d..5a005eb2a 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -30,11 +30,12 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=True): # TODO: Change back is_debug=False MultiprocLogging.configurer(log_queue) - try: - if is_debug: - logger.setLevel(logging.DEBUG) - logger.debug("Starting Integrator") + """ """ + if is_debug: + logger.setLevel(logging.DEBUG) + logger.debug("Starting Integrator") + try: # TODO: This dict is duplicated in solver.py - Refactor? # "Alt" and "Az" could be removed once we move to Eq-based dead-reckoning solved = { @@ -131,6 +132,8 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr logger.error("Main no longer running for integrator") +# ======== Wrapper and helper functions =============================== + def estimate_roll_offset(solved, dt): """ Estimate the roll offset due to misalignment of the camera sensor with @@ -138,6 +141,8 @@ def estimate_roll_offset(solved, dt): center of the camera's FoV. To calculate the roll with offset: roll = calculated_roll + roll_offset + + TODO: This is currently not being used! """ # Calculate the expected roll at the camera center given the RA/Dec of # of the camera center. @@ -149,8 +154,6 @@ def estimate_roll_offset(solved, dt): return roll_offset -# ======== Wrapper and helper functions =============================== - def update_plate_solve_and_imu_eq(pointing_tracker, solved): """ Wrapper for ImuDeadReckoningEqFrame.update_plate_solve_and_imu() to From dd3e891454772408ed3de89d3e7a8b3c6ec95a23 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 16 Aug 2025 15:39:21 +0100 Subject: [PATCH 104/253] Move init of solved dict to external module. Desktop-tested. --- python/PiFinder/integrator.py | 31 ++------------ .../PiFinder/pointing_model/astro_coords.py | 40 +++++++++++++++++++ 2 files changed, 43 insertions(+), 28 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 5a005eb2a..ee8ee3c5c 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -18,6 +18,7 @@ from PiFinder import state_utils import PiFinder.calc_utils as calc_utils from PiFinder.multiproclogging import MultiprocLogging +from PiFinder.pointing_model.astro_coords import get_initialized_solved_dict from PiFinder.pointing_model.imu_dead_reckoning import ImuDeadReckoningEqFrame import PiFinder.pointing_model.quaternion_transforms as qt @@ -36,34 +37,8 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr logger.debug("Starting Integrator") try: - # TODO: This dict is duplicated in solver.py - Refactor? - # "Alt" and "Az" could be removed once we move to Eq-based dead-reckoning - solved = { - "RA": None, # RA of scope - "Dec": None, - "Roll": None, - "camera_center": { - "RA": None, - "Dec": None, - "Roll": None, - "Alt": None, # TODO: Remove Alt, Az keys later? - "Az": None, - }, - "camera_solve": { # camera_solve is NOT updated by IMU dead-reckoning - "RA": None, - "Dec": None, - "Roll": None, - }, - "Roll_offset": 0, # May/may not be needed - for experimentation - "imu_pos": None, - "imu_quat": None, # IMU quaternion as numpy quaternion (scalar-first) - TODO: Move to "imu" - "Alt": None, # Alt of scope - "Az": None, - "solve_source": None, - "solve_time": None, - "cam_solve_time": 0, - "constellation": None, - } + solved = get_initialized_solved_dict() # Dict of RA, Dec, etc. initialized to None. + cfg = config.Config() # TODO: Capture flip_alt_offset by q_imu2camera if ( diff --git a/python/PiFinder/pointing_model/astro_coords.py b/python/PiFinder/pointing_model/astro_coords.py index d522f553e..c82bc4fbf 100644 --- a/python/PiFinder/pointing_model/astro_coords.py +++ b/python/PiFinder/pointing_model/astro_coords.py @@ -6,6 +6,46 @@ from typing import Union # When updated to Python 3.10+, remove and use new type hints +def get_initialized_solved_dict(): + """ + Returns an initialized 'solved' dictionary with cooridnate and other + information. + + TODO: The solved dict is used by other components. Move this func + and use this elsewhere (e.g. solver.py) to enforce consistency. + """ + # TODO: This dict is duplicated in solver.py - Refactor? + # "Alt" and "Az" could be removed once we move to Eq-based dead-reckoning + solved = { + "RA": None, # RA of scope + "Dec": None, + "Roll": None, + "camera_center": { + "RA": None, + "Dec": None, + "Roll": None, + "Alt": None, # TODO: Remove Alt, Az keys later? + "Az": None, + }, + "camera_solve": { # camera_solve is NOT updated by IMU dead-reckoning + "RA": None, + "Dec": None, + "Roll": None, + }, + "Roll_offset": 0, # May/may not be needed - for experimentation + "imu_pos": None, + "imu_quat": None, # IMU quaternion as numpy quaternion (scalar-first) - TODO: Move to "imu" + "Alt": None, # Alt of scope + "Az": None, + "solve_source": None, + "solve_time": None, + "cam_solve_time": 0, + "constellation": None, + } + + return solved + + class RaDecRoll(): """ Data class for equatorial coordinates defined by (RA, Dec, Roll). From 88000516f9d3f3dcc01636c6e01b84c6e13b5799 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 16 Aug 2025 15:42:28 +0100 Subject: [PATCH 105/253] Remove setting of flip_alt_offset --> Not used. Desktop-tested. --- python/PiFinder/integrator.py | 11 ----------- 1 file changed, 11 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index ee8ee3c5c..ee040c114 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -38,18 +38,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr try: solved = get_initialized_solved_dict() # Dict of RA, Dec, etc. initialized to None. - cfg = config.Config() - # TODO: Capture flip_alt_offset by q_imu2camera - if ( - cfg.get_option("screen_direction") == "left" - or cfg.get_option("screen_direction") == "flat" - or cfg.get_option("screen_direction") == "flat3" - or cfg.get_option("screen_direction") == "straight" - ): - flip_alt_offset = True - else: - flip_alt_offset = False # Set up dead-reckoning tracking by the IMU: pointing_tracker = ImuDeadReckoningEqFrame(cfg.get_option("screen_direction")) From 7ad624dd5775b41c8154495c75138d821c43fd5c Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 16 Aug 2025 15:50:27 +0100 Subject: [PATCH 106/253] Remove setting of location and datetime in the integrator.py loop --> not used. Desktop-tested. --- python/PiFinder/integrator.py | 12 +++--------- 1 file changed, 3 insertions(+), 9 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index ee040c114..4ade63140 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -48,7 +48,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr # so we can delta for IMU updates last_image_solve = None last_solve_time = time.time() - #prev_imu = None # TODO: For debugging - remove later + while True: state_utils.sleep_for_framerate(shared_state) @@ -60,15 +60,9 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr pass if type(next_image_solve) is dict: - # We have a new image solve: Use this for RA/Dec + # We have a new image solve: Use plate-solving for RA/Dec solved = next_image_solve - - location = shared_state.location() - dt = shared_state.datetime() - - if location and dt: - # We have position and time/date! TODO: Check if this dt is needed - update_plate_solve_and_imu_eq(pointing_tracker, solved) + update_plate_solve_and_imu_eq(pointing_tracker, solved) last_image_solve = copy.deepcopy(solved) solved["solve_source"] = "CAM" From 2b22c0ffb72b705f58f067b056b84212c3bdc409 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 16 Aug 2025 15:54:32 +0100 Subject: [PATCH 107/253] Remove unused datetime. Desktop-tested. --- python/PiFinder/integrator.py | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 4ade63140..d3c6b4dbe 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -72,8 +72,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr # the last plate solved coordinates. imu = shared_state.imu() if imu: - dt = shared_state.datetime() - update_imu_eq(solved, last_image_solve, imu, dt, pointing_tracker) + update_imu_eq(solved, last_image_solve, imu, pointing_tracker) # Is the solution new? if solved["RA"] and solved["solve_time"] > last_solve_time: @@ -147,12 +146,12 @@ def update_plate_solve_and_imu_eq(pointing_tracker, solved): pointing_tracker.set_alignment(q_scope2cam) -def update_imu_eq(solved, last_image_solve, imu, dt, pointing_tracker): +def update_imu_eq(solved, last_image_solve, imu, pointing_tracker): """ Updates the solved dictionary using IMU dead-reckoning from the last solved pointing. """ - if not(last_image_solve and pointing_tracker.tracking and dt): + if not(last_image_solve and pointing_tracker.tracking): return # Need all of these to do IMU dead-reckoning # When moving, switch to tracking using the IMU From 2f93f087fe5c96d8e83def32656afd88d7823b4e Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 16 Aug 2025 15:56:58 +0100 Subject: [PATCH 108/253] Rename func --- python/PiFinder/integrator.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index d3c6b4dbe..db543b5a9 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -62,7 +62,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr if type(next_image_solve) is dict: # We have a new image solve: Use plate-solving for RA/Dec solved = next_image_solve - update_plate_solve_and_imu_eq(pointing_tracker, solved) + update_plate_solve_and_imu(pointing_tracker, solved) last_image_solve = copy.deepcopy(solved) solved["solve_source"] = "CAM" @@ -72,7 +72,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr # the last plate solved coordinates. imu = shared_state.imu() if imu: - update_imu_eq(solved, last_image_solve, imu, pointing_tracker) + update_imu(solved, last_image_solve, imu, pointing_tracker) # Is the solution new? if solved["RA"] and solved["solve_time"] > last_solve_time: @@ -111,7 +111,7 @@ def estimate_roll_offset(solved, dt): return roll_offset -def update_plate_solve_and_imu_eq(pointing_tracker, solved): +def update_plate_solve_and_imu(pointing_tracker, solved): """ Wrapper for ImuDeadReckoningEqFrame.update_plate_solve_and_imu() to interface angles in degrees to radians. @@ -146,7 +146,7 @@ def update_plate_solve_and_imu_eq(pointing_tracker, solved): pointing_tracker.set_alignment(q_scope2cam) -def update_imu_eq(solved, last_image_solve, imu, pointing_tracker): +def update_imu(solved, last_image_solve, imu, pointing_tracker): """ Updates the solved dictionary using IMU dead-reckoning from the last solved pointing. From 060f65a070acc3a4ae62eb91870982f6cbd5a9b0 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 16 Aug 2025 16:08:33 +0100 Subject: [PATCH 109/253] Refactor to set_alignment(). Desktop-tested. --- python/PiFinder/integrator.py | 33 +++++++++++++++++++++++++++------ 1 file changed, 27 insertions(+), 6 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index db543b5a9..45d9d5456 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -138,12 +138,33 @@ def update_plate_solve_and_imu(pointing_tracker, solved): # Update: pointing_tracker.update_plate_solve_and_imu( solved_cam_ra, solved_cam_dec, solved_cam_roll, q_x2imu) + + # Set alignment. TODO: Do this once at alignment + set_alignment(pointing_tracker, solved) + + +def set_alignment(pointing_tracker, solved): + """ + Set alignment. + TODO: Do this once at alignment + """ + # Convert to radians: + solved_cam_ra = np.deg2rad(solved["camera_center"]["RA"]) + solved_cam_dec = np.deg2rad(solved["camera_center"]["Dec"]) + solved_cam_roll = np.deg2rad(solved["camera_center"]["Roll"]) + # Convert to radians: + target_ra = np.deg2rad(solved["RA"]) + target_dec = np.deg2rad(solved["Dec"]) + solved["Roll"] = 0 # TODO: Target roll isn't calculated by Tetra3. Set to zero here + target_roll = np.deg2rad(solved["Roll"]) + + # Calculate q_scope2cam (alignment) + q_eq2cam = qt.get_q_eq2cam(solved_cam_ra, solved_cam_dec, solved_cam_roll) + q_eq2scope = qt.get_q_eq2cam(target_ra, target_dec, target_roll) + q_scope2cam = q_eq2scope.conjugate() * q_eq2cam - # Set alignment: TODO: Do this once at alignment - q_eq2cam = qt.get_q_eq2cam(solved_cam_ra, solved_cam_dec, solved_cam_roll) - q_eq2scope = qt.get_q_eq2cam(target_ra, target_dec, target_roll) - q_scope2cam = q_eq2scope.conjugate() * q_eq2cam - pointing_tracker.set_alignment(q_scope2cam) + # Set alignment in pointing_tracker + pointing_tracker.set_alignment(q_scope2cam) def update_imu(solved, last_image_solve, imu, pointing_tracker): @@ -155,7 +176,7 @@ def update_imu(solved, last_image_solve, imu, pointing_tracker): return # Need all of these to do IMU dead-reckoning # When moving, switch to tracking using the IMU - assert isinstance(imu["quat"] , quaternion.quaternion), "Expecting quaternion.quaternion type" # TODO: Remove later + assert isinstance(imu["quat"] , quaternion.quaternion), "Expecting quaternion.quaternion type" # TODO: Can be removed later angle_moved = qt.get_quat_angular_diff(last_image_solve["imu_quat"], imu["quat"]) if angle_moved > IMU_MOVED_ANG_THRESHOLD: # Estimate camera pointing using IMU dead-reckoning From 8395eb9a4c5e0e03b039f96fb6d41ef337b403bf Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 16 Aug 2025 16:10:36 +0100 Subject: [PATCH 110/253] Lint and update comments --- python/PiFinder/integrator.py | 16 ++-------------- 1 file changed, 2 insertions(+), 14 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 45d9d5456..38545419b 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -81,10 +81,10 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr solved["constellation"] = calc_utils.sf_utils.radec_to_constellation( solved["RA"], solved["Dec"] ) - # add solution shared_state.set_solution(solved) shared_state.set_solve_state(True) + except EOFError: logger.error("Main no longer running for integrator") @@ -139,7 +139,7 @@ def update_plate_solve_and_imu(pointing_tracker, solved): pointing_tracker.update_plate_solve_and_imu( solved_cam_ra, solved_cam_dec, solved_cam_roll, q_x2imu) - # Set alignment. TODO: Do this once at alignment + # Set alignment. TODO: Do this once at alignment. Move out of here. set_alignment(pointing_tracker, solved) @@ -199,18 +199,6 @@ def update_imu(solved, last_image_solve, imu, pointing_tracker): solved["Dec"] = np.rad2deg(dec_target) solved["Roll"] = np.rad2deg(roll_target) - """ - # TODO: This part for cam2scope will probably be an issue for Altaz mounts - # From the alignment. Add this offset to the camera center to get - # the scope altaz coordinates. TODO: This could be calculated once - # at alignment? Or when last solved - cam2scope_offset_az = last_image_solve["Az"] - last_image_solve["camera_center"]["Az"] - cam2scope_offset_alt = last_image_solve["Alt"] - last_image_solve["camera_center"]["Alt"] - # Transform to scope center TODO: need to define q_cam2scope - solved["Az"] = solved["camera_center"]["Az"] + cam2scope_offset_az - solved["Alt"] = solved["camera_center"]["Alt"] + cam2scope_offset_alt - """ - q_x2imu = imu["quat"] logger.debug(" IMU quat = ({:}, {:}, {:}, {:}".format(q_x2imu.w, q_x2imu.x, q_x2imu.y, q_x2imu.z)) From 6df3a18c7a1b136bdfc19960fd633e0c6673edc2 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 16 Aug 2025 16:12:54 +0100 Subject: [PATCH 111/253] Add comment --- python/PiFinder/pointing_model/astro_coords.py | 1 + 1 file changed, 1 insertion(+) diff --git a/python/PiFinder/pointing_model/astro_coords.py b/python/PiFinder/pointing_model/astro_coords.py index c82bc4fbf..ffd26a3fd 100644 --- a/python/PiFinder/pointing_model/astro_coords.py +++ b/python/PiFinder/pointing_model/astro_coords.py @@ -49,6 +49,7 @@ def get_initialized_solved_dict(): class RaDecRoll(): """ Data class for equatorial coordinates defined by (RA, Dec, Roll). + TODO: Migrate to something like this from the current "solved" dict? NOTE: All angles are in radians. """ From 0aee663008b26a859071f11735647a23fb07806f Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 16 Aug 2025 20:20:22 +0100 Subject: [PATCH 112/253] Rename class to ImuDeadReckoning . Desktop-tested. --- python/PiFinder/integrator.py | 6 +++--- python/PiFinder/pointing_model/imu_dead_reckoning.py | 4 ++-- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 38545419b..dc47614dd 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -19,7 +19,7 @@ import PiFinder.calc_utils as calc_utils from PiFinder.multiproclogging import MultiprocLogging from PiFinder.pointing_model.astro_coords import get_initialized_solved_dict -from PiFinder.pointing_model.imu_dead_reckoning import ImuDeadReckoningEqFrame +from PiFinder.pointing_model.imu_dead_reckoning import ImuDeadReckoning import PiFinder.pointing_model.quaternion_transforms as qt @@ -41,7 +41,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr cfg = config.Config() # Set up dead-reckoning tracking by the IMU: - pointing_tracker = ImuDeadReckoningEqFrame(cfg.get_option("screen_direction")) + pointing_tracker = ImuDeadReckoning(cfg.get_option("screen_direction")) #pointing_tracker.set_alignment(q_scope2cam) # TODO: Enable when q_scope2cam is available # This holds the last image solve position info @@ -113,7 +113,7 @@ def estimate_roll_offset(solved, dt): def update_plate_solve_and_imu(pointing_tracker, solved): """ - Wrapper for ImuDeadReckoningEqFrame.update_plate_solve_and_imu() to + Wrapper for ImuDeadReckoning.update_plate_solve_and_imu() to interface angles in degrees to radians. This updates the pointing model with the plate-solved coordinates and the diff --git a/python/PiFinder/pointing_model/imu_dead_reckoning.py b/python/PiFinder/pointing_model/imu_dead_reckoning.py index 078ea650d..aa0d4887a 100644 --- a/python/PiFinder/pointing_model/imu_dead_reckoning.py +++ b/python/PiFinder/pointing_model/imu_dead_reckoning.py @@ -12,7 +12,7 @@ import PiFinder.pointing_model.quaternion_transforms as qt -class ImuDeadReckoningEqFrame(): +class ImuDeadReckoning(): """ Use the plate-solved coordinates and IMU measurements to estimate the pointing using plate solving when available or dead-reckoning using the IMU @@ -28,7 +28,7 @@ class ImuDeadReckoningEqFrame(): EXAMPLE: # Set up: - pointing_tracker = ImuDeadReckoningEqFrame('flat') + pointing_tracker = ImuDeadReckoning('flat') pointing_tracker.set_alignment(q_scope2cam) # Update with plate solved and IMU data: From 0e95c074f48912b35c4320a203cbc2a2393ea344 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 16 Aug 2025 20:42:12 +0100 Subject: [PATCH 113/253] Add .get() methods --- python/PiFinder/pointing_model/astro_coords.py | 14 ++++++++++---- 1 file changed, 10 insertions(+), 4 deletions(-) diff --git a/python/PiFinder/pointing_model/astro_coords.py b/python/PiFinder/pointing_model/astro_coords.py index ffd26a3fd..e952b4487 100644 --- a/python/PiFinder/pointing_model/astro_coords.py +++ b/python/PiFinder/pointing_model/astro_coords.py @@ -6,7 +6,7 @@ from typing import Union # When updated to Python 3.10+, remove and use new type hints -def get_initialized_solved_dict(): +def get_initialized_solved_dict() -> dict: """ Returns an initialized 'solved' dictionary with cooridnate and other information. @@ -48,7 +48,7 @@ def get_initialized_solved_dict(): class RaDecRoll(): """ - Data class for equatorial coordinates defined by (RA, Dec, Roll). + Concept data class for equatorial coordinates defined by (RA, Dec, Roll). TODO: Migrate to something like this from the current "solved" dict? NOTE: All angles are in radians. @@ -60,13 +60,13 @@ def __init__(self): self.dec = None self.roll = None - def set(self, ra: float, dec:float, roll: Union[float, None]): + def set(self, ra:float, dec:float, roll:Union[float, None]): """ """ self.ra = ra self.dec = dec self.roll = roll - def set_from_deg(self, ra_deg, dec_deg, roll_deg): + def set_from_deg(self, ra_deg:float, dec_deg:float, roll_deg:float): """ """ if roll_deg is None: roll = None @@ -75,4 +75,10 @@ def set_from_deg(self, ra_deg, dec_deg, roll_deg): self.set(np.deg2rad(ra_deg), np.deg2rad(dec_deg), roll) + def get(self) -> (foat, float, float): + """ """ + return self.ra, self.dec, self.roll + def get_deg(self) -> (float, float, float): + """ """ + return np.rad2deg(self.ra), np.rad2deg(self.dec), np.rad2deg(self.roll) From 6a0861a4ec8214ab907343aaf188298bf106a784 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 16 Aug 2025 21:11:54 +0100 Subject: [PATCH 114/253] Add type hints --- python/PiFinder/pointing_model/astro_coords.py | 2 +- python/PiFinder/pointing_model/quaternion_transforms.py | 8 ++++---- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/python/PiFinder/pointing_model/astro_coords.py b/python/PiFinder/pointing_model/astro_coords.py index e952b4487..9e5c92950 100644 --- a/python/PiFinder/pointing_model/astro_coords.py +++ b/python/PiFinder/pointing_model/astro_coords.py @@ -75,7 +75,7 @@ def set_from_deg(self, ra_deg:float, dec_deg:float, roll_deg:float): self.set(np.deg2rad(ra_deg), np.deg2rad(dec_deg), roll) - def get(self) -> (foat, float, float): + def get(self) -> (float, float, float): """ """ return self.ra, self.dec, self.roll diff --git a/python/PiFinder/pointing_model/quaternion_transforms.py b/python/PiFinder/pointing_model/quaternion_transforms.py index 21cc400f5..75ad1e302 100644 --- a/python/PiFinder/pointing_model/quaternion_transforms.py +++ b/python/PiFinder/pointing_model/quaternion_transforms.py @@ -27,7 +27,7 @@ from PiFinder.pointing_model.astro_coords import RaDecRoll -def axis_angle2quat(axis, theta): +def axis_angle2quat(axis, theta:float) -> np.quaternion: """ Convert from axis-angle representation to a quaternion @@ -42,7 +42,7 @@ def axis_angle2quat(axis, theta): return np.quaternion(np.cos(theta / 2), v[0], v[1], v[2]) -def get_quat_angular_diff(q1, q2): +def get_quat_angular_diff(q1:np.quaternion, q2:np.quaternion) -> float: """ Calculates the relative rotation between quaternions `q1` and `q2`. Accounts for the double-cover property of quaternions so that if q1 and q2 @@ -60,7 +60,7 @@ def get_quat_angular_diff(q1, q2): # ========== Equatorial frame functions ============================ -def get_q_eq2cam(ra_rad, dec_rad, roll_rad): # TODO: Rename to q_eq2frame? +def get_q_eq2cam(ra_rad:float, dec_rad:float, roll_rad:float) -> np.quaternion: # TODO: Rename to q_eq2frame? """ Express the coordinates of a camera pointing at RA, Dec, Roll (in radians) in the relative to the Equatorial frame. @@ -82,7 +82,7 @@ def get_q_eq2cam(ra_rad, dec_rad, roll_rad): # TODO: Rename to q_eq2frame? return q_eq2cam -def get_radec_of_q_eq2cam(q_eq2cam): +def get_radec_of_q_eq2cam(q_eq2cam:np.quaternion) -> (float, float, float): """ """ # Pure quaternion along camera boresight From 1af8e9af5ae82ebc9327f51706a9874387c5857c Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 16 Aug 2025 21:12:10 +0100 Subject: [PATCH 115/253] Add comments --- python/PiFinder/pointing_model/imu_dead_reckoning.py | 12 +++++++----- 1 file changed, 7 insertions(+), 5 deletions(-) diff --git a/python/PiFinder/pointing_model/imu_dead_reckoning.py b/python/PiFinder/pointing_model/imu_dead_reckoning.py index aa0d4887a..3d4b03453 100644 --- a/python/PiFinder/pointing_model/imu_dead_reckoning.py +++ b/python/PiFinder/pointing_model/imu_dead_reckoning.py @@ -1,5 +1,6 @@ """ -Pointing model functions. +IMU dead-reckoning extrapolates the scope pointing from the last plate-solved +coordinate using the IMU measurements. See quaternion_transforms.py for conventions used for quaternions. @@ -19,12 +20,13 @@ class ImuDeadReckoning(): when plate solving isn't available (e.g. when the scope is moving or between frames). - This class uses the Equatorial frame as the reference and expect plate-solved - coordinates in (ra, dec). + For an explanation of the theory and conventions used, see + PiFinder/pointing_model/README.md. - All angles are in radians. + This class uses the Equatorial frame as the reference and expects + plate-solved coordinates in (ra, dec). - HOW IT WORKS: + All angles are in radians. EXAMPLE: # Set up: From 594354e478fde1fdf12f71d79bfa35a6aa2639de Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 16 Aug 2025 21:12:42 +0100 Subject: [PATCH 116/253] Add comments --- python/PiFinder/pointing_model/quaternion_transforms.py | 1 + 1 file changed, 1 insertion(+) diff --git a/python/PiFinder/pointing_model/quaternion_transforms.py b/python/PiFinder/pointing_model/quaternion_transforms.py index 75ad1e302..835f61ea2 100644 --- a/python/PiFinder/pointing_model/quaternion_transforms.py +++ b/python/PiFinder/pointing_model/quaternion_transforms.py @@ -104,6 +104,7 @@ def get_radec_of_q_eq2cam(q_eq2cam:np.quaternion) -> (float, float, float): def get_q_scope2cam(target_eq: RaDecRoll, cam_eq: RaDecRoll): """ Returns the quaternion that rotates from the scope frame to the camera frame. + TODO: Update? """ q_eq2cam = get_q_eq2cam(cam_eq.ra, cam_eq.dec, cam_eq.roll) q_eq2scope = get_q_eq2cam(target_eq.ra, target_eq.dec, target_eq.roll) # This assumes an EQ mount - We don't know the roll of the scope frame From ee27efd5c0cf62ad0afde262e0043ce41736354e Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 16 Aug 2025 21:27:08 +0100 Subject: [PATCH 117/253] Type hints. Desktop-check --- .../pointing_model/imu_dead_reckoning.py | 16 +++++++++------- .../pointing_model/quaternion_transforms.py | 2 +- 2 files changed, 10 insertions(+), 8 deletions(-) diff --git a/python/PiFinder/pointing_model/imu_dead_reckoning.py b/python/PiFinder/pointing_model/imu_dead_reckoning.py index 3d4b03453..fdb2d9916 100644 --- a/python/PiFinder/pointing_model/imu_dead_reckoning.py +++ b/python/PiFinder/pointing_model/imu_dead_reckoning.py @@ -40,7 +40,7 @@ class ImuDeadReckoning(): pointing_tracker.update_imu(q_x2imu) """ - def __init__(self, screen_direction): + def __init__(self, screen_direction:str): """ """ # Alignment: self.q_scope2cam = None # ****Do we need this?? @@ -67,11 +67,13 @@ def __init__(self, screen_direction): self.q_eq2x = None def set_alignment(self, - q_scope2cam: quaternion.quaternion): # TODO: Setting cam2scope might be more natural? + q_scope2cam: np.quaternion): """ Set the alignment between the PiFinder camera center and the scope pointing. + TODO: Setting cam2scope might be more natural? + INPUTS: q_scope2cam: Quaternion that rotates the scope frame to the camera frame. """ @@ -84,7 +86,7 @@ def update_plate_solve_and_imu(self, solved_cam_ra: Union[float, None], solved_cam_dec: Union[float, None], solved_cam_roll: Union[float, None], - q_x2imu: Union[quaternion.quaternion, None]): + q_x2imu: Union[np.quaternion, None]): """ Update the state with the az/alt measurements from plate solving in the camera frame. If the IMU measurement (which should be taken at the same @@ -120,7 +122,7 @@ def update_plate_solve_and_imu(self, self.tracking = True # We have a plate solve and IMU measurement def update_imu(self, - q_x2imu: quaternion.quaternion): + q_x2imu: np.quaternion): """ Update the state with the raw IMU measurement. Does a dead-reckoning estimate of the camera and scope pointing. @@ -140,7 +142,7 @@ def update_imu(self, self.dead_reckoning = True - def get_q_eq2scope(self): + def get_q_eq2scope(self) -> Union[np.quaternion, None]: """ """ if self.q_eq2cam and self.q_cam2scope: q_eq2scope = self.q_eq2cam * self.q_cam2scope @@ -148,7 +150,7 @@ def get_q_eq2scope(self): else: None - def get_cam_radec(self): + def get_cam_radec(self) -> (float, float, float, bool): """ Returns the (ra, dec, roll) of the camera and a Boolean dead_reckoning to indicate if the estimate is from dead-reckoning (True) or from plate @@ -157,7 +159,7 @@ def get_cam_radec(self): ra, dec, roll = qt.get_radec_of_q_eq2cam(self.q_eq2cam) return ra, dec, roll, self.dead_reckoning # Angles are in radians - def get_scope_radec(self): + def get_scope_radec(self) -> (float, float, float, bool): """ Returns the (ra, dec, roll) of the scope and a Boolean dead_reckoning to indicate if the estimate is from dead-reckoning (True) or from plate diff --git a/python/PiFinder/pointing_model/quaternion_transforms.py b/python/PiFinder/pointing_model/quaternion_transforms.py index 835f61ea2..909a0453b 100644 --- a/python/PiFinder/pointing_model/quaternion_transforms.py +++ b/python/PiFinder/pointing_model/quaternion_transforms.py @@ -101,7 +101,7 @@ def get_radec_of_q_eq2cam(q_eq2cam:np.quaternion) -> (float, float, float): return ra, dec, roll -def get_q_scope2cam(target_eq: RaDecRoll, cam_eq: RaDecRoll): +def get_q_scope2cam(target_eq: RaDecRoll, cam_eq: RaDecRoll) -> np.quaternion: """ Returns the quaternion that rotates from the scope frame to the camera frame. TODO: Update? From 47b41941c85c6e2c8cb6072d3e5a51ea999c3a43 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 16 Aug 2025 21:32:22 +0100 Subject: [PATCH 118/253] Re-order --- .../PiFinder/pointing_model/astro_coords.py | 76 +++++++++---------- 1 file changed, 38 insertions(+), 38 deletions(-) diff --git a/python/PiFinder/pointing_model/astro_coords.py b/python/PiFinder/pointing_model/astro_coords.py index 9e5c92950..1bc12a5b1 100644 --- a/python/PiFinder/pointing_model/astro_coords.py +++ b/python/PiFinder/pointing_model/astro_coords.py @@ -6,6 +6,44 @@ from typing import Union # When updated to Python 3.10+, remove and use new type hints +class RaDecRoll(): + """ + Concept data class for equatorial coordinates defined by (RA, Dec, Roll). + TODO: Migrate to something like this from the current "solved" dict? + + NOTE: All angles are in radians. + """ + + def __init__(self): + """ """ + self.ra = None + self.dec = None + self.roll = None + + def set(self, ra:float, dec:float, roll:Union[float, None]): + """ """ + self.ra = ra + self.dec = dec + self.roll = roll + + def set_from_deg(self, ra_deg:float, dec_deg:float, roll_deg:float): + """ """ + if roll_deg is None: + roll = None + else: + roll = np.deg2rad(roll_deg) + + self.set(np.deg2rad(ra_deg), np.deg2rad(dec_deg), roll) + + def get(self) -> (float, float, float): + """ """ + return self.ra, self.dec, self.roll + + def get_deg(self) -> (float, float, float): + """ """ + return np.rad2deg(self.ra), np.rad2deg(self.dec), np.rad2deg(self.roll) + + def get_initialized_solved_dict() -> dict: """ Returns an initialized 'solved' dictionary with cooridnate and other @@ -44,41 +82,3 @@ def get_initialized_solved_dict() -> dict: } return solved - - -class RaDecRoll(): - """ - Concept data class for equatorial coordinates defined by (RA, Dec, Roll). - TODO: Migrate to something like this from the current "solved" dict? - - NOTE: All angles are in radians. - """ - - def __init__(self): - """ """ - self.ra = None - self.dec = None - self.roll = None - - def set(self, ra:float, dec:float, roll:Union[float, None]): - """ """ - self.ra = ra - self.dec = dec - self.roll = roll - - def set_from_deg(self, ra_deg:float, dec_deg:float, roll_deg:float): - """ """ - if roll_deg is None: - roll = None - else: - roll = np.deg2rad(roll_deg) - - self.set(np.deg2rad(ra_deg), np.deg2rad(dec_deg), roll) - - def get(self) -> (float, float, float): - """ """ - return self.ra, self.dec, self.roll - - def get_deg(self) -> (float, float, float): - """ """ - return np.rad2deg(self.ra), np.rad2deg(self.dec), np.rad2deg(self.roll) From 30a15ae4291f2fe507fe13e770e599f95da1eab2 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 16 Aug 2025 21:41:50 +0100 Subject: [PATCH 119/253] Import RaDecRoll --- python/PiFinder/integrator.py | 2 +- python/PiFinder/pointing_model/imu_dead_reckoning.py | 1 + 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index dc47614dd..0cfbf73ef 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -18,7 +18,7 @@ from PiFinder import state_utils import PiFinder.calc_utils as calc_utils from PiFinder.multiproclogging import MultiprocLogging -from PiFinder.pointing_model.astro_coords import get_initialized_solved_dict +from PiFinder.pointing_model.astro_coords import RaDecRoll, get_initialized_solved_dict from PiFinder.pointing_model.imu_dead_reckoning import ImuDeadReckoning import PiFinder.pointing_model.quaternion_transforms as qt diff --git a/python/PiFinder/pointing_model/imu_dead_reckoning.py b/python/PiFinder/pointing_model/imu_dead_reckoning.py index fdb2d9916..27072217e 100644 --- a/python/PiFinder/pointing_model/imu_dead_reckoning.py +++ b/python/PiFinder/pointing_model/imu_dead_reckoning.py @@ -10,6 +10,7 @@ import numpy as np import quaternion +from PiFinder.pointing_model.astro_coords import RaDecRoll import PiFinder.pointing_model.quaternion_transforms as qt From 5cf8aae926a7f0e30c77f6cb2ee5234500c0f44d Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 16 Aug 2025 23:14:56 +0100 Subject: [PATCH 120/253] Add TODO --- python/PiFinder/pointing_model/README.md | 13 +++++++++++++ 1 file changed, 13 insertions(+) diff --git a/python/PiFinder/pointing_model/README.md b/python/PiFinder/pointing_model/README.md index 18149b96e..f68291f2e 100644 --- a/python/PiFinder/pointing_model/README.md +++ b/python/PiFinder/pointing_model/README.md @@ -3,6 +3,19 @@ README: IMU support prototyping > This README is temporary during the prototyping phase of the IMU support. +# TODO + +>Remove this before release! + +* Support other PiFinder types +* Use RaDecRoll class +* Type hints for integrator.py +* Lint using Nox +* Roll offset +* Alignment +* Go through TODOs +* Discuss requirements.txt with Richard + # Installation & set up ## Set up a virtual environment to test the PiFinder From 26e1681c2e9b1da5ee12a6409980151326a32a11 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 17 Aug 2025 00:36:26 +0100 Subject: [PATCH 121/253] Add sky test notes. --> Sky test OK --- python/PiFinder/pointing_model/README.md | 15 +++++++++++++++ 1 file changed, 15 insertions(+) diff --git a/python/PiFinder/pointing_model/README.md b/python/PiFinder/pointing_model/README.md index f68291f2e..0a4632497 100644 --- a/python/PiFinder/pointing_model/README.md +++ b/python/PiFinder/pointing_model/README.md @@ -16,6 +16,21 @@ README: IMU support prototyping * Go through TODOs * Discuss requirements.txt with Richard +# Sky test log + +>Remove this before release! + +* 20250817: 5cf8aae + * Tested on altaz and eq mounts + * **altaz:** Tracked fine. When the PiFinder was non-upright, I got the + feeling it tended to jump after an IMU track and got a plate-solve. This + wasn't seen when the PiFinder was upright. When non-upright, the crosshair + moved diagonally when the scope was moved in az or alt. The rotated + constellations in the chart were hard to make out. + * **EQ:** Seemed to work fine but I'm not experienced with EQ. The display on + SkySafari showed RA movement along the horizontal direction and Dec along + the vertical. This seemed to make sense. + # Installation & set up ## Set up a virtual environment to test the PiFinder From d6fa83f293db215db0f99f1ac71489ef9f0f13e1 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Sun, 17 Aug 2025 09:41:33 +0200 Subject: [PATCH 122/253] Fix tuple type hints --- python/PiFinder/pointing_model/astro_coords.py | 4 ++-- python/PiFinder/pointing_model/imu_dead_reckoning.py | 4 ++-- python/PiFinder/pointing_model/quaternion_transforms.py | 2 +- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/python/PiFinder/pointing_model/astro_coords.py b/python/PiFinder/pointing_model/astro_coords.py index 1bc12a5b1..dbf5a71bc 100644 --- a/python/PiFinder/pointing_model/astro_coords.py +++ b/python/PiFinder/pointing_model/astro_coords.py @@ -35,11 +35,11 @@ def set_from_deg(self, ra_deg:float, dec_deg:float, roll_deg:float): self.set(np.deg2rad(ra_deg), np.deg2rad(dec_deg), roll) - def get(self) -> (float, float, float): + def get(self) -> tuple[float, float, float]: """ """ return self.ra, self.dec, self.roll - def get_deg(self) -> (float, float, float): + def get_deg(self) -> tuple[float, float, float]: """ """ return np.rad2deg(self.ra), np.rad2deg(self.dec), np.rad2deg(self.roll) diff --git a/python/PiFinder/pointing_model/imu_dead_reckoning.py b/python/PiFinder/pointing_model/imu_dead_reckoning.py index 27072217e..4bd257c85 100644 --- a/python/PiFinder/pointing_model/imu_dead_reckoning.py +++ b/python/PiFinder/pointing_model/imu_dead_reckoning.py @@ -151,7 +151,7 @@ def get_q_eq2scope(self) -> Union[np.quaternion, None]: else: None - def get_cam_radec(self) -> (float, float, float, bool): + def get_cam_radec(self) -> tuple[float, float, float, bool]: """ Returns the (ra, dec, roll) of the camera and a Boolean dead_reckoning to indicate if the estimate is from dead-reckoning (True) or from plate @@ -160,7 +160,7 @@ def get_cam_radec(self) -> (float, float, float, bool): ra, dec, roll = qt.get_radec_of_q_eq2cam(self.q_eq2cam) return ra, dec, roll, self.dead_reckoning # Angles are in radians - def get_scope_radec(self) -> (float, float, float, bool): + def get_scope_radec(self) -> tuple[float, float, float, bool]: """ Returns the (ra, dec, roll) of the scope and a Boolean dead_reckoning to indicate if the estimate is from dead-reckoning (True) or from plate diff --git a/python/PiFinder/pointing_model/quaternion_transforms.py b/python/PiFinder/pointing_model/quaternion_transforms.py index 909a0453b..f7eb7714d 100644 --- a/python/PiFinder/pointing_model/quaternion_transforms.py +++ b/python/PiFinder/pointing_model/quaternion_transforms.py @@ -82,7 +82,7 @@ def get_q_eq2cam(ra_rad:float, dec_rad:float, roll_rad:float) -> np.quaternion: return q_eq2cam -def get_radec_of_q_eq2cam(q_eq2cam:np.quaternion) -> (float, float, float): +def get_radec_of_q_eq2cam(q_eq2cam:np.quaternion) -> tuple[float, float, float]: """ """ # Pure quaternion along camera boresight From 536cbc47783440ba1c3c334c0ca3567fa08981e5 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Sun, 17 Aug 2025 10:07:55 +0200 Subject: [PATCH 123/253] Remove else: for clarity --- .../PiFinder/pointing_model/imu_dead_reckoning.py | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/python/PiFinder/pointing_model/imu_dead_reckoning.py b/python/PiFinder/pointing_model/imu_dead_reckoning.py index 4bd257c85..ad1f05cb5 100644 --- a/python/PiFinder/pointing_model/imu_dead_reckoning.py +++ b/python/PiFinder/pointing_model/imu_dead_reckoning.py @@ -104,13 +104,13 @@ def update_plate_solve_and_imu(self, """ if (solved_cam_ra is None) or (solved_cam_dec is None): return # No update - else: - # Update plate-solved coord: - # Camera frame relative to the Equatorial frame where the +y camera - # frame (i.e. "up") points to the North Celestial Pole (NCP) -- i.e. - # zero roll offset: - self.q_eq2cam = qt.get_q_eq2cam(solved_cam_ra, solved_cam_dec, solved_cam_roll) - self.dead_reckoning = False + + # Update plate-solved coord: Camera frame relative to the Equatorial + # frame where the +y camera frame (i.e. "up") points to the North + # Celestial Pole (NCP) -- i.e. zero roll offset: + self.q_eq2cam = qt.get_q_eq2cam(solved_cam_ra, solved_cam_dec, + solved_cam_roll) + self.dead_reckoning = False # Update IMU: # Calculate the IMU's unknown reference frame X using the plate solved From 2206da745ced31c5aecad37038417d2a4c1703d4 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Sun, 17 Aug 2025 11:12:22 +0200 Subject: [PATCH 124/253] RaDecRoll: Make it a @dataclass and ddd support for None --- .../PiFinder/pointing_model/astro_coords.py | 49 +++++++++++-------- 1 file changed, 29 insertions(+), 20 deletions(-) diff --git a/python/PiFinder/pointing_model/astro_coords.py b/python/PiFinder/pointing_model/astro_coords.py index dbf5a71bc..1fdcf16b2 100644 --- a/python/PiFinder/pointing_model/astro_coords.py +++ b/python/PiFinder/pointing_model/astro_coords.py @@ -6,38 +6,47 @@ from typing import Union # When updated to Python 3.10+, remove and use new type hints +@dataclass class RaDecRoll(): """ - Concept data class for equatorial coordinates defined by (RA, Dec, Roll). + Data class for equatorial coordinates defined by (RA, Dec, Roll). + + The set methods allow values to be float or None but internally, None will + be stored as np.nan so that the type is consistent. the get methods will + return None if the value is np.nan. + TODO: Migrate to something like this from the current "solved" dict? NOTE: All angles are in radians. """ + ra: float = np.nan + dec: float = np.nan + roll: float = np.nan - def __init__(self): - """ """ - self.ra = None - self.dec = None - self.roll = None - - def set(self, ra:float, dec:float, roll:Union[float, None]): + def set(self, ra:Union[float, None], dec:Union[float, None], + roll:Union[float, None]): """ """ - self.ra = ra - self.dec = dec - self.roll = roll + self.ra = ra if ra is not None else np.nan + self.dec = dec if dec is not None else np.nan + self.roll = roll if roll is not None else np.nan - def set_from_deg(self, ra_deg:float, dec_deg:float, roll_deg:float): + def set_from_deg(self, ra_deg:Union[float, None], + dec_deg:Union[float, None], roll_deg:Union[float, None]): """ """ - if roll_deg is None: - roll = None - else: - roll = np.deg2rad(roll_deg) + ra = np.deg2rad(ra_deg) if ra_deg is not None else np.nan + dec = np.deg2rad(dec_deg) if dec_deg is not None else np.nan + roll = np.deg2rad(roll_deg) if roll_deg is not None else np.nan - self.set(np.deg2rad(ra_deg), np.deg2rad(dec_deg), roll) + self.set(ra, dec, roll) - def get(self) -> tuple[float, float, float]: - """ """ - return self.ra, self.dec, self.roll + def get(self) -> tuple[Union[float, None], Union[float, None], + Union[float, None]]: + """ Returns (ra, dec, roll) in radians """ + ra = self.ra if not np.isnan(self.ra) else None + dec = self.dec if not np.isnan(self.dec) else None + roll = self.roll if not np.isnan(self.roll) else None + + return ra, dec, roll def get_deg(self) -> tuple[float, float, float]: """ """ From 5c4fbf7eb133a614aefd771c1f6bd9f82eaa9d2b Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Sun, 17 Aug 2025 11:21:14 +0200 Subject: [PATCH 125/253] Add note --- python/PiFinder/integrator.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 0cfbf73ef..0710396e1 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -129,7 +129,7 @@ def update_plate_solve_and_imu(pointing_tracker, solved): solved_cam_ra = np.deg2rad(solved["camera_center"]["RA"]) solved_cam_dec = np.deg2rad(solved["camera_center"]["Dec"]) solved_cam_roll = np.deg2rad(solved["camera_center"]["Roll"]) - # Convert to radians: + # Convert to radians: # TODO: This doesn't seem to be used? target_ra = np.deg2rad(solved["RA"]) target_dec = np.deg2rad(solved["Dec"]) solved["Roll"] = 0 # TODO: Target roll isn't calculated by Tetra3. Set to zero here From 7ce3303960762b1d59a27618be18a68126e58583 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Sun, 17 Aug 2025 11:21:40 +0200 Subject: [PATCH 126/253] imu_dead_reckoning: Disallow None as input to keep the interface clean and simple --- .../PiFinder/pointing_model/imu_dead_reckoning.py | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/python/PiFinder/pointing_model/imu_dead_reckoning.py b/python/PiFinder/pointing_model/imu_dead_reckoning.py index ad1f05cb5..1a0ee8239 100644 --- a/python/PiFinder/pointing_model/imu_dead_reckoning.py +++ b/python/PiFinder/pointing_model/imu_dead_reckoning.py @@ -41,6 +41,8 @@ class ImuDeadReckoning(): pointing_tracker.update_imu(q_x2imu) """ + # TODO: Declare attributes here + def __init__(self, screen_direction:str): """ """ # Alignment: @@ -83,11 +85,10 @@ def set_alignment(self, self.q_cam2scope = self.q_scope2cam.conj() self.q_imu2scope = self.q_imu2cam * self.q_cam2scope - def update_plate_solve_and_imu(self, - solved_cam_ra: Union[float, None], - solved_cam_dec: Union[float, None], - solved_cam_roll: Union[float, None], - q_x2imu: Union[np.quaternion, None]): + def update_plate_solve_and_imu(self, solved_cam_ra: float, + solved_cam_dec: float, + solved_cam_roll: float, + q_x2imu: np.quaternion): """ Update the state with the az/alt measurements from plate solving in the camera frame. If the IMU measurement (which should be taken at the same @@ -102,7 +103,7 @@ def update_plate_solve_and_imu(self, q_x2imu: [quaternion] Raw IMU measurement quaternions. This is the IMU frame orientation wrt unknown drifting reference frame X. """ - if (solved_cam_ra is None) or (solved_cam_dec is None): + if np.isnan(solved_cam_ra) or np.isnan(solved_cam_dec): return # No update # Update plate-solved coord: Camera frame relative to the Equatorial From 431cbbfe596ddeab9c793cf47b990bec9d850f09 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 17 Aug 2025 10:26:19 +0100 Subject: [PATCH 127/253] Fix missing import --- python/PiFinder/pointing_model/astro_coords.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/python/PiFinder/pointing_model/astro_coords.py b/python/PiFinder/pointing_model/astro_coords.py index 1fdcf16b2..fcd323c1e 100644 --- a/python/PiFinder/pointing_model/astro_coords.py +++ b/python/PiFinder/pointing_model/astro_coords.py @@ -1,7 +1,7 @@ """ Various astronomical coordinates functions """ - +from dataclasses import dataclass import numpy as np from typing import Union # When updated to Python 3.10+, remove and use new type hints From c8097f8db7117ddd688724ed9223fa2a52cf659e Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 17 Aug 2025 10:30:25 +0100 Subject: [PATCH 128/253] Rename object pointing_tracker --> imu_dead_reckoning to make it more explicit. Desktop-tested --- python/PiFinder/integrator.py | 32 +++++++++---------- .../pointing_model/imu_dead_reckoning.py | 8 ++--- 2 files changed, 20 insertions(+), 20 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 0710396e1..70af00e7b 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -41,8 +41,8 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr cfg = config.Config() # Set up dead-reckoning tracking by the IMU: - pointing_tracker = ImuDeadReckoning(cfg.get_option("screen_direction")) - #pointing_tracker.set_alignment(q_scope2cam) # TODO: Enable when q_scope2cam is available + imu_dead_reckoning = ImuDeadReckoning(cfg.get_option("screen_direction")) + #imu_dead_reckoning.set_alignment(q_scope2cam) # TODO: Enable when q_scope2cam is available # This holds the last image solve position info # so we can delta for IMU updates @@ -62,17 +62,17 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr if type(next_image_solve) is dict: # We have a new image solve: Use plate-solving for RA/Dec solved = next_image_solve - update_plate_solve_and_imu(pointing_tracker, solved) + update_plate_solve_and_imu(imu_dead_reckoning, solved) last_image_solve = copy.deepcopy(solved) solved["solve_source"] = "CAM" - elif pointing_tracker.tracking: + elif imu_dead_reckoning.tracking: # Previous plate-solve exists so use IMU dead-reckoning from # the last plate solved coordinates. imu = shared_state.imu() if imu: - update_imu(solved, last_image_solve, imu, pointing_tracker) + update_imu(solved, last_image_solve, imu, imu_dead_reckoning) # Is the solution new? if solved["RA"] and solved["solve_time"] > last_solve_time: @@ -111,7 +111,7 @@ def estimate_roll_offset(solved, dt): return roll_offset -def update_plate_solve_and_imu(pointing_tracker, solved): +def update_plate_solve_and_imu(imu_dead_reckoning, solved): """ Wrapper for ImuDeadReckoning.update_plate_solve_and_imu() to interface angles in degrees to radians. @@ -136,14 +136,14 @@ def update_plate_solve_and_imu(pointing_tracker, solved): target_roll = np.deg2rad(solved["Roll"]) # Update: - pointing_tracker.update_plate_solve_and_imu( + imu_dead_reckoning.update_plate_solve_and_imu( solved_cam_ra, solved_cam_dec, solved_cam_roll, q_x2imu) # Set alignment. TODO: Do this once at alignment. Move out of here. - set_alignment(pointing_tracker, solved) + set_alignment(imu_dead_reckoning, solved) -def set_alignment(pointing_tracker, solved): +def set_alignment(imu_dead_reckoning, solved): """ Set alignment. TODO: Do this once at alignment @@ -163,16 +163,16 @@ def set_alignment(pointing_tracker, solved): q_eq2scope = qt.get_q_eq2cam(target_ra, target_dec, target_roll) q_scope2cam = q_eq2scope.conjugate() * q_eq2cam - # Set alignment in pointing_tracker - pointing_tracker.set_alignment(q_scope2cam) + # Set alignment in imu_dead_reckoning + imu_dead_reckoning.set_alignment(q_scope2cam) -def update_imu(solved, last_image_solve, imu, pointing_tracker): +def update_imu(solved, last_image_solve, imu, imu_dead_reckoning): """ Updates the solved dictionary using IMU dead-reckoning from the last solved pointing. """ - if not(last_image_solve and pointing_tracker.tracking): + if not(last_image_solve and imu_dead_reckoning.tracking): return # Need all of these to do IMU dead-reckoning # When moving, switch to tracking using the IMU @@ -185,16 +185,16 @@ def update_imu(solved, last_image_solve, imu, pointing_tracker): np.rad2deg(IMU_MOVED_ANG_THRESHOLD))) # Dead-reckoning using IMU - pointing_tracker.update_imu(imu["quat"]) # Latest IMU meas + imu_dead_reckoning.update_imu(imu["quat"]) # Latest IMU meas # Store current camera pointing estimate: - ra_cam, dec_cam, roll_cam, dead_reckoning_flag = pointing_tracker.get_cam_radec() + ra_cam, dec_cam, roll_cam, dead_reckoning_flag = imu_dead_reckoning.get_cam_radec() solved["camera_center"]["RA"] = np.rad2deg(ra_cam) solved["camera_center"]["Dec"] = np.rad2deg(dec_cam) solved["camera_center"]["Roll"] = np.rad2deg(roll_cam) # Store the current scope pointing estimate - ra_target, dec_target, roll_target, dead_reckoning_flag = pointing_tracker.get_scope_radec() + ra_target, dec_target, roll_target, dead_reckoning_flag = imu_dead_reckoning.get_scope_radec() solved["RA"] = np.rad2deg(ra_target) solved["Dec"] = np.rad2deg(dec_target) solved["Roll"] = np.rad2deg(roll_target) diff --git a/python/PiFinder/pointing_model/imu_dead_reckoning.py b/python/PiFinder/pointing_model/imu_dead_reckoning.py index 1a0ee8239..feb449102 100644 --- a/python/PiFinder/pointing_model/imu_dead_reckoning.py +++ b/python/PiFinder/pointing_model/imu_dead_reckoning.py @@ -31,14 +31,14 @@ class ImuDeadReckoning(): EXAMPLE: # Set up: - pointing_tracker = ImuDeadReckoning('flat') - pointing_tracker.set_alignment(q_scope2cam) + imu_dead_reckoning = ImuDeadReckoning('flat') + imu_dead_reckoning.set_alignment(q_scope2cam) # Update with plate solved and IMU data: - pointing_tracker.update_plate_solve_and_imu(solved_cam_ra, solved_cam_dec, solved_cam_roll, q_x2imu) + imu_dead_reckoning.update_plate_solve_and_imu(solved_cam_ra, solved_cam_dec, solved_cam_roll, q_x2imu) # Dead-reckoning using IMU - pointing_tracker.update_imu(q_x2imu) + imu_dead_reckoning.update_imu(q_x2imu) """ # TODO: Declare attributes here From a08d1a308729b5802766ed94663908cbc7a2b9c3 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 17 Aug 2025 10:34:46 +0100 Subject: [PATCH 129/253] Remove returning unused dead_reckoning_flag --- python/PiFinder/integrator.py | 4 ++-- python/PiFinder/pointing_model/imu_dead_reckoning.py | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 70af00e7b..a64a33d1b 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -188,13 +188,13 @@ def update_imu(solved, last_image_solve, imu, imu_dead_reckoning): imu_dead_reckoning.update_imu(imu["quat"]) # Latest IMU meas # Store current camera pointing estimate: - ra_cam, dec_cam, roll_cam, dead_reckoning_flag = imu_dead_reckoning.get_cam_radec() + ra_cam, dec_cam, roll_cam = imu_dead_reckoning.get_cam_radec() solved["camera_center"]["RA"] = np.rad2deg(ra_cam) solved["camera_center"]["Dec"] = np.rad2deg(dec_cam) solved["camera_center"]["Roll"] = np.rad2deg(roll_cam) # Store the current scope pointing estimate - ra_target, dec_target, roll_target, dead_reckoning_flag = imu_dead_reckoning.get_scope_radec() + ra_target, dec_target, roll_target = imu_dead_reckoning.get_scope_radec() solved["RA"] = np.rad2deg(ra_target) solved["Dec"] = np.rad2deg(dec_target) solved["Roll"] = np.rad2deg(roll_target) diff --git a/python/PiFinder/pointing_model/imu_dead_reckoning.py b/python/PiFinder/pointing_model/imu_dead_reckoning.py index feb449102..9b3eaab35 100644 --- a/python/PiFinder/pointing_model/imu_dead_reckoning.py +++ b/python/PiFinder/pointing_model/imu_dead_reckoning.py @@ -159,7 +159,7 @@ def get_cam_radec(self) -> tuple[float, float, float, bool]: solving (False). """ ra, dec, roll = qt.get_radec_of_q_eq2cam(self.q_eq2cam) - return ra, dec, roll, self.dead_reckoning # Angles are in radians + return ra, dec, roll # Angles are in radians def get_scope_radec(self) -> tuple[float, float, float, bool]: """ @@ -169,7 +169,7 @@ def get_scope_radec(self) -> tuple[float, float, float, bool]: """ q_eq2scope = self.get_q_eq2scope() ra, dec, roll = qt.get_radec_of_q_eq2cam(self.q_eq2scope) - return ra, dec, roll, self.dead_reckoning # Angles are in radians + return ra, dec, roll # Angles are in radians def reset(self): """ From 3a01c1c32eadd34083e0e59c54e0985f82a4d5a1 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 17 Aug 2025 10:50:14 +0100 Subject: [PATCH 130/253] Change invalid imu measurement from None to np.nan. Desktop-tested --- python/PiFinder/integrator.py | 5 ++++- .../PiFinder/pointing_model/imu_dead_reckoning.py | 13 ++++++------- 2 files changed, 10 insertions(+), 8 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index a64a33d1b..d2ca047a3 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -123,7 +123,10 @@ def update_plate_solve_and_imu(imu_dead_reckoning, solved): return # No update else: # Successfully plate solved & camera pointing exists - q_x2imu = solved["imu_quat"] # IMU measurement at the time of plate solving + if solved["imu_quat"] is None: + q_x2imu = np.quaternion(np.nan) + else: + q_x2imu = solved["imu_quat"] # IMU measurement at the time of plate solving # Convert to radians: solved_cam_ra = np.deg2rad(solved["camera_center"]["RA"]) diff --git a/python/PiFinder/pointing_model/imu_dead_reckoning.py b/python/PiFinder/pointing_model/imu_dead_reckoning.py index 9b3eaab35..b4fc28915 100644 --- a/python/PiFinder/pointing_model/imu_dead_reckoning.py +++ b/python/PiFinder/pointing_model/imu_dead_reckoning.py @@ -27,7 +27,7 @@ class ImuDeadReckoning(): This class uses the Equatorial frame as the reference and expects plate-solved coordinates in (ra, dec). - All angles are in radians. + All angles are in radians. None is not allowed as inputs (use np.nan). EXAMPLE: # Set up: @@ -113,12 +113,11 @@ def update_plate_solve_and_imu(self, solved_cam_ra: float, solved_cam_roll) self.dead_reckoning = False - # Update IMU: - # Calculate the IMU's unknown reference frame X using the plate solved - # coordinates and IMU measurements taken from the same time. If the IMU - # measurement isn't provided (e.g. None or zeros), the existing q_hor2x - # will continue to be used. - if q_x2imu: + # Update IMU: Calculate the IMU's unknown reference frame X using the + # plate solved coordinates and IMU measurements taken from the same + # time. If the IMU measurement isn't provided (i.e. None), the existing + # q_hor2x will continue to be used. + if not np.isnan(q_x2imu): self.q_eq2x = self.q_eq2cam * self.q_cam2imu * q_x2imu.conj() self.q_eq2x = self.q_eq2x.normalized() self.tracking = True # We have a plate solve and IMU measurement From 15b0fe99a9127f9ed6c5597b816e29f7c1e3cc22 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 17 Aug 2025 10:52:42 +0100 Subject: [PATCH 131/253] Remove unused code --- python/PiFinder/integrator.py | 8 +++----- 1 file changed, 3 insertions(+), 5 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index d2ca047a3..4a4e125b2 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -132,11 +132,9 @@ def update_plate_solve_and_imu(imu_dead_reckoning, solved): solved_cam_ra = np.deg2rad(solved["camera_center"]["RA"]) solved_cam_dec = np.deg2rad(solved["camera_center"]["Dec"]) solved_cam_roll = np.deg2rad(solved["camera_center"]["Roll"]) - # Convert to radians: # TODO: This doesn't seem to be used? - target_ra = np.deg2rad(solved["RA"]) - target_dec = np.deg2rad(solved["Dec"]) - solved["Roll"] = 0 # TODO: Target roll isn't calculated by Tetra3. Set to zero here - target_roll = np.deg2rad(solved["Roll"]) + + # TODO: Target roll isn't calculated by Tetra3. Set to zero here + solved["Roll"] = 0 # Update: imu_dead_reckoning.update_plate_solve_and_imu( From 85b39dfa8a42d333ed952dee342d5928f24b5c6c Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 17 Aug 2025 12:00:20 +0100 Subject: [PATCH 132/253] Move to class-level type hints --- .../pointing_model/imu_dead_reckoning.py | 51 +++++++++---------- 1 file changed, 25 insertions(+), 26 deletions(-) diff --git a/python/PiFinder/pointing_model/imu_dead_reckoning.py b/python/PiFinder/pointing_model/imu_dead_reckoning.py index b4fc28915..010e538a4 100644 --- a/python/PiFinder/pointing_model/imu_dead_reckoning.py +++ b/python/PiFinder/pointing_model/imu_dead_reckoning.py @@ -40,34 +40,33 @@ class ImuDeadReckoning(): # Dead-reckoning using IMU imu_dead_reckoning.update_imu(q_x2imu) """ + # Alignment: + q_scope2cam: np.quaternion # ****Do we need this?? + q_cam2scope: np.quaternion + # IMU orientation: + q_imu2cam: np.quaternion + q_cam2imu: np.quaternion + # Putting them together: + q_imu2scope: np.quaternion + + # The poinging of the camera and scope frames wrt the Equatorial frame. + # These get updated by plate solving and IMU dead-reckoning. + q_eq2cam: np.quaternion # ***Do we need to keep q_eq2cam? + + # True when q_eq2cam is estimated by IMU dead-reckoning. + # False when set by plate solving + dead_reckoning: bool = False + tracking: bool = False # True when previous plate solve exists and tracking + + # The IMU's unkonwn drifting reference frame X. This is solved for + # every time we have a simultaneous plate solve and IMU measurement. + q_eq2x: np.quaternion = np.quaternion(np.nan) # nan means not set - # TODO: Declare attributes here def __init__(self, screen_direction:str): """ """ - # Alignment: - self.q_scope2cam = None # ****Do we need this?? - self.q_cam2scope = None - # IMU orientation: - self.q_imu2cam = None - self.q_cam2imu = None # IMU-to-camera orientation. Fixed by PiFinder type self._set_screen_direction(screen_direction) - # Putting them together: - self.q_imu2scope = None - - # The poinging of the camera and scope frames wrt the Equatorial frame. - # These get updated by plate solving and IMU dead-reckoning. - self.q_eq2cam = None # ***Do we need to keep q_eq2cam? - - # True when q_eq2cam is estimated by IMU dead-reckoning. - # False when set by plate solving - self.dead_reckoning = False - self.tracking = False # True when previous plate solve exists and tracking - - # The IMU's unkonwn drifting reference frame X. This is solved for - # every time we have a simultaneous plate solve and IMU measurement. - self.q_eq2x = None def set_alignment(self, q_scope2cam: np.quaternion): @@ -132,7 +131,7 @@ def update_imu(self, q_x2imu: Quaternion of the IMU orientation w.r.t. an unknown and drifting reference frame X used by the IMU. """ - if self.q_eq2x is not None: + if not np.isnan(self.q_eq2x): # Dead reckoning estimate by IMU if q_hor2x has been estimated by a # previous plate solve. self.q_eq2cam = self.q_eq2x * q_x2imu * self.q_imu2cam @@ -144,7 +143,7 @@ def update_imu(self, self.dead_reckoning = True def get_q_eq2scope(self) -> Union[np.quaternion, None]: - """ """ + """ TODO: REMOVE """ if self.q_eq2cam and self.q_cam2scope: q_eq2scope = self.q_eq2cam * self.q_cam2scope return q_eq2scope @@ -166,8 +165,8 @@ def get_scope_radec(self) -> tuple[float, float, float, bool]: to indicate if the estimate is from dead-reckoning (True) or from plate solving (False). """ - q_eq2scope = self.get_q_eq2scope() - ra, dec, roll = qt.get_radec_of_q_eq2cam(self.q_eq2scope) + q_eq2scope = self.get_q_eq2scope() # TODO REMOVE + ra, dec, roll = qt.get_radec_of_q_eq2cam(self.q_eq2scope) # TODO: Rename this qt func return ra, dec, roll # Angles are in radians def reset(self): From 213d27263b78284443d20ee2bb81d7fb77bae7f9 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 17 Aug 2025 12:09:09 +0100 Subject: [PATCH 133/253] Rename confusing func name --- .../PiFinder/pointing_model/imu_dead_reckoning.py | 13 ++----------- .../pointing_model/quaternion_transforms.py | 14 ++++++++------ 2 files changed, 10 insertions(+), 17 deletions(-) diff --git a/python/PiFinder/pointing_model/imu_dead_reckoning.py b/python/PiFinder/pointing_model/imu_dead_reckoning.py index 010e538a4..38da1bada 100644 --- a/python/PiFinder/pointing_model/imu_dead_reckoning.py +++ b/python/PiFinder/pointing_model/imu_dead_reckoning.py @@ -142,21 +142,13 @@ def update_imu(self, self.dead_reckoning = True - def get_q_eq2scope(self) -> Union[np.quaternion, None]: - """ TODO: REMOVE """ - if self.q_eq2cam and self.q_cam2scope: - q_eq2scope = self.q_eq2cam * self.q_cam2scope - return q_eq2scope - else: - None - def get_cam_radec(self) -> tuple[float, float, float, bool]: """ Returns the (ra, dec, roll) of the camera and a Boolean dead_reckoning to indicate if the estimate is from dead-reckoning (True) or from plate solving (False). """ - ra, dec, roll = qt.get_radec_of_q_eq2cam(self.q_eq2cam) + ra, dec, roll = qt.get_radec_of_q_eq(self.q_eq2cam) return ra, dec, roll # Angles are in radians def get_scope_radec(self) -> tuple[float, float, float, bool]: @@ -165,8 +157,7 @@ def get_scope_radec(self) -> tuple[float, float, float, bool]: to indicate if the estimate is from dead-reckoning (True) or from plate solving (False). """ - q_eq2scope = self.get_q_eq2scope() # TODO REMOVE - ra, dec, roll = qt.get_radec_of_q_eq2cam(self.q_eq2scope) # TODO: Rename this qt func + ra, dec, roll = qt.get_radec_of_q_eq(self.q_eq2scope) return ra, dec, roll # Angles are in radians def reset(self): diff --git a/python/PiFinder/pointing_model/quaternion_transforms.py b/python/PiFinder/pointing_model/quaternion_transforms.py index f7eb7714d..85822841c 100644 --- a/python/PiFinder/pointing_model/quaternion_transforms.py +++ b/python/PiFinder/pointing_model/quaternion_transforms.py @@ -82,23 +82,25 @@ def get_q_eq2cam(ra_rad:float, dec_rad:float, roll_rad:float) -> np.quaternion: return q_eq2cam -def get_radec_of_q_eq2cam(q_eq2cam:np.quaternion) -> tuple[float, float, float]: +def get_radec_of_q_eq(q_eq2frame:np.quaternion) -> tuple[float, float, float]: """ + Returns the (ra, dec, roll) angles of the quaterion rotation relative to + the equatorial frame. """ # Pure quaternion along camera boresight - pz_cam = q_eq2cam * np.quaternion(0, 0, 0, 1) * q_eq2cam.conj() + pz_frame = q_eq2frame * np.quaternion(0, 0, 0, 1) * q_eq2frame.conj() # Calculate RA, Dec from the camera boresight: - dec = np.arcsin(pz_cam.z) - ra = np.arctan2(pz_cam.y, pz_cam.x) + dec = np.arcsin(pz_frame.z) + ra = np.arctan2(pz_frame.y, pz_frame.x) # Pure quaternion along y_cam which points to NCP when roll = 0 - py_cam = q_eq2cam * np.quaternion(0, 0, 1, 0) * q_eq2cam.conj() + py_cam = q_eq2frame * np.quaternion(0, 0, 1, 0) * q_eq2frame.conj() # Local East and North vectors (roll is the angle between py_cam and the north vector) vec_east = np.array([-np.sin(ra), np.cos(ra), 0]) vec_north = np.array([-np.sin(dec) * np.cos(ra), -np.sin(dec) * np.sin(ra), np.cos(dec)]) roll = -np.arctan2(np.dot(py_cam.vec, vec_east), np.dot(py_cam.vec, vec_north)) - return ra, dec, roll + return ra, dec, roll # In radians def get_q_scope2cam(target_eq: RaDecRoll, cam_eq: RaDecRoll) -> np.quaternion: From d46c0cc46725824756e0f5c278932541d14f1ba5 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 17 Aug 2025 12:15:43 +0100 Subject: [PATCH 134/253] Move calculation of screen direction quaternion to a separate func for re-usability & testing --- .../pointing_model/imu_dead_reckoning.py | 34 +++++++++++++------ 1 file changed, 24 insertions(+), 10 deletions(-) diff --git a/python/PiFinder/pointing_model/imu_dead_reckoning.py b/python/PiFinder/pointing_model/imu_dead_reckoning.py index 38da1bada..27ee85de7 100644 --- a/python/PiFinder/pointing_model/imu_dead_reckoning.py +++ b/python/PiFinder/pointing_model/imu_dead_reckoning.py @@ -172,14 +172,28 @@ def _set_screen_direction(self, screen_direction: str): Sets the screen direction which determines the fixed orientation between the IMU and camera (q_imu2cam). """ - if screen_direction == "flat": - # Rotate -90° around y_imu so that z_imu' points along z_camera - q1 = np.quaternion(np.cos(-np.pi / 4), 0, np.sin(-np.pi / 4), 0) - # Rotate -90° around z_imu' to align with the camera cooridnates - q2 = np.quaternion(np.cos(-np.pi / 4), 0, 0, np.sin(-np.pi / 4)) - self.q_imu2cam = q1 * q2 # Intrinsic rotation: q1 followed by q2 - else: - raise ValueError('Unsupported screen_direction') - - self.q_imu2cam = self.q_imu2cam.normalized() + self.q_imu2cam = get_screen_direction_q_imu2cam(screen_direction) self.q_cam2imu = self.q_imu2cam.conj() + + +def get_screen_direction_q_imu2cam(screen_direction: str) -> np.quaternion: + """ + Returns the quaternion that rotates the IMU frame to the camera frame + based on the screen direction. + + INPUTS: + screen_direction: "flat" or "upright" + + RETURNS: + q_imu2cam: Quaternion that rotates the IMU frame to the camera frame. + """ + if screen_direction == "flat": + # Rotate -90° around y_imu so that z_imu' points along z_camera + q1 = np.quaternion(np.cos(-np.pi / 4), 0, np.sin(-np.pi / 4), 0) + # Rotate -90° around z_imu' to align with the camera cooridnates + q2 = np.quaternion(np.cos(-np.pi / 4), 0, 0, np.sin(-np.pi / 4)) + q_imu2cam = (q1 * q2).normalized() + else: + raise ValueError('Unsupported screen_direction') + + return q_imu2cam From 020b88070120e3a0ab1992200ba154ff3c38de86 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 17 Aug 2025 12:34:13 +0100 Subject: [PATCH 135/253] screen_direction: Sketch other types. use axis_angle2quat() for flat v2. --> Desktop-tested --- .../pointing_model/imu_dead_reckoning.py | 20 +++++++++++++++---- 1 file changed, 16 insertions(+), 4 deletions(-) diff --git a/python/PiFinder/pointing_model/imu_dead_reckoning.py b/python/PiFinder/pointing_model/imu_dead_reckoning.py index 27ee85de7..4986ecea9 100644 --- a/python/PiFinder/pointing_model/imu_dead_reckoning.py +++ b/python/PiFinder/pointing_model/imu_dead_reckoning.py @@ -187,13 +187,25 @@ def get_screen_direction_q_imu2cam(screen_direction: str) -> np.quaternion: RETURNS: q_imu2cam: Quaternion that rotates the IMU frame to the camera frame. """ - if screen_direction == "flat": + if screen_direction == "left": + raise ValueError('Unsupported screen_direction: left') + elif screen_direction == "right": + raise ValueError('Unsupported screen_direction: right') + elif screen_direction == "straight": + raise ValueError('Unsupported screen_direction: straight') + elif screen_direction == "flat3": + # Flat v3: + raise ValueError('Unsupported screen_direction: flat3') + elif screen_direction == "flat": + # Flat v2: # Rotate -90° around y_imu so that z_imu' points along z_camera - q1 = np.quaternion(np.cos(-np.pi / 4), 0, np.sin(-np.pi / 4), 0) + q1 = qt.axis_angle2quat([0, 1, 0], -np.pi / 2) # Rotate -90° around z_imu' to align with the camera cooridnates - q2 = np.quaternion(np.cos(-np.pi / 4), 0, 0, np.sin(-np.pi / 4)) + q2 = qt.axis_angle2quat([0, 0, 1], -np.pi / 2) q_imu2cam = (q1 * q2).normalized() + elif screen_direction == "as_dream": + raise ValueError('Unsupported screen_direction: as_dream') else: - raise ValueError('Unsupported screen_direction') + raise ValueError(f'Unsupported screen_direction: {screen_direction}') return q_imu2cam From a8eeab0dcc4c9adea3595d9e294ba655a66bcfc1 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Sun, 17 Aug 2025 13:47:01 +0200 Subject: [PATCH 136/253] Fix latex equation formatting --- python/PiFinder/pointing_model/README.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/python/PiFinder/pointing_model/README.md b/python/PiFinder/pointing_model/README.md index 0a4632497..302ffa50c 100644 --- a/python/PiFinder/pointing_model/README.md +++ b/python/PiFinder/pointing_model/README.md @@ -139,11 +139,11 @@ The inverse (or conjugate) is given by `q.conj()`. Intrinsic rotation of $q_0$ followed by $q_1$ -$$q_{new} = q_0 q_1$$ +$$q_{new} = q_0 q_1$$ For an extrinsic rotation of $q_0$ followed by $q_1$, left multiply -$$q_{new} = q_1 q_0$$ +$$q_{new} = q_1 q_0$$ ## Coordinate frames From e38ccab6b122cf8c74d28dbd359b929d1a2da72c Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Sun, 17 Aug 2025 13:54:56 +0200 Subject: [PATCH 137/253] Add photo and explanation in README for q_imu2cam --- python/PiFinder/pointing_model/README.md | 12 ++++++++++++ .../PiFinder_Flat_bare_PCB_camera_coords.jpg | Bin 0 -> 251787 bytes 2 files changed, 12 insertions(+) create mode 100644 python/PiFinder/pointing_model/docs/PiFinder_Flat_bare_PCB_camera_coords.jpg diff --git a/python/PiFinder/pointing_model/README.md b/python/PiFinder/pointing_model/README.md index 302ffa50c..ce746cc35 100644 --- a/python/PiFinder/pointing_model/README.md +++ b/python/PiFinder/pointing_model/README.md @@ -195,6 +195,18 @@ We define the following reference frames: * $+z$ is the boresight of the camera, $+y$ and $+x$ are respectively the vertical and horizontal (to the left) directions of the camera. +## IMU and camera coordinate frames + +To use the IMU for dead-reckoning, we need to know the transformation between +the IMU's own coordinate frame and the PiFinder's camera coordinate frame +(which we use as the PiFinder's reference coordinate frame). + +The picture below illustrate the IMU and camera coordinates for the v2 flat +version of the PiFinder. For each type, we need to work out the quaternion +rotation `q_imu2cam` that rotates the IMU frame to the camera frame. + +![Image](docs/PiFinder_Flat_bare_PCB_camera_coords.jpg) + ## Roll The roll (as given by Tetra3) is defined as the rotation of the north pole diff --git a/python/PiFinder/pointing_model/docs/PiFinder_Flat_bare_PCB_camera_coords.jpg b/python/PiFinder/pointing_model/docs/PiFinder_Flat_bare_PCB_camera_coords.jpg new file mode 100644 index 0000000000000000000000000000000000000000..7aac61044cccad2e13f98debe767f3e72c64611c GIT binary patch literal 251787 zcmeFYXIPU<*FPGH1Vo9TC_Nw`2!a$T0Rm#7NfGH?2|e`QLs3A)&;%7BfRxaY-kV5O ziuB$R2pvK%0Z!cedG`BW=lXy6U+2^Luoq0`mz7yFYpqP~d)At{FUBtBLFZ4sZLI(R zH8lVq005u_TqXelNQsDwSi(rI{e`KCIEI7{Kt`-dh<^YQCcve?FaVHD!u$`;B;ox} z8)6S6B7e!=Ahs(Yz5YM4;kE$s|Hw8+aQ_#R1`>Gy2PbzYS10>de%eaG%@7=;M=hzf43naB?H8f051PMGO2hR=|6qS#*zQSSBSgx4_`fw z@;`Rc0|0SU|H0RY`0_t(bmLb{>OJ|r2q97 z9UzVDzxZm<*IWN-LsT}C?0;eMf5!F9y!5~L6#s*XB7f+QcNvL=mRK(TpFI43;sF43 zoB#mXGEwF;u~-nxANteRf8TEqv51JIq&P&F2>xF+@v}d3jf6PwNd7{k>cqE1^k;Sv zXB#P&`1+>>>C->_zpeShClFiw8Rbs_04V-zCD{$)clRGzG8O>qU$Vs6OZMQeb^w4V zvHl~&`*%(MgjoO4`oFW8?r;9JvcLJv3B zB8vYI@GqkLLsb9JA911}Iq{#0;u6I_{QqlkF-?r@WG|Wlw3MV1WJ6>mw*jQIBxJNC z7e7e8663W?e{1+(PZIScDh8yax=c+>Pmqw2k&=^LBI-+Q8Sp1)C#Stc$000Fab5Ej z@V3hhk>J>LO3p_mE%YybZ*z&7yM|C*zIls*k%{{b5AR*R2V&w9k`SrKPo63$Dk-aI zY3u0f=^GfrEG(_8ZEWq_+&w(KynTE_U%v?pk9Zpy7ylt4@#Ck@NnbNEv$D}Sxp}2! zTYt2*cXW1j4-5_skBp9uPs}f1u!~E$<&{00-0pRugj+!PO^G zqt7l8)XGJ1(10c;0`$lY&%Yr4{+_e`DqUxR0xY(wNO2SeU%voc@pr}ZeJ@#!DF_W} zQ#K^L9jKMd3HVZT0=OS{$AAP&){l!UJWH$YY_*P4OfQaw9qog}2U~7$$i$BMo(|^* zLYFn!1Htt_p1IRrtA>;v% zR_4F46pmrYU7jUPtEMm>$R_)tjjy?(8uD`MDOcsftAVj*!t!`bYaH*aCj&}?#y60D zP~YEp`$scxway7rbY;y@MN{D!NP69Gx^0g#Gfv&R*XIl#G3-$hNtfqby)5OnHBw!d z8ewP=`NYjtUD0iCOJBJlVZdzZCcFxQ~yd>&7ddm61Q8jYs7}ov zTDe~m9^_&BUgGee%rWpcEw|g?OdT`zrv+w)OI>p#dyBw4p+Xh70 zRUf9?o2ydEqd+$wE(75x*zw6IM7+?CkCqne(Z-jcc|)iW70*`8@}xU6munX(n_#W7 z>%pJ(F|MYAqW*ik^kkQg(Po^KwbfzXEk-QZXZ)<7%vn6hx;CRLHbvuG1iAni=03A127?8Ct&1+f8TG%{bJpy{X19fGfUOK6PHPd6)^Z?lZ{C2h6#IBD2&e{&MPfklc0tWoOwsX&N*xG8!i)1vu7ijm{LxCm=B#B`lxS9IMML1+RiHIAcDu|4yxVnhP_#L-%xiW( z4Z<@>kCD2!VZYYZ?ju{Xa;%qOp#H-z_C#0M5oiAX^VEbY3u(iLD%JR;*@%tT{MTa? z89D%Z9I!h|sxizAeLQ42g$c>l_k;?2{jhlDa!cKS_csz^_#J-AVg^xmTNCn6O&?zZ zr)a)?_vpq!=V4|TX{%j)Gkt1#N%!yHlfA$zvfFZ5aPDqEqjg%5A#Ig;rMy0t5z!j3(7n-9bTfAmghy*nP2huR2@Hml{qm zqr7NXPZ&;iI~JVKf=hj_W}y-_8PWOE8JNwlbvR#2#Xp2f;lH`6!%E}ovk|I8B@j}` zylUxFI;q4};abdirJ$akGxi9VPJd!~D(UYQ+HPoQ!!-11XhWOoMzYVlLGKe3gYOx9 z=X~iotIHuG@;%uP-;ZzhJ7pecsG3(-nd=14g^r!Fy$%%HH@M>_BQyA}|ETfKe5bk1 z#6-pkg@SIhtNUIWk`y@=xt$uEN?#Djb!0A}FvUhXR`1LyN@kx9JNUESnc)vuvR?YYSDGKsW~BVI zUnp0&j85eFM9*evsHvI0d$b&ocFh@poB2}z4U?t0>&;_O4s=n@dP4)$uT2@86`d{sI%IrHj}(8- z7LwjAiJC)Q0M6{nEg|gSZ121USe@;%D?m0uP?yATT=$N7D~o&9&F$UZ$F6+9M4`vm zgCNa0GalRqr67&%+=L`j+=qy|Shum=GhXEz+af^3D}xQ!jq1?BXx}$nuFh!IU{;MA zypzwxqH10$x3B^c-!l?5Tlp=6u?WLn+iB-KA>sZDfRwx6mnE5nuZN^-Qy$~}sDL$D zwTB9_<)`T^&mR;VcPxYK<~BW)%+0@4vEWlRatd!I2}$eJ(m6L<4^;P98~OQIF#Bk> zIj$synD7b(>9L#zR{T6l8a=yb?D4)fbP~F1EKRb+*>+g`dLe0N%-Q=9}zA5S|9LpuTOwduY7_$8j_iv}XE_^hdXd zTwjIjO)12Nm#sM<4x@Uw&@m5JP{$h@ z@(|pS_Kt8D!7ix2?A4>-ICYW}tt8Ls-78GF*q)d%GN`NXi-Jovy#tUAv+qG*fp$r7 z(7GK+2BOv3XJ&_b=HbEkm6yZVVBgrtgk3JUZoT~a6`Po46+uBG>=cipjmkhpNtM0LrTDT&q zg)oFwV_x?WyZ;8uVcyp{Y-||A*2GuajFvtqh07y7Jy9_R-eYYGU!7a}yWjRtw5|Lr znRE7X4lCE&>-}B~Oaw;uY2xjAYo088)#}W zL$Z-Yx0^C01W~A=d8#h}Yp_DZJ-I5gW;5>lj`MGJ%aemU*LG>9y*skJ^}7W>)MS)N zFZYO9A!H7p3#55-o87ZcK?nD$OS8?Yj=ZSLZ1uZwbrgOjMj2Og0bts!f0bELzjU3A zk(rAvZSMTj#+LED{K|P9pqy6_6ZDt0!U^AQorE8*dSNwSs)_0qQmxmL&JzcUD6kw-x?+T1}eTP)1l!B^rF6w{) z*RNZ5;7d_)UH?1@6S6#ZMNJ>GuvJ6XJb$Wld#Y1fPF5ppIA@U+={FP2H8~x0GzmQ9 zEc-32`8r)l(vl2@k{FE_(sYWCK!qMJ&{Ok2boKgk7#@;8Ou*T&ybNS(tWah^8Rq_zo$@CoRv3_XcYQE zhQv+l^?8xRXbklipHFv|M>kziK0J8n+El$9Uf6J$JsG#yU9u+|I$P*{uh#XGs{i#m zc6=XHa?9Y{a{7}FM=0XvX3(iSW}-pT+ytro>V|2@7?aoAmqQ3IVU92N9k5*iEdT-V&Xz;y&xFu!X_fXX?{#(P;WNIkp#oy4g`4AY;+$_x^Iet@q>2 zY^@X7No{&=!p*RD3PpOHt|I!;v&Su4?r~X39OX0$(tds;_P%bu00<+?xyR~B#cRJt z`QF*qq&9K=cjk97_>)~zFF|w(JzK{oqj7;UhRD!3<<6C)<#qHciB3tZ^%&D|_25ki zrF_D2z*EDDfs6>GWXsAJQ}2t)w@K}^Gws<4-VWb)<0yPbGi;K&JjhX>upVwv65T-MHif zvALvx&LE(xf}dW7jc+;L!KMTWDYVtKMOkrzJibbImA7$tEh>S-A5_*-TG8g*--=wZ zcf79oUbFdXGjMdGO5nDUf058kU!@b@20n6Vh@+B zSPu73^u%wky_$br*YsW|Tyt_X@)taDqBQ;kRJKV4n>kFv>LWukk=x-{`sfG!^elw_ z7b;v82kU2BQI&6yN{Y35zbHbo1B*Hty_WQWmM}gU+pA&t5-*l(j_; zx~Ma1tCg^KUhz)s12ByTb@hqdi(q*8(g2L<9}cyzop&!tz^st;ked&->3QOy~} z;z3v|D~-MUMj*ze?|8pJy`rMGw;fx}xLyxFj6TxcbA1)|yP4f$RMfVDa|)EpIdqW! zd?u^~a=AfzSHHs2?fq(RanEg`-)H^L%nK%rG0apfbOHGvkjvE*xM;h9NNhDfiUz2H zi@$aMabDFY<*hi-K&>~H+2Xl;hgh@iA&iHIjG@iZ=M+Zbcj7k~Stj#Kr7`^J!3UC( zL74#f%>@f9PMH!6XM^Uh(#x3-hc%C`L{a$2y?4*e=y7(rJH?VtyR9hOu$I`Aq;dBx z4meQD|0Q!wc*i<^o&Qt46~rc5va9W`Y=;h5G_EnG^w@-iEXyKW?+s*f=wzhrmvv?; z``VUqd7MP*x8SwWRGeY1J14Em83>KAN{zfarvZMNJ*`psQ|tCE*4ItVt!w?KOlR4H zj)|M&f;WQ_j}c^PiGx^cW%G)3@#=}8;Mz@D7tw}%!i#&_Y*qH z({B}%zMt1l!0IRjilP+l&@wGwd6H2XXcc6@L&Z8e|M8BIlI$T2%{Zi^X{UhE;{{`U zk$3Z&@zb%!r`}@;=E{UsL7?3^H}bhIXR=q%V}}Jv>-a9cEAlw{MMInV${I`ap7>>@ zrK;A(2neKyatv!HQ? z{av}?^ZI~G0o?a5MY55Q{P-iKNGGR7#|cvEbKY1MyucLa+a{4yAm*Q>^A>?z7n5MTeIMd zuUZf#G#5oLD1*0A`WO~PkjBaK@P;{o`M_YH+a!QhHqg;@RJVdqM~MC<>2;7;(D8l6 z`<=#J70q@<%H>msnh%Dla-|#h!{f7Y4b|*h@xg-++TL2cfB14tuGRSCj}q+f0o)(dppk&${i@jN7#3cOMH57E!8eLxpGJSuxTE4vcDj!KStCAIwAzM2BMTcwff>tbp3aqQeUIl2+b9{SEbJ`p&nL$YSLI8rqyy> z3u9+G$~e(qwI1epy=lz5GT2mTSrq}Z`578SLwP7SZwf!laN!fHUwvF6b9kdiPHl+$ z^<<}!b1#cWK8~!!iC)1mN_943pMGei_FDs=UfSA95yI@I(obbF>0b?$3cB}5P0V&iY@CM< ze0k~e5ye?Dpy_a%L)+J5A%D_4!c6XitfeG4#nqIz|K@ys=dB(~p5zgU@S6v$5A%z> z=G-og=h85aV`&`~|gx`OLRC>i`&3MkTFI!P@@J1IhpBL|0eO;ioh|0;( z-nV9q|SEvQz^mn z1UtjQS2v3cl%(sn)!gE4a|N-Whk47_U{Hrt_^a^;l%J7 z8xr`wmZai0)^SS*mxRN}%K(xGJcX8T(LEHOf2-%Io=YKY!Iv%o-{mk=ubyy_rHlbs zLR?PtegU6+Xfmw^i0t9g+4r~1>;nhSMf&~qFu9xVxi=RWI%Zg@$Z_N@QKQ|ZYOb`e zAHM1pQqU+~oD{>&3H1;Z_FXiM7@mDqbd(vFcMg0BY7a0(m@ztaoWU=xQG`@sd)#e`tqYTYg^`}gbRRoW(;LJNF}d3&Rm?i@})48 z1i05XuaTti%z^M4N5(?e_<3tT|1QZf%u;}0It>7>ox2%i7rXRk?LEIO^O2kWN;A51t|!i*JW3&oyY@k3-AswgZcR6wzgBE)DUlLR5Pl2rVNw zo;*IPu{L)3N};+C$BBolAY$If3~M*T^<z+^!UxAhzV)=c}#x;#mqNQKw&Q&j%Paw5oF$Iu`ha3sAN)?Q;CC zd9B5(h!oEf@4!>5p>?-V0?#0HSMTF@-{iVXMlSy`c55^=0FjoH9~o)%ai6j0G-t=> z!MBfNkSRTH&NNPfpN^jaPgM;w$UY9J)hoxcU+i6e6p-I}N=uzBkM%{iA`vPzz?L(W z9a9bu=2A-2#_@s?2lb@kF9oO!-4aZRchbqUOjZZ$vp6c~QJ+fuIo4?vTi#JtKbRhy@xEV74nF%cjRM1IVzdw2@>YuAE^kNq*4x5(-@ufP9A$nfWqqSqJ^miI@ccWArk6C-X%wRUzSErH#Wh+=JH7N-lFNIw83TW~? zd|41%paUe2ug`QL0;?F*`?0G`(gwhH! zD@E#Pi?)O-z!$V#G}FE#Sy}G=3fYJnUTV}*Sd#JI=!CU!4%9(!-!3TTkYu5aO3juE zfG57FY%ijA8!Rt0w|rTGE9sK0SesDDtJ2LYO&Oc>9St)C@sNrDf9{`LUN5h!n#$rxE1= zgR|)GPLwmHYH~epTxwxD3}<8Zi_cDwL4KpS;iga-;jc3pN1O9MNGmuu&vT!8k^*61P?$cgvl*t9LTzAh>0^qfx`&Z`9fn&-~1vOvD0I ztF*EzrPmqAclN&A#Cl#J`bSe(?QTOEeWY?s>0GBMo4U(Ja7*#8EqeGY!#Vv?mb>>p z#PCkn@wo?wGHwZ1y?5eOlw>Si@08nR7R8?NYoTwVDPorKff=RktbMK5*soi5K}M*; z5Jkt~ZS}HK>sdtvmnVs3l&FLK+y>T~)vcYzZ?vn4u94rnHh`33WRtusqIU<-tjoxi zYNqZMd6cyKyfNu`YsvnjQ$t9DZvgyjILQ4o7UP|vy^>m9OU%x>lz%x@HpXlTQq5VT zt2fM)2-0T-1pbAeud5;#6O}0$UTRxh06?6f`^7jdV(7?=G4e)Ra3S5={hSreRQ5nr z1U0qa1fZcogu_$%S_E*;sOxz z$&QI-q_R<{47Je9;>7n`^bI-gBX#TrfV8VfF?L8{@2GH6>wrgpNOwb(QoaK=WL>PX z9eu;L$lNo^B??uK8KmEljlTd~B0GXFAm0AAyEX7MdpR$SOk5LdwYpB?@vz~z<6CiA zJp}JHC-Pa*r#`PdNfvYU{p-=%zI65vR8Vc_fVX>vG2d!S zbAYzkrFvpc%A-7uip3gA)%WwrtElm(>6=FFm(uPFHNyp-k8+oP8`JXMqtKY+&lz+) z?t9wK-#s_1*_VjDf@*lXPoHm{m%#n_C9-)bZRMaVpL2Y}LnbJ_x}AbgGxx`x2}+jJ z$Q_%Cq4%v$kam}Wa?D7=WS~6OWuWZKvZ@5slzCR@3X97uVJY*x-<|v9OvD;oAZ^~6OnIPB zv?O`pSqM8zX+zrQK+jnE0 z8akNJJZFPy$i30{{A+uHwW5b`ukA4o-DnqeIC<@xJx#q!hpHak$=AfWZ4kXKeA{>f z(U)u$mt(c8Kbz!Z5#zw!1O~}17MvFCGJ`V6lr7k);bKMHERqe9{r%e5Tx{; z@Et;|ML#7;P^w&`2&^~>KBe)lwDsroOIMmQRGl$9Eh1?F8;>qQF|XxW?8Rd{S4J9F z&cZEr_65|Z78AMyAJV2427J7^7 zcG-$wHnl2~S7LV(R|E3RUer9(;qdqcH5?dXp{U!5N^I`U@cY(WW$0ILQxtK1`z=3`qf*mVX`lZGv@8RuppRE{-|+>Zky686pS4Mqc&g~{ ztEr^AayTV$N8>b<2IT5p`EDga>&oKK{dANazXdu1D=f5ceiU!iZtoX1gP7J57pGVn z5Su&Vgr8 z?zjQp$WGk`VP~_7gM6yMuS!)QYKG3<_dKqso@K-}NU7Mi%anYqKTe1*-BnER?rN%( zy<@Pl))~>tcw+5ycGVTdyS?A@F^aptppZtYGK%~@y z+XFcQd+v3-v-|=RP1fOEa50D;;gp1&Rx56*#5+(Mg+;% z=}ORHx*=Sh#8ALwJX@Rc;5b89=B>hgrM8ydpStCXfx;LkrsdkIaKrX?Ev|U_W6#)f zQmS6XN`CZ_54y)`-p0_9e`(Vhlr9sPP|n$oEE&NEe1ny9eZPqDG5j_IUNssYYG zmE&ICgBUH*_D2rD4GN8{0XozPqf^Nr}-j*U6ohg>*rF5M_ z;pmknyHCCD%XJsD*$QHsC0Uo%jHx%AMI@YC$zfSOvr+rhNAi9;yFygWa#_A~Mv$MP z=PANEo9>-X&Q_3?&b;`>X8)Q@Z&U#M`RN0^jJ!Ievui8b@DO^F-=DNA9+hb^@^tG> z;ksC;4AqWA&(UGgmdfC3m*Q?9IGmoHXN&4`ibhU$fk=GpPV#;)+|{8HcSQ(u&zd7PuPBW9Fbupjq&R5 z48xp~B^b}(*fAOF+-V?kSVX~D`P{rtgA#t|8pb{O+hij0B@$s{*2J zAsgCJsR)(LLdU7J_!Kn#_CY*ep+lt(5(D}Im1pP}soDokTz@n;Cudvpl#CG<1Xr|p z9T3dDd^zirV1SxsQ-lBqxIW=wA7ahy^NiG4wG7$3O|o5WTSa5P{4N(DcrEfsZ{Ze! z9zD02c&BPW?9LERG^gd)GCD>3WRg_VJ-?^lh6(~tXO1oa%4MBCdYm$G6iVkFOB16V z0zh^1cr^yj5Q!_e!Q!3bMXwHGj!w7f)|x?hixf)?g?;{XSCEj#b`e6$jLp00p!_Vm zk?Z)Kc$ru-<7wi`BB6$7%XRjnVXFOGr;;-mLG`Rc1~^Zx>{wxni`p#3fgRzdas1Xz1;IC!U!_kfDp?q)I(C!9O<_ z@qO~B!M)5oUbCUmK9SUbDw-3`%D;smJ?~WTL}Dkyy5z*C;y^BYTV`oyG;$W)`Uy`< z^MU}}t~5YXeu&93oIDT|J&rSji`CS;{zjHP7)6W?E&y3Rif?5|5b524Lz$O)HH3CaL3A=mwtiI4 za$8!JTXSI^f@9@R@`pPhmz_i4T6kYjh+$65*QYgZ$r!o5WdKMKVZ8bHt`~ONkOd%5Iop#E?*=1)#!*tis< z(qZqd9yvsKS9bPA(96-rtE-uOkE~I$Pi$oT{MUL`W+MGGM>AV!VPMYv*Xx)09{8~O z0D^!GCef{lnpMAUExvdZySBDwYH7+>D4^bLaEZR3@U!adbNERYyRjfh{&>{H@>F6% zGy?s`7pZdM)=u1rIl1#d+Cp`M*=5Mp=DaJIlYeL%vR@=suNaZ|(K_Ht(rfpU?TyrC zeumEo&qvAIK=iyxQR=p|Qq{{12Cgf?QCCp22?1tjpV>AtfMD!W{5tZMpG*0{){61< zUj8n--ii=3YwYeQown%R@W@*md3FGF+e!kUJ4pP_r84QGD$oz=%*fbdN~a2z5_IclTr&5mC{gs--c(DRti)hws&Md zF%sZ-CgZNuQToN6JZZSk;~KTRhcYx9lPuz0xNE@U+qo z>^ps&C5L+i{#wD)WT|vZN}(K)v1P?09sRH7fuBZGFGd)&~S|H{4N ztigJW*(tJ>PWhI!>QZd?1*nP(on0}WoKR)%CUk9?rn^`$hM;?hCq?&9bj;SP+s9eu zB`4q^*|n_Y*12s)D>lkL+7=!>Is5JWuKa4Pht{EeO(pr;D}`}WMWCO^zZ#y(DWO*G9!-pl>)-F`rRv&LEMe?Z!B2zb>xTAum)0N<06Q7|sLWjQ6OehuVjCzwC<87wEOGxGkd@WGG3%8Ke(v4J zK4K`{$;f4%mqA0!HEDI+sXscfw%7=`%G%A!?DPvgtw1AubaKdWh%VT=lFh*sT<3Fn zyp!OfBRfDV>o3&I0F^vESck&7i%H_`8Zp&zATCUm+-F(LNL=XH=LfM3F3# zSTNCO$vzFk46*KK%#yIN1WDKs3(_svz`vMYA$B+(FN+81lE_Q1m4XN+?>z9|LLp4}1fJOnXH2BUimKXJIKK0!NfUaJs z2NW*0q0lc9Tgl(0DXEuJ=Qp4|Z$4fAZp?CW7l@XjLGACMUpLLAH(hmv=@$$3RKxmGKjAyTekXc!%##n)OM|@l z*$Ba_8l&l1W)-}bH8oi179z#0%3~XT^T<+A7fkWj;Y0xLh0(OG`YdwBhdb zHc+G=_Wr?!`qHrCuV5|<$i^sy#pMK6=)Er~`)uC2f1aQmVoCt5_0BFpUt{e*k)&k0 zOR}L$3cdaPtnan!TbMmW#NKX70Mi5xT>x&CKYPDb@a%ztDp=By9L7Z|MBz&|_!`^$rBpAWnF|JNgm?aMPO({ycB5LLVDei=Jky<#j0);w?_|J^EF875 zN^m+uq44cnt!CTLrIq8Y@}2Hck1m?DMCY;-G6(_rQ{|vZukW`aK$E1x7&vQ)DKLclNBul^3`s9tra!8?(y= z_FFk)L;_lRsn+33YhXIkTy|G^K->(5b9=8Sul2`OmP!5HC_lZ=Vq6{t0TBB>L{*J0 zqg#~6L4LoyK-c|Ybs)I6exSpcn7D;j?=3YbD%A$3x4Xpet?93(AnmH(Wn^B_6|GCh zMBBC3)Qz!9T!9Uq4F9a_)Bz}L1@VW}G{l&e9&qjy?#o;N>^@hemYYA6e<{UuI(Z;H zTv%?^RNKfwIm2Nd&%Jlb6|GUuVn^$EL`$n5q*Csmrs5Ft+*a_2}^+6NRi1AYT}rpojmf~WH0)N-#Qeg z9qC>4bq?mrCTFl8U1+e?3l50>aJqq&ySodNyj(*5!)Al+3UsR_!uc|R{~;tHB8R-=?dX- zWM2xCpXjsUUlJ)2g=O%}jBPVmOJZ?qP=O9jEhK%h3fH9+$+W@7_In-&@h3VQkTD-=Y$Bh{P{ zeGQ&%cn1aj679gK7Fh&F$yV5C`xHnrw&^(pc5}1<*c1nvgzq=mgGnb*9+Ee#xi*bK znj`f%t+TpD2HWFXOw&1-bKe}f-jIO7{d`Tl3| zGk11|O;?}3a28@N;v>vR4gBtY#t!KucMIJz>uIba?g@Avxlkh3Gkjd1Z`0k*jNcsV z@eXVH!>@7YdGdSH;-2zzEH962O^@Lx6Y%iWtsf?A{GL&g%)uDRVv-?$C-hYQW6ryL zQ=x-ovlC4pr{U+9Gw|WhuS__`-vEod-78Rpc2c)_kCYMnBt6R!GdG>k7YJnm3Eq(e zqGx2z>>A2MU6HtbqkQkA?g`As!RWKj_I{V>f&4LlSpS~fjM=n8J&rkCbARPTZ-*x* za4@yvenj%|#Nv?uOUi`jfh>BoJ_{h^Ij6IS8tg@~ic-txaMNn)_JEv&*AT_@vk>pP zgJ0Ws!p*k?3mt@4EBL8ruVq8D6nYPD&s1A2|e|*+^6J?2(?V=&;bl z+az5_=fy9w7XV=%+3FQT-BePK@kYem)2P&46kOfP(lc-xp1Q5$^rn_Yu<~OS(-&m+ z3}+Y))c_o6bjNoP(43v=U&MLd{{Ss)#BZ1e&)*-9Tn%_4lbA`{ zdpXLwfAA)Hku|kdj@diJN&EuPlY&%VVa8#KGg+A$2y8I=u~}W< zrL(w@$*dp!ltZ5EFx37glg9e)d;`;UC?;FJrJ17e>6mc@L2Ns9J;me0?n`Nx-uZLc zkj9AZ(e>&YZSnaOWxz`mqL289j2YF@{l`IaaYfoJ7A~oVCL(Ga$pMMnEl_P&AX;VQ zK{?G6f6aN&xVj!?`xMFfKoHe_OK}l_>{LMCNXE5?F6t!YNqKep@iJBfAbK? z>VsP`Q}*_2&8=egVoS!*7vJW^BPjhZ{dOM&;``J7Tuk@4gw03*Ho)v$&>chPE3HnYrbd!EOzB>7swo7-&$^?hTCJFB}stcV=c` z8!M(b85f<<9@Tm@!*A~>$sV;+y;Ke>uWsKru}PN@4cNGPRS0#CM>_D@`Pt-C?OAAwxCLA4jz3{;*5h_>XGA!FYky9*52{%GKF@qrEIxT4V~prN(1HSDwLGg|l?uT*-|M)p!--5TN9$ z&&oj2y|PjqJB{DoL3Y5`1u>cHDB=zBvP)#er{iw5?C*eOWr&Qf|A;l4mGoYZt_D7%QZHpG`vijB{})tjnNSnbrC) zWoDngpPlqC;E!o&6yyP+V_Jp7T^+Cv*;JM0eHv7cj#0NKv&Is?QRfbZM1;7#)-h0G zA2}!J449)qbQQ%>Vk8}z$vsz|B``f5r+rEqMa*c^$+cGq6db0%>N_1;?uSr!K?wQE z0?85|lLh5h;t6Z0ETII?NYDN!Tv*nzjzMUT(MOG`FV&Ld7`bezk%~gp`YqFXizuer zS2~wU>UfaCZEn4Bf|6DJ3+yE?XY@PR(uU&3x#X+4Xxr>nyWgFbl5};p!KO_W-i?Mc zO1r{A7Ku2o5!3MdIYq6Z$yer1%aVc z7)rMNR`1hhHqoQ;Q;1C}xeUbhSE*>EqPwB&#F^;+Wb0d8 zVbn|dEwdWuZ0(#urE^R& zcAyk3);WT>);iAls_|@P0wZS^0BP}s0Jmf|3KHC2n_qZ4f|bkmEZXYPr$E!s9$03x%*@WV86#yJCbea9b4isI?!+5>>2fs=wj=aM^$ef)+#y}6sNF%}mgsVM>Hd3GNSsLvY&%H=Htcdc^U!+w|#sAZeWcRUQ|xyM}N zwPdvWRfKE+Vouif9nU}yHPIMob2;l`{Q85UI8XJR0;oOu{RkcV)^yiWv#Pe$A53z3 z9x#9U^#fc+vayV=2+jb>&rp4b>s9uN8*-1AoR;L^44sw`xCW+C4lfdc;<0CoeHK%Lx&RikJK>+iRG6rw}1RwsrSG9=>;y2nCAOnoy zj!Eo(rnR9BlN6v~InFpI7yu9GIj&(?q#++{A=w?t5AuRG?Hx!wQzweq_9P^i8QB&6$Q?W`HFlLDms&G}f3Qi7s zj+_pE!n4u`QHWcH&lx?l^An2c#k`Pk04I~}?a*_9+mCvH+D4gW*cvm)9AKR1uN{81 zq$gp{ld;MDjY^Qpy&G#Da6NJB&svM@QzN&Vk}&0o!bDc!y+R&j2#3r%%O`A?3mj(Zd7 zkM8mL^H7vJqi9u{_*uKA_`6oLA~tqFfruzD2HYI3Iv+~+{{RpE(;hd{G^jK?Jxbvq z54ud1CDf2e1-TjSKQ6WNUzA!B@Apqoy@qk~XY}=}u|VQMpS#gd@e&6(_04ltz|xY{ z9n`T^qSd5+xp-gx3IlaLyf)gkqy)sR%O=lZmO^v*kHA;C_-ppV@UFAsdl=PMjbJJ#)iy0e|76Oc|qmG6_lAn}h;>-u<@ zo*l!>q3u!5tJAip^grUi+JnM=8;Z*2(WRAcMo3T}U>xM_Bx9#ud9P9MU+rb!i}(;t za?v{uk||TiKu_Jxe>yr>h_%ZU@|t$S5CAyZ0qdN1$@H&G(7q*jg33`G=(40^B;#n$ zUO71RuO7b!#p_J=X>naxN8i}~mb8D1-Wk>rO_k(rla3q{pL*&)w8ZjxnJiBOrh4iJoK;8 z@*JL?9-41+@~$n;rHhk_dL#Kk)IVYSDAb}@eBQfxQPZIB>0V{6e#B6S-9@t#&nhwa z6V|`2+wXxs7nq%~uRVD0T%G6a<>A|pm&;xc1GRk`<+g{#`v%YCCsX~1i)EGuP`m&K zy>QoGv9_rO(-KR^UB^F9ui?#qU)SHV&W$S&kgqw-a=Mr7kES+u!U6uYMJ>sVDPG9_ zLFfIJJYi%0qG{vC2Lz1N5AZYM)}C``e{`jeGO`|nw;e0`%)kAQ?Hu7@1h-;6I&)lI z_v~|TozYv4gdRVatqm&zb4T*N-U;~grvCuPrmcJEaU=FV#O9k5e$zT?forVaZcP2+ z2>x8x^x=8?8boqh&uAm~M^DPR3%}UWd)jgbTxXmPl^((?Qk182`OJgI-?dGO1#Md4 zfX*@jB7ZkkJ!vU_}0+w8OSP0$>*=X>0Hgv>}GHg zZ3ri++x~G;?9ow_kHN9=>-Mk_g=_aG9G!r5Kd(w8{h)tpr9N=InUr-Hh%Mstx-ZWS{gh2+jyze^Hv!RMm&f(fEMBv_I`y>;S)$10dxFN$uZ{ zd}f^|?G5`>$g!(l$+&&u5M!@$a(V4vwx96ELut*J4aaWZN|=7e@3bkl&U%u+mD3u~d|=lShCw*^xj zSw2`rx5}>UmqeG~ep`ObehdA#e`#+Ou9c-~lIglsE(PYNG7l;xAKb^^d~g&Wt}FUd z_)qY!MEFhNXgoQk%`NQeqt3jzAk91DmTYi2{t>{gqrv_d@VA2W3x5uHKGrKc8)XWS z#Gyw{r@1G&HPhqQivHj5)56>yRZ2LDsZOiwx?YF;vHdu{o;*Xxd6it3FO=}u2sXJs z7dwA4R{M{|Klm%Ji9RZLQs==}-wrP&wON+tIfP&wkW{HXdS|76EyMAj_M|RRwR!pL zv;s5f{!M>VAGLqM;qhNj(Ul_-8!2QsAf6pS?Oznh`yI*=L9`(8fK+4G(!ZL#X~U(T z)$_6b+y2cAf4A_DFHv6)GW(hMf<7|-)QaWKuXOA&kWc~m@N@VYbblQG0BTGYlU2Cq zBPB)-dJdSc+d02uw<)*me1q9}_2acy{{V(Sc=NW!GU z{iu-{rq(V11LgS_kHCTa>ND}@_M(LBU0!)h4wxA#eE=MO75hCu?1etf>t@7bgSWrF zYwZt*+BS#auLo(~7P;_kwewlTBWs69%RfJPzE8rwi-+=B7`l!Xs;X-FsH0^Yf^R}HdKbUX$Uf;D8pvC>Oao2!CkLmbzs2}5B?KL4We{9`_ z$MA*V`*Hq#>-wr1uZK5nUx)U*1CS$+kNk#mYtm=%mw}hT^6MJUhAgdSc$*gM1aA3d zI|f3Id-2l0K*9J^LlX(l4U3GF7P@SYPiPg2s<|iFr7y$bU{ja|LlU_@QxQ^3myAzGL z#!pJQrvAv%0J62NGmbII75OeB4anS2^g98Gomw!fIJDYM&!zewh|*ttc+>zFTDAL* z0K|+3{>z%nT?69|pv5lrE7lzU0Lxd&&t8VVer>;GOOiH=RRr`QJw5tX>_4&{!3x6E zoOAbo!nmz%4&@0m`RE@DJ|Sv5R`O}&8OCIHJwB(JVE7B-Teb5Y7_sQbk+k>eU(v)L zvJ9>lY#0ZgSLXV3>sYZe^GK?sF?i zxQ}3gh~qdN^UZg?4oS_XUrqyEf#Nst2<%sI|KTKZGMf3tpxYLUp$Dcjo| z^WWOOq|&@13k)E_^c?2Bb4~F2`6?Ypp#*isR5ulo@vgJ*(#uS;@~mu?&NI_L=kl+a z@v7SE@PH8^rFByx zXQb(uw-RY4+B3-mCmf2w)nT}~wspf{LBnw?B~)WkyhM=E7T8K)g_=9o)++wdThL&GD7-e{A=HIJu)E@mK`uT^d0M$ zv2>Z2%3a5f_2_z4q{^G*`3I+7^__`Jxzt(OMyfW9pKgAYsx8&mZqv7^!O6{0wvkr> z4gmD#v|*G6+_?j;2$$gVU48zxY?=9Cwl1_pnFm93Pv1%egbq^vj(8sI}_UnKa~;l8kx8DMPa+B>z=&QEt)t1h7V(p zPw}V|Qb`6RI3uN7T}nUoU~+qRs+GDAnZ1P?cpS(B4&9H?`_`S8>qqR z266uY*Q;M@Suj-l;DA3KDZ$y3%*c~RjigmLCnvUg{VH|PAt{oBaPN=tr^9r>ZaCuy zE5Ro}*R^UT>jvET$vHl`{d-pG*SV8&F+brP&+fM19%`%jW99PW>)aks;a!|}hX9eg zp2s8)$E7)Lyut&FfyZB3)zgb5RFdd<>*!@mBw&DY03CZ)W9ZT^5d*j$K|Q_wtJNj) zP85uE7(e4xWk^9K2VY+P)T2vHSxTk%Jhr{e;#n)=Z?KS$bgC%-<3I3h4eJSGv;CQe%=wsjsYch*CYw{W}WaCvCEA$9nm^ zW*ReAk@fj@I&>v?v+|3@zYcXT58O!7##94>c|WCjlh|Cq+fh0m-GzR;c#pz*M~JPO z8#G}%l1(+qWPUb{&mz@ z?PL-4VeM9~^f_&0^5s%F{AySrF|Y-A9@XT^9nYzSZf}IsOA$62J~7FyyL)BAqm8E( z6bNHb%yF96M~!}}JJ9L%u;o>V)&&5;+@q#yIU^oU&<1;RS7o}7gl>80D-!1FIF1Wr zjl!I%C1ylkr!}g`u!6wgkHht^B-ZuE-YwuiG0q6Cqs4m5x)ExA_a6LLokanTQ*$dF z&BrGo=la)`UTXF|dN6ykyqaO2DJ~{$&({Z`uN3%otG|vvX!}2hx|1|E7NMk-@K4M= z0l;7~I2G1-*Wx^04%TceE(@&Jvm`O7UPxvEh|e4j_3b|zJTSiwuSdnr4mjh}tnFFl zyMX}mGDb|82XD>6Cys0Gcxxz4dr7U&&v@HCv{edD$ANy(I$y;90NAU?cYhT1J6ns- z58vIv7@8B5-iUcSurOm`jB-fFQC)R#TV~L2`CXsM9 zcRdNoufYos5Zd^5-%7mGXPQ{IyU46C0un~kxAn&!o$L0DhbrY)OGEjei8G}+@~5ge z{aWJl`$@*7``LpqZKoiDIM@eXpp5ngx+$-s@PCH}w;nwCLGl#f5t87qrl;5_^bzG(V&who{HuZ2zH`P$ zO#XFQpU6g;@Khb1qn?=K{{YoQvNBH7#nT6>HN04e!zbTj4tOj(V;;2mE{MC_(u!3wCzz#&-B1Qk9B15TwQfTk zvTlnzc)@Ip4t;v@pUh&iAeJGzIWVMg&vJPK9kJ6V`qr(wETtq+aG`OMc=jhCb^L!S z%aI$V_C|%9$rGtZ3xm)c?j60yujyKs4TY1-Mc&FV2Tx8%*EuzjZvmg=j12Diz&OF{ zxcB0;o(Dz|mSV_29N=#M0337e-lAKb6mPjze8=9S9QQt)=;GX{g;Av=UJF@`8x)n{JDv+z| z@{UG(=cm(}bK63)HM1yAcmQPcjAV{GW7@hTvJ%FLDr2JM4l+UO)AKp$$E7&Hu?8@! zath_JLFc*a){EO(dy)BmCy2@@Fa|w?)eiNx=gH)7u}{oYvCW zxOK*HoRP&!qFfnaaA8KdLBCCuc+-yn&m>5bBg;Mg$&F$6#1Es z1`c{--?!&ahSW#7oM#}C!1JF#J^gE{mfqG|iQ{lGNgUvUTe$Qc#{lzCHM>R^%wLrJ zt&R!q0LC&u&S?bbB+RI6yMzV1hGkQ zU3LuPlgak=^y4}FD_R{jS`jlTEu5Z%XdQU%!0+GbQzv9~Ql%Hr$6Hw)THOf*5L94( zBOc#c+qW`C!sa4)3!X8~F@SpW-!*<4e=BM!QWS%XXXror{VQx(0$CAvoup-QK*{QT z`|((pQj}4V1Y!@KT#dXaJ$dJ^=Ur}_VJnd;sYPRsqq)Wb?VMD$8dsXCSo8OAPg9N# zJwL*|N5bA4p62!|WgEAirv!7)ABREj*1bAVYje)TJD*wp%pMBX9_g>443cMJG4(uy zp5SM=750aNKW;CH{{RGjBuPJm;j`6jY*Xy<$8f9&Wn;OroRgjhU@HgVUWsM!{{Z2| z*NCpy%WXc;xX4kLBMLiYoc{ovSI0gZON*Ulbt{D)U!G(Ojxbw2dCwn-udB*38dYHG zO&^=_KM~ZSIMSx9N{pQCJBT~7cop-wy7Zw_*~Msj7-|(= zHBwIZKYF|)`&N85@pahK^u1OIC2U~}famZ$pUS?U({+T@;7glk3=h6*`HlUw{1Ku2 zJ+|=gi~JWPmSHSzxd!WifAw1R89Y(ysS zBw&23N2ut1de>Gb2H{RM6VaTQOuRdbKx`T<8X*vfm8d2q1#m3j8fLe`dy zd5Lq6!kO~pftnSLenW%mXy#>F$dBwca)Z7k=c&a-CYPqW9nc^LryXkQw^ViJ< zgYEblS0XXFl=>!+;D4j1NqGIh(Y1CbNWKGw0-dc55JpTYf(dCBjSale308%r8I-K;b zk@TG}82dVL&N1KdtHqhKk%ji4rqj<%XNvqojQFZ~&NJ(Chb)>(%gaOkKl(QK6^HQK zh8GRtYPz(cDLA_%?D~9+d9$2L(5_v!p7ii;w?eAK*G5D*_ ze<($>CvM_1kA5qkiY;L3(j0hF7X9Bl|#7d;;yTea;d%xs=9epJJ zl~JXfU0&gI=yMs&ulGl%xv$UX!MKmE!v#WWa(~OJKd)&0B(ivLz9Wir zN)<4)sNGt$IVC62MLzv3a{7c83c}Xb6%GjJ1J|e4tbb(Mi*X&yYQ&DGx8YivMvBWH z+U|yAen3CNpI>uYvT2+1w~UNe)^TocM=imuivafiB$rp&c_Z*2qxXlomm2XLyj0@a zZWmU<(SP#ppGmd+(nprv_;%HakV3qB3R`_5*5B_!ocap%W2f_m?mv|@X}LJ(^smZW zcDp~&B^7-RB-_TMENZwTk4lVNjg9iE`j9;<&<2Q%0={ZNqD8j_Yn;&YaSXfw04Kk- zF|3@wlza3eujgKtbXZd;ryp94w3q_{>FYoqdNlGzTky|OihF69$F6J8-%o)u+~*Zl ztzlf19esMx2M)SnRVX;mOwv7)DLa&4ae_KmSoZL2!!7_g6+8s1In!YK77IQ^x*T?9qX~N&{r4( z?)2lWcb3{Uy7J4CMmhdfuWhD95Cu3n_U=8aJHiipec}h6;r7N! zC$Q_qdk(qq_SW-FXR{klK`c%O(aY<=+2Cn(-9k8m2LVFfudAt4ZaPjiYcJ zj(7$tG&N4;K-`t~Q=leC{o(vAqr0y>ZnUNSmo@TZ6s&UjTPA3;_o z(OdgQMN+ArzfQbVuxm4Uz%eD191m){4Y*=R#sJ1asYRlbxxgm_oO8$j09up3LKi7s zJz>7@-Co^CUsF>JWy^^U4tjIVOl%dRJuox$IPL30X}0RwV0z=+3Uundi%AO}yx|Iy z^BzF&if8uT2vB!*`c#jkKxGYs&*k{kE22VBlBXj$t(@A}mrV%z`mP2Wr=g~Q!a}}{ z`5G6);~DvvJ*nUDkFWQdr`n>q5&zZwqwyEsa)1i*%cwr7ggkJb^<4m2Q*}y-}zTI|I2Y1cE$gV3{&~(j7OE?J4&(PP8 zh|2l3f%W-U5;%Lc50PWEc$Wlj1-_W5rIlk0n|bY@YWAH|!L!0ig+qXI^{yjT@ZIDw zmROHMdU9*Vt%j)s>?mh6rk1CZ>N=xasV4w>W372UyW;5zl!1zqkOzOlwLD>Qc?H8; zgkZyhJ?qQ_#P-+UwJ>XNX#D8fB5j(rzQ&7hVb6ybi~T=l%7j_aXtP4aN zDpZriiIu?w9CSDXAG~EbI!!`5Bl$~-xQ0{al=N)iyl?P}O!#T>TgN{R?(S_G*FwCO zKPo`LC?Q+`p!0=bGyXN<8jaqLZ1k&pHuIPUM~?t9e{kdsVEPWHoK~NXyfLX*&8_N< zsJ+G2#Na%SBTFoj6#$oZJBw}LmOPK3u4}^jE9ua`h&6%{Eym|K&UW-%`yLOe?~45n zaa1T={GN;@h{PndFn%O!i{PCc+j*c*e2=}O?4zzvUz@P&*1jy(p6)xrHNhXeRgyIu zae_M^Ks#4g@gv7G_`_Y6@!JcMp+*K26SM$0&N|?8?_N^UBjVXt<{P&T#4+bRhAZ=& zb!Ap=N9!00e$JYL9rmc+P!)2ZmE2EJ(*wS7{&}hHr;R2F5LRNNso{@v$EQF#3WxW9 zG!3``jl_}Eb^x66K9uEw)&6|56&(No5HK=5y$2s!;gqa;P|%{GOSp2Oe~4$>*Pgz@ zqjK^oI|7s(5&hCTn!V&Ts)uFgIYE!i`gE$3Bc!5RK-oFKBaWRr<2|^nlh)>r%+3*c z(&umou+9cMa69`_lx`#4@(#VhBOIvidHQ^ z4D`=I+ZpvHrbUu(-VEomgVznzj<`KdPCt7wafJjBRgYYBT!G)HA6_YQGMst~Zly{U zAy^(d3=YI`-1V(!CGsEli@95;ILBV(j{Q5kqMu7*2vB;HJH8wWi)08f6OomsZh=94n2 z5~Z+r@()~)bHVM#eJX6^_cV;l~MtGFD;x8 zPP~3KryZ7NQ4)>(DGh=!da2`&^U1D@PqIhy?Z7RJC(DtR;8Uf5QVmO6qNN$ijKgf-|%g2P4x1{{XLB_BL-49syu7Gr&CafywWV zFe_>eHby{g_Q=GZc^H0}{5@-?gl{B{3`I*O%>5rmVIuVT1{sGS9P_~Zx#OPo^$)Fs8d}-M8QKnT+=9J-!o0UY(7clrOdRhlIR_1&UV43N^$Yed@KejE-S~p-10*0U ze0S(Rr#_YJ#)HuLe0E~#rph0*_4U7mejQkNBE%6sr#G1R8TlYM13v6>5A&~`J{{;M z%8qN4Er2iv7m?E#2mb)C_}8fZ(l@a9$K#F0j|<3cw1gIl56q;m-)sTYzTx--T^EBi zV;-SzYikzmj-%xn`EoJ`sr+-CSL&Hg9aEv|ehHsrrHI5c?Z4UM#s2^pG+zr(plJv- z4Gib~0(ketySO`g6v^xe6#Z-ChlV^8uPx*F62d)7Jg}6?+d~egZrt@9GCiyG{{Z%C z@TZ16G2m8BJN+)&?Kdp4#!_9oakr3oR>}3vem(xy8s3+#d}`IK^yp%?hQX5G%Z~&X zPzyODyOYnQdG95|RjA#L>1P<6JrwzmF!+`6L&m=yylHQ&c*12YxVN{0B_b$d$U9MT zag%~iQhVcy{+NGa-vUSBABFbuN1SV3qeV!W%CE%^$@zr41z8ILnmMN4t9m4+9ur}L`zWM5qfOeuoB&r&O%@ipkvG^d<#B%~q_ zLU_$}Tru0w57xYc#n;WN>#L^Oe8M~;`WIq9kgw4^GU2t4%^;`nLs#gJ35ZQ%AsBQ*4t}mpDJWk3GQZe-mDVaR$^RbGDzRS=;H>5m~@a z5jOrk$*VUE1-k+1T;3pO?=#IOU3@9odMy$3KSTcj2I0W`34_X?@ua!xKCW`r-_v80 zg@nBaTGxWr3}bTj_4KS8X3Knsq2{|Qbpi}$K8C&~RJxzj(Q3s5WTOe6rySQ2Yoy*E z7hPPK*g>_iCO%SdJJ+MgW8QK(>yhhKnq=LylaE2(zJnysXMv|yoKm$&^7rk3&t{WUQG60Ad^u#l(te!f^ZlNU}OQ;pw4U9yy3fy zW2PzzE;cT6>z~HGjtb)+?0HV7vQlzZ*P`<5esT1f`ZYfhu-IH2vGT*yqb_?zCZyKf z$*Wm*vFD4a__XI5Zco$y0J5NJ-YCvK!L>=wKQ}O#b!yTKza?$+wiZ>Wy;;svOl)))aM976(!8l)%WxAG;QZov>`lmS0tHOXE?_= z6`Y_%fT-)h`cz3Xd1ogbxc*hj;JO`Xxh2LFmR_BGKPsyvxXO%!)O*rM#~_}k)0(1A z={Bc+=R9*sQvvTI9!bde%`v}tKqDg=9eJxhL3hpx_3fInA$_^Q&(es)xEZMno~yeZ zz5f6jvmK(JnOE>0m8a!w1&W`WrCN>_Ob`zpy{PtJQHskrQaJ1RRm8U2^5ZOO`YBJF z1&2>u)a#IUD8M{p{{XK~kpRnhm41A59R*+5v9419cjKO&DPb5~Fu*zE-|JJXzcTea zAJdASKqZS21AsG*2fwKItMGi?xdZX$s4A>`cqjb-0F7O@+K++3=|hcx*0w;(2VsxL z>smp6Uo;K@!5)~XE%!FUS2+AC@olTOXE?{?eQ9pW=yAR&g^jV2CFF8(>0dqE3yY0K znp~oS0OG!y)&_0zGRN2YSDYqMbgl*98#~S+t5|NC(e!5W5-My(q#pA zH&NE9lF*jQCM(Cgn~@Lg28s}?t9mDb*H2)u#A-*x^?uYCA0`Z7{)SkEAh!E z9U1zHtJL9yH#-~T=y}IqYJ5@N?ZbuxC$IQddNlZ)f=E66I#ZKRi3ePkImxWtEUs+| zh~Uh#7`GI|a1Y_$r;cVVv<^?Nr}M>kf7vQV`0_~~UIjHYK{xMNF|^|znf{fFZuUj! z&Qt9#A2I=z10KKU@T(u%E)SLK*Xik9B53`J;CkadKb=E1iPWOt4yV5rr#oE&$jle# z9(G0-ik>}ENiay>tUvvJm2EUwf^!}l9P!EhYC)r}0Z?+I9`&4e6_O!cM`#QeE6|R- z)QPGxwm{n1D}%tt(xs0^K)zgIfnoa852KyA48ReC@Aw+IN!U3%78g?hV;KAeJNrz3 zkSe@dc?btB?%2&q{h#eor()0l*8O?bE)maK^UK4rjt@~=nuXg)Hx7f2E04L8FNQlu zt$0<{+3wPnh??R&1Js^4sFq@QZZYdsywxm1{{V$o60CnHylf6)848s#%*2hO+3W72Lyd{Qp7FqAvUuB**Oe7 ztD1YbO0q^hNBvu>qb>EH7UP!pEG<)@EnVL^TMF+IT`G0!7ltb z;g0MP)MK@Nj`*KJ{@Bw9b@|X`ax3D`8b=n8C6Z05BgiGcQ}|cH=Q&%aR>^LD4wdE~7XCH-MEJX_cu77Wm@V%# zZ8~dHcN=XtfEDtjnMlBq6m7`BIVT-4_P6a%`%6LbAK}f$nI+A#_=Ce&@X4me0WsWZ z_oPX_2Vt~`vPlQ9#yPLXzllC2)wQ1$7Q0~gF`xtwl}jGDRp1_T*1ulKFi=aHNd9)u z@spIfZ*uGDT8^Ws&A#a+LneM%1A0JhgrG5xM3igR&sJk z=NRPRbmQm;UTehS9K!PUaXyQMvc6b*S#EI?qqCGO7%?GFAF1wt&oxbBfh5Udm^jJg z9AJ&V*Wa90$c22vCB%CM2H-|XIOH6j=l=lJRv?Z5`{R%0`9KUg9Zopuli#g;l%FcG z_Hn1FN9^GxR8$H+RSFJqo`sFh~VT7tVh?k9lffU)NHMGNvA}?`3KD8 z(`q;hM#>$K3l`)WcBY!}95rNbSt!o0ze7v{aJa9Q9hB)*d-;H!P z^Ihr}CR>%-F@??!G70A#(1YpyXbB2t)BzJI z`<#K1(B*&5D?$>!r5ILV%2^fLIqUObeL%qN?kdbmBRjTddhkI!=hy4l)z-J&0A=6| zF$5kvllb-Lw-~1+Z4P9KSNDJc&m*f3P&#D(RGW7+NXi={A|2UPIbt~Pk-<3s01DW( zXNUK}hSAAZ$pnrugU&t3_WCt!mRT`y!=IFv7y~1wc^LZDmWo?;+@y?-8Ji=M*m{3j zV}|<|0~dCi0UR(V85zjr06#xZVOl^)N0$|DL`BOc@$qXcrqrZKU1KIh%RK8Mr} z)pyKgkLDQ#PBX|LXSw{n>nTX-f^sd}mfUs~3{HCSo(I#9@bA}AP^7K`V4bHNazBeX zJbH1~s!a;Y{{Vc3JYZu00x(B$gX!0%c&&7|$L<^gz<(Aoj@cvW(;v#9?Su<3!x0Ke zJdL?*gU4ZvV1dx}t8nS^2~yjqO{KB-PjGY3=~7!Hu^@@t?*heG@wvKl*FV?Rx2^5P z#Av=&SCVtke7FD{bk7~fLU^p_9W*+lXYQ3@uz4*@q?=U^-K2EK9=!9x#cauEb{wK` zhapMGILSRbk8kpBEt&i1axw;SxMU7G4*b^Nl`CW`pOh{;s<=zf<`MGWmoS22LSP$0l_}M zTGzB!fm>kMA1Y4-ayt?_9OKry3mrJc3L~%1zbON*-oSRpxb&`HXj)3|TV!3uhzK#pF~~gE>`%dcI>+I!!I?Z) zc7!dxw3l)c3WMb?RDZym99QOt!mkWmYknou^o3Ui!lb#9Se_Hzo;8nhvYw;sXU3SUuEba)6);8M9k^pR+@R`X6uhdt~o*uKc zw7EJRso(Zs4tU%32e>A`Yd>Khf?gWeyfx~Ts=W^G`On}*ewk9# z>3JWGC_1%|we@?y5Bx9iW$w48qFY*NR#HzK@&U3ys!8P-XFPT4Yx&CY9;-gRt=((7 zoSC`3nXV*m;iM$6`VNA>XMb;vZVw6kEFKyvZY0(2kz#pSNq_=f_NW6Pmmp_>*R6gc zlC37q$8Z=J?oYWLKPt}w1e2&vcUPKmq>sM;0AcSA+pmaj{A+vyBt>BoGkl|Y8TIYg zHT?&8f8rL6_84sKrAAoMRd$hs#})kd_=`%^JPrF7I_U24-RttKVUYa$SmlWCovYWk zTKxCWzAJoQ_<4A-_-|dmvB1KGk)3(u03UD|>+4^W=J|@LijzNN;mjYf!o^!t`%bg* zEuG0#4U&6j-l}+;#5VdrhwgQ9epn+iH$8?=YW`C^DgOWk3jL)#GODubaOz7Q4%?W3 zWB&jGQavm5SN3E5vwk6d($imf7sMJ|RXd7>G%ZdM>2qY8Hn4$#C|T_Zo1y9 zadN7_VkqTvv@sv-<2mSg<2WDFukH2VZ-)N>4Sou1o-vjcOYs>?SjpO6;!l+ZG0{oM z>tDr<)|EH*n?)$g#z+LCNlGyV!EMZ))sxSvH4h$ z@{l;`!8tzSzhOV%n|fEpe+z1w-^5>qtu?l!6j;2=8pu{Q!}Vi>o}DX6QgT*8_#Myh zYQps|axK{L`3!ni>O(L&HTiG<00jB?h4J6Ua%%S98A`~ug$xq}^4XQT zjEo}!Gh7n9bZ1Ou&8i|XIRG~mT%_l{OTvcKDhiUdC*EGF}IkJpXXJjj!2a6 zKPrx-@x>a(xn-rV`a@uL_RW0z`$_zA(!LRX&t53_q4t%9^s6_PIUAsG2?YNDyNsX0 zg*`-}ZA}ex<2Qt~&lX4EC@BxfuFB0ahJ2&wBlcyp#PE z`RsnR_#ZRAr~1+C;-SkEh_tZ^*f06lX$6{?hdJW8i$U{a9Z!C>*RB)*c)+b@N>(Yg zlCj&Kdeu2C;!}`Le>$@*$N=K8Cb~SSZ>Kd9ea22!-Zw9t`&Ml7Mh9NKjZ=G%FcgnG zcg1At33Tu-_7UzmcCnNK${h?<*G^j}VlrA_O z_@{qn#xbxCD}Ttq!Q(&5oVM$;a2V`8s(F}>emyz?BNb2&)48daO@)q1gZN^)2;fBT zobyfyySe@&fzpm<1~AhXju&a~-;T92SpYGB53V!*c&%?O00l-zPM!X>D2y@4I6u~% zm>EXKHaLxU4_cU6A;PMTndY>1pl&`>j+Ck*@7uR}6JSzXD8?N}Uuuxq#$zL5jW*Qi#?tHs{yrPYW81p44+P zIhSHH6l9WvZ>>lnj19^MJx}9K^Hi|_aJ4#+tCbn{sT8fy5+D=q{L9m}YS2_Fc5+8! z+|^au!v`dK)u{1-lhAcFQI&}?HD}pwU9dk~dg8p&<6e$Cfp6w~DpMA7RS_N67-Cf}Jc&O2tjp7!GM-&)L9CFA4d z>@i-u;oCQ!&_{5;QvK@^_u=B)-Mo=ADJLM0dh1&m9Uq4EgE+`MbsfJ0n#b{_%<^gw zhvi7d2Tc8IPfzfkxn=}$5JHRt)A`p_d@&{PM7;p*=Rc(n$PPD7irxqWq9D!2N&f&m z)+Nu4lGg35rHrWu<;ces?G~B@7VEJ{C+I(~^sYa|eguP2kUTM*=Q#vZNDg`pV%t}7 zHsFubgNpRM86RS{{ma)L)yCU=J(?LKo-h~Gcdt^>?4-7gD-2_fovQf(w_|D)mQ?u% z(;~FuwR{gV86KR|V^s@-oQk-TC{Vlu*0f5*r+vtzx58j_?_AC1_}HDN9=Oj+?2NrJ zjy-E0?ls$#7|#Z=s}kb-9LC3)b`g=^BN?xhzB%{=O=l(gpg%$D^slYSD!?j^JNB+) z#r6^E+Dw+%-IXD6>x%JnOeAa4ac8HNVqF@EqwsgeR-f5-(!}7d8=&U6sP#fv?H~ik z<f_}$>6XMHr#@JC#B0P;ENYviZXSuS2TC!sw0cdzE``vWQ!oKM{{j9hC{Owx}~ zmv_uIbJUPBYW#Prw7Z^q`u%I25XB;ePN$(O`c=r{3aUCDqz*DY>%pA5p4=jijy+4| z8^#Y(zTGiaBDq4NZ_Ez^oOG^fKvc?b0Vf@XeLISBdBp8uwRj^Ped{+pZXAbM73c8| zLCyf@6*t>Zpak%G^y^&E5`^C8X!jVYBN8lxF&Q8QBd_I6){_)yok+MC-6uHd^rsuU zbs5e{?c4lokdjHGkgMnL$^5zLQY`a3?Z)z>pKSE2jF(c~H)E|bMdjoXgT_4t4Dqlh zfW0z5p!BXV-AK7b#ycLF{OLvWq(y&-08W3#r=1QEXHNNS94|pk*nhgU&PjbKAV11L z0~H_J8~fE?Scth9|JVI4lTllU5!8*W1`p*}GRmO(oc@*Ne-1op2EU@CEBwT9kN&-P zrgc(FwgK#V*U!#J(7{}m;$TNSbI?{xTreY?b;zjhCmlNc+~)?dt}ZYE9RcHt=QZR; zw3jFlmE_{N`^orVatBOy2A~&D=6v1y4^!`1*RzkA1~?-b#x&p25Q25?1m8Wb_Sykrdie@gUn={|IDV;6ZO*DE?h@t41|>woo67M4Ht%^RBWZS zYPNXQs#U}cTC0lItgS`u5qn1M+N)@lL~B*;+Ix$=_YARTVg{jKzTf=Jlbq+A>%OnL z8gnaU;7=ZbZh~|WUNCeddc+pVS7IanOWumE=e**PjaKT6G4twQt)I8a7*|!;`H*ld zJoBUaO*?LQM78ZLv$IEz?2g3hq!(^)cMGwq7utI_TBNZkk}|%fVp0WI zr#$dv+yRwyqi3V?F@`a0M|+|~C4XxP5UkjJtcRIxx0#_D#v<9nk>OY(+{ToiqFWTR znyBR_RZ{BOjR_P-;|GOicKazqYs-gUb^B%Uly{sDqSVt0Q_=PAV7?=LJe{wlkxk}C z757pSf9z9L`YH}f&nIO$&PehFf}gdY?OU++Qh$#!z?Ut0MPaDsM_GsM92d$j;&B-Q zWS zmAAfq+nlUzcy-IlCw8t^5ia#t3Wzc(SJT8H15p|3>)yp7bUZBVf~{f&2|<*U3PR3hRhPUOv(Vy$HG z;1aMlbWewl3>hgMHc>zBbw?Mfy76*53JvCCgX4xl7J+ z5SLXV-g|A4arxw-V4e3v_Lb{0{CEO87e9-9y2}~gmGw-Z{l*H&ifG|}j@qouq?7Gn zlx?HHg{p0{5{t^5k2=7fv58ZL>iY`#b!->-f-SWDy(($`9y5O?bgvsuUD`mqY02o$ z*Df>`1u`0 zww0AmSWNrZ#hQ#1-)$JIMI>>cMA`LOcifs5)w((enA5+j!}@}D;Z^(sVdn{z3`-WI zS89h}=fC&cGR$d2{#h(89Bj+fY}Jdt#(rOTGfkhB6affJ;*%jMIi=af$PN~|S+_JT2!vxIFZwZnX!>&$EG2WE@?tYZoTA?;Rm zTz5eM3H%-!lPf1u^vgzXULW70s;MAJzyY=Xk{c7h!|mI}Ee8G$Chd%@i~TXk{z7Am z1d{=+m7Dgm4Oa!nW&g%D_A@eIMpwpO&#>~5w5OU5MVdiZ7CJnq=S?OS3+pr{s-hg0y*^cw!#|-BFPZmGok`r}z;pPQd;;;0I zKE0%isV+|gI9X)aqf)387;jclCbbt1OlpLY{GWaM5sZ7mWa%@@PpxBrLKP7p#$Gw? zLjOI%7dzd)UVAEf)*g2deJzU3;+QAZlSf<#ZWhb6sKF6}zH38Gt30PzJ78o77X%Ma z`0Ed9+&8J1B^?>>1qR}qld}c#l8Cil$5CY2sA6ZG$s|=XjLUUJ2YTnrtnC&7Z1~=; zkgdibQOa(0VE~&pFg0uHK>K( zf)a1Id{tOYdcljLW!RD_HQ)XvD!?`-_u>FEhlx6*{(#i*3my*?`#{&Qpm>X`hd~k+ zJstqd++{q@+71fWn%K#FNqnOWo`U`p@(^PSCAT?c=lM+h2y<+aVGRBGJMcC3dwHPR zwAG-)*K?<>cVH?v|- z%cN6$Q8R5mt<3nMe0&Pvn93+ncC03wS3;%L9Pa*hq^TF#^p{!gdaDheVzz>lVtw9X zSJ!TZ^da`2QUXUz?<>dq{HE{)%2J!3-?;Kb;&jVb?R#CTe&AF{yDKu}2 z9={)5X(yVU*djl8k6o&|8b!1%zFcQdXf{Iq2&VAuq^>fx`=Y_NkiJY8n;UMUxy%PL59*1qx_S;h5wS$kBeiC#n) z&%#E8AIlf*jP~oIy!0Mh;;C|AAxmOu@UxE|MkOzQ1XNvjk!J{fU@ZHBJ8D3WWH{3u zPER?>53_BONhc|ET$I-YTLs6q5@4Cp?iNhg{Ll4MWo)4IM?#$Utzf{nK>4&yHd(at zhAY%Lga3u9i$C7Yd#cg1T00tg$Fib{X6||X>ew~64-#M>Wg`}N!mr!`;&Kz4A}~+T z|E5=(__j4&s&WoA*|l8i0-Xp9!~i4kJA}6Tw~1>(gUd^H37BOQI$jPVAO)ePtQQ?t z5cBYY0~@_IthD#?(|Z<}-bN%36HfxQ={>v@r~Kx@-Ewe6dBhJ-C~ws3>Eo|2Ii{u- zMLO0L+;TQ9ftj}+vFpHtLyXI`&EJ-Z8ewEMdXV{H@?IglycC+NF)uip1W7x76ihc` zQB~eOcdo{LH{!jpbo?$+K`ST#a%?dngrf~!6WiQ^F`M5iz+|}u0eZZ%inelosXX0_w8Spm| z#sUt}iWe3r4S^AZ@I24{wP9k+Wr5cRzh8-ah>lhCTi1|QZaq7%eLK@6i8sCfjmWW( z;m5{Rc3FmX#;G}nw_4QfoW-{C-+1CM7CkwQ^#a{-SyrIsI|M#3)>Ey_-%fCVMNUG{zltcVn=H-RCo=`87`8gXg(Wm!FSA)r-LJ7 zuhYhd4xkmFdS|c6&ybuXjUjDxIu|X_Gcsjsy=H2FW{N1Hz55vI^Jq3kc z){K?r8_;m*rcM&V)Q=ob%8MoW;mhNt9!ngp38Ip=Tr-Eg<@X+VSjgJ9N>?|2ClXA7 z^!VQoA2&@Jxe3__F{2Zn;S-bY_ma%GeVqz_9WD4@QkY2l1}3w67N_jImVGbCd`AG% zop%z%I`l(=aB7>82n|`KOZ;o)p>{#NP<)Y#W;iH9a%0%P zaHbqxYjE%y{^Q+k*4z`zL`ZyUXBu6zVB3K`nG`2yJURh>k4N|r zWqBi(S;gM&%ET_PPp%%|Uxe<{VIdep{iv?S@Y4J}_n<|`65bDYgF!Q3CF;uZX-ctf znmviiWs{^1e47bYY%1{0we~SilGjX`>!s~x5C-J-lt1BS;4?Ts*a=Q}2FI^ZI~yjz zwTNq76BV1o)3p2bqnA~tN2#vwI(_6rBnugVaPu00j4%#*JQF}4`zMKD5t~`@g83gn z>@rSlHU`@N#ADUUpEnHd#3tvkP|rhjE4CLf?HKgjy7%DhyvOXZV^-~f)p^MkO-`&p zpzWm8;oF}EkiKODxqk8-u%zK%pO zK3Y9Ml9izl>=AEC>UaiGvew%_3%TZ9h=VjaCJiCawP$CtZ-0EI`~KGt|2?C(nnO$a z>#g5{-+pHF5gLj{)r;Gg5FgmeLh1CYC$tCV%?WaosZe)gP43!wYt*+<+HJ@M<923A zrbA-$-J-Huqup*p{WU}*nZ$o7E{kR3qR6W8&B3vLPw2yHN%m5;Mt_%u@KDl?nBtrl zIqsw%X3CyY3`Lu7qhQEJ= zzoyaYr+43IsXNr(2tYX7;p^1W$>iq#Bj(0IlZFI071sj9zq^lDc)+yE@sN*9J~r8+>h_(Fkcbcay%JDD4CBh-*5#XhiCU z$^<#=8RJ%)U0`XJ?~VG82zq3f5}PLB6Ul;B?_&NY_cE^e72I>NS8;>v>oS_XrOkDO zdVPATI+1Bj2-@Q(Ep&fUiCBdmeAP#^fg*U=1zJr-t zS=F5(FGAdYR>9J)Y*{w`7O^|Nxn&NoN@M8fT%)T`fBva=YDX*!s<+vY?B3!gtmRiK zsHzNG@q3V*jK%C4b#^Kfg*8>m8m>)0MdgCcexU^4*^Z7(BL-yPon>67{EbJIaS7UVq(As{>cTSOCL>c10vZ_cysQaV~lPP&*;_J66l5c zha|wxWevI4R;ZBLrjV;yadpA*X5Rcdf^{Hf{+}|NB&$4fVza-@f7@GKc^>E*a zcA!_Gh1yAH*zNT(SV9#f4@*mgxRU_!rd8N{iS>bt`imHN58QM{zh}&bgQe(PTx;*G zg&ilbTs(~n_d#25Zc6Inal~MX^ubaKpkuUfrpEISBJfd6BZ3Tc!Rnamn3_aA6=uPH zHv?urTMcKYcBy%m|1Ln9(V5fr%AWTomnDv{|Ds&`S)tVQyBJUv^u3OI>Nq=FaEC^) zLnNlO9ZR?7*h^pecetoJ&@Zmg^KICYwM!t{*L2tLf*0Jv zq(h1VN-dG>C&-+YbNhMGI3@SjjM>_A9O+BR$!yp9>mCU@Pupr?I|9M;SDu}r-rL12A1dSGZbkV!{{ifR91SoT zUtGiwWz?M|#_`Jr*2bphm#zat`JwQYpaYNU?3^Tma<%b0DXgR-dSijIBwC>En}JtQ z>0=ZJO`I1p4l{~RBvoQ)2X&KER(8W*r7!prG_nv**%q$*XX4r|g0pZ}fyKHtEq zInqE!te1on2t=Qi%Vq0r>An5<^_wKohtvDL{+@k@=lhx>4}KIZ5OAbO6T&m0o0%d@F*~_&wut7mjWK|$Fq6&_B zt!WnhG-LkF8#+3L_<3zMct9())~}!Rt9Hp8j8scccH}$~a#?~?4b!<>xs67p)}lDW zl1HRZXRo*N)L6NB;bL(QVLt-cExIPYW+V;hzUq{+vc}hiZPal&BedptQVo99WgP5T zna16_he?sPyncxFE++ky#~TmT-%JF5!&k`W8^v=jOvn?mIP)-d?88stcy-$&l=GX_ zzw2+;{+6x%;DC(&IfXUj4IMKbuX^8Xx&!(asEN?(hjVvnFWd%VtU2#95CWw}MCHVm z*ruJ=Qx6r0R+~~k%kNV)AY?CdhLxXw73S*{2C#Z0NcC?|p0C$BuepWy)PZ^Xde`Md z628%WT%oR3>vJzo>4vFDdlJt6-p7q9U$FL>sVn4#B55KBt0=6!Mx@uP!w(#({e_fb zOd5MREt*BDt-=zUj#q2ENgr8O4|qo`#fY2M-3tg38}%^Du7#yXGX9eP zIMRe=<9UPs|@KCRyc-fur1>kE{psIyqoeHAA!XzZ2k${Rb zcZ*6Oq%wbp)3U4yh@TMV$kg{EH||jOdkDsT2<-u3==^E`_2k9m-a-}c&1B0 zzVvQZuWPip9qh{ApJk%#Q z4P9f{90Bl@bK*Z8olWSkI=0;Y3v}bG?H@(zKwRkg-IXRGpuLAfW=(50EpAf!H)44M z#dMc8(7{~N@gw;_k@4(0h<|T%-m24n-8Fh=uIG*gTWHcHbx}yJnP-H&kbE5`xs6+*P#`JiKxrYSL$ScF;Y?D ze#ZIS4Z&JvVToOzU7J1FN283fg?WSi{SYfzdPs44s75;T$9rlc1VoqR&#?E=xhS5l z)hHeNC?(C{uIowe{e=;c=-P0jUp7}6e8TQ|Y;6|!b{Hq>X!HNj$5B!3u@+R+ukuYIT^3x1*TFy=-`8}mGZLuL+Wv+*zn4Nhbe z!g?S_V_*-aF26Ym+0aW;GdsWk!ThL#-A^C=`kLjUTpyDdCb$kCYM~@&qkpeOZPmA< zxNm`&_qJuxmjvyN?p;@0Xs4y)^aFnNFijmX8GvZAL)y6rV7EXP_Faq7^QZ%64Ex0| z^lB{FA)9;1*lTlhdO8mB#5x7A1$x~oD*2T7xMRc*bs^asOxdixUdndURpIy`zrOPO zMy3|ihh8p$+$06m*f!mfG(&fg;{~4A3Dwj_$9B;eciraa{a_}qs@bY@oZ)?xb)Lj~ z<#Fk_UoTxKX#YCkz)xy&EA$;WT2qTTG^#&#D7N6yk%7h9b)4lkBRF1vvJgWb_H^$W z{Jrq+#!tmX@M@0uhNO@y~M%ugekz+w+4C*X`_VX&xE|-k9;3qY~7YX*%k|atif3w z*5}#f^}7ds!@UsKubV6{ZjlIwi&0>3hib5WFjjr7arz&i>b$8bnjSRVQyIUY&iEA9 zH`K7C${hT}H1TtrHKk8CxVkRvj@r@gX;hEozAJOlLR^ZfSSWKG;U;Q|syXvk|F#y4 z%r>XI{U$FG$cbKwcDAeYpZWPHo`MoCK@M6l`qVB(l2YQB+PeifaoC-D9azBlhi21V zRRa^;?NiqnpXwM_aA8LqP^Z6^&qoXl1PB8ikepuGxq}g=#1zuWJIe2{9YG$Y*n#5% z5802T_l|nkPRy8zu$H^&`Uwm_#_SSvUXT#vqsUJnwzkV#?@@FD5= z!u7z=rxYqKYx-$v<=`LS9oooe+OCUIOCnB3{du%gkTTNs%L>_)EVuN|<2Z)O1>*+M zR~;dI;kJpR3vJ{$3ycq9MqaWF-;+`9L!{)cPpj0wSY>-s?uAwjc`+K=_^Ao?yGHG> z`uO0=x!duXP4d#3QW^Bp5(pAUS7(NqoA(EV(%TA%`Y}l{o|hTwXS*509eu?vrm)j% z4~Q}zIPkKG{+DRKf4eDrgRwC6mANB}_&vv07>$!BAQn zEw%mk1I2Rt*C~Cp#+;_adkekjejOc5fE2GYx3Yc&WQ(T6fIZnSHqeEK%r0#tIDTi3 z`v*KDVEV%)=1ZxIUuk5$MC) z#aSyzXR=6keee*o1M=5%F5SrC6tY`1aX4uun`eDhR-*7nOJ1@Q7Z zOx{-DzID&kq(bUd)q|E%PKo@rNH$uOuhk5FkUnFxKB>;JRjZNmCTX^y$+ zt)d;WT-#sI&E4PUkBS1M16Zow@C96yL(bf}X%VvLx0Sig0puVYHaHz5NOE5$$vYJ} zwIXtZMuu)O)9dk5Pilf0zKAZ}s?uYWEp5Ko#-i(C4crnKnw(>W;Y_R!W&b5bDv*QsPYS&1)CFO9hQtw09*>@m|E{pkoik7_`+UbKU|GD2r3v{(m-cc<%^ialtyDwp#| zEwY_gJz5A%u70iX421JH9Ng|{gv+bTo`GVM-n&f7dF>mEC$th=mkL8pPZTTjSgA40CJG^qdP8P0_vJso|u5y}8^K@k$S%wGJ# z%Gj^7imnk^wvq!>6#oGTEn-`NGc}3f;0KWrZbKEM)EV_KVn4to7m^IUr!sWD<{7Lf zEzw3?TByqPM$&6N-Dr`6@RSX4HQTdVb=l*4zAO(~Fk9uzvduD_bvGmZNGpT^1gVwr z4V@M77yp%VA(e3#%L;O+lHqf?Y1l-3-rJ*oBjdpgJV;=ejW$?*Zm_v|J~(?S~6yGixZGAear9? zJ*$pQ%UQO6yz&oFIn-+MWsV=@@`o`jF45sc3XFuC6JUL>GoqmkqvCBpsGK>Q6~8u+ z!?~J+2oM7}t3vt0mF7uMK)t8$fIH4|W8fcfTaHBk=%~CMHOwD?ROGEz~U%>@= zDh$B0y3+En7mn6w`*LmZt(6wGu;s_Od;t-D&get3s1C%sL5|IxQJS_0A5sBxiKcWr z!7UMr%G<%XVov2G;7Cs5TaV1!IrQ`VHP={+%DSjP8^_kso)xB)_fHz%MUz>zZHGS0G)_A#95{e0f4?g8NsGSF0WcCP z<%CriQ-qu(sVEXREDi^#p`CB*zBDV_zPR=u3Du>ID`57%dmYxdVY`KIVK0E!1%EkD z{IW`SP;=u*@VwYDFF&$au+hcH#z;~%j-HFdw%zGqIRcq%E_ow^okXTbE)+)HNe*NR z9;6=$Jg*^FFRXm%#A!45R4QHsp84j99JQiFkT&!Al904_BUrM>2L7%W)ZzqH4Ae|q zyNs1}F4KYwcX%?~be#Yi|+i7-#wz6M4dox5}~E##rUG3_?B1|Xqn z*Cy+UbMn+I!QF#M_Sis?b>9r;pOfMmpFSk_(a3j-j6F9@kh||kS$MF2qZG(BCFxt$ zQ73tAKk!;-eu>K0ZZlltaayms(>?GPGTfp_AOE=4AMopT2pgNa4h&Y9;!BP!4pd5f zH&N|aUwT|UecBGwk7m*fywPw|+g;j7n4ZFVwBJ36QZ=l9{+B)dRqziWBciR4T`;Hv zjkxeb17mTzx1qDc59+HEwz#I9*_cZIbJKXjSI^fXNl|=H3|4bSRdqwVH#_4Rgp4-^ zW&(+fcqtx>#YMOqCdYkNl@qg|ucRxuo!rlj?$rJJLv>5JJgnvmMs@~n=LYvu;IDR< zxF8Hm44i@fMAoMJZk~Ml@^gnE5VJ%4f7G{cIH(~24a6Hq4ZpeIqy&fSnVWasJ1s<| z0EZ;4vaBs<-WVFE!-MI{n(~*7`wpvRD@7I;U77axZ~5eFzQk6knj}2-?|?I7y=0rB zJ(KynK)36>w)&pED|nI7C?xr8e`jXFyZLu*l@?D(KT%_}#93blBi@>m4TZhO0+BAc zAK{L5pO^fsJR3wB`nI`}ugK!@*_f#7a9WN0k#X7V4hlu{D9%UP5A|7JxJ_l&j1Dea zDUX-W!;L2eHJVDMeEmwDh*o5bt;JFFrlXCj#)4EicR1h7Xt~F0TkwFkxwB~*{g-P_KVhic^pa5Qf&XikRLW zci@=}Gm|U-pyi%oA>9`yf1|S8+jK@0q|M~3e}H)(gINJdfc}t^f>gh59AwPkP1}8( zk@IHL{J_v>H7*4fukHH*D9~uj>jG|r?Sy$%ikqy%w+eFVvKzL*1d-V?{``a$UdBP7 z0C1=t=jM?N^H?l(7+xD(W?Pe=WO~EekoxO_iObCc!CGn1R(14&?C;M{2KOu6fN~*n z!jQP>-b9ZA#&10@3}UrUT<#B*y!84|k4f0B-yON{<$Y0}8h&3I;D1C23!unCx`D)v zC%PAVWxHk6nBQ-(Wnn@giI}oK3&e3QOZP0TV#jWIt?+2Lb5h&LGs(Ui?TxPT9w;H z-afG8&3icl+2nJnv(hxe7_ah5?ucfiMf%l@EL&F>>9E_ZVIJVQI#FK4-BjS#&r|2>7BRl zkC3vRkG&*2rmpzUj{s`wH4?zyoAvvrQ8q(rFX#fC&bRU4*r|!C3tyb?S2h5V+BAA# z28vnw>?TSwCvwho`Nw6^>OG2Cow za?TDd;L_&Q-LhAZ0RQs0)5hYc|}4)p#&;!ox4CUhIBq{PgW({89v4(8K{F z50mrH3h7ic-KZBRO*VR~ce(`|fz%j6gasOo`!tKQ@DREd?R#Z{31J|A95zQX9Zc)E zLmj^ID5G~pc3hU%Mdj9bi{JC3!c{&G3#wMeyF3lbG#6CXZDwl8J;?OBV%uJpa5m9G zd-MAH&3&BEg#44hcg>Hps{ZUqsJ@FmxS_Y=a{dx-(kSvFBvIS{Rz5=fbwpy9!}LXc z;`bZowYCR}kag$aj)heFzI1x;M&^|sFTvWA?uba?E`q5zde%O`d3moZ_8CvYk*o~{ zaYvK-s5W|ypQQR%RfS)sGWSyTcbWP*hE`Gk$G7R&AM2VAJFY3qyQ%3djCUu@7NXmy zJgYo@D?i0Voj_GBRTSlJ3{RynJl*n7Fo@`L?T6;0+`|_|KHS}@Bl5P~f0^2M)Bw)x zo^BvICP6lbtSy|jnM$1fuhq|iau=&K#yjKpG&d)nFVPQ55w0dGjv4L(52fXVJ?|@U{&YGZ<*GGcCL)Iw9Ue1@UoC>PsbKUqD&254J; z2exr|G@P+n8$(YWUFl2MlR>O0ckWvEikT~_;ef?UN#4l{4~9VJa3t6=7$_4Q29p`` z?MXQkvsV6Z>4*_st(;Q!!@ELQcPqPPO2DDMw2mspTb>F!*Zu z%8EJmoA!{gn48ucgB!LC8x%A5d~jZ`i`6$T%ExO;sNbAV{>o(DnRHrlMt!wAnXjw7 zWk~F(V~`x%xqC5O=4;#iII^a|jPV=dc}m68s=VKe#;zh!WJM8#4RZfiftxoovC%)&F~|D z7@%(;Ad_Wnc=lX3NvBXnY;Sb1cuVK&k`~X}Xtx=EFB`qtn?7=tChLAC16FsDgciBt zN;Y{k&ShM1pz6N|LKJwynXpwRWTB1IvU%!7i-3kJC&$;+Z%dyI$54RvKXwag`+Kp@ z9v;HBPON3>{g-k<`>VNZ`qq}~m*AY$c@-J(0>k=W2XdEzJ95tyrnf1bMkn$g>w5tp zyqB&N8dBHkEY!0ifl)mq#4x;d{EaZ zV&nX~pAJR}CK2q<_?li?9rJ>H%EX5K%J1vXTx3)2U1duu>YBjGmemC&hJ*ZjG7UZ& zxls>!jDm^>3wvjv{vtF&fLi90vr@{BgEtb_WBBd6 zGjx$cg2wW8 z=FDbfVQHTfuS;ny$s&*j;<= z(4r7q_pLMSwbXNVWG-vqsxH>#!pkj^lRa`MP-{5%2G^SlX`9byj}YRyG~ztb?YSeF zZkGGg?@apjReb-4gxsus!Uc^SnAL)VbV8o9#w|GJ=)Xg4TS=R}s#*SRBqqLoiG-b@^|2|3L zQg?a?KxTa4009eBp^lijyc*kUBlBikG$)4tLK%(dF4gE>$UlxfIu|RnLk-f``8<@h zhfG(o#0{`KpUiU8CT=}ynQ=ZFj_1E`L`{7pCuZLB8|$Dc)ZW$mI5PV-vXyJ5C*fSf>!eAGNe3z)NzZPYFFxl3}nGW}J zS;DS%Gta3bp$Ztgsr*mx3OeN08?%Jd2^!SozjqA#@hs$r0T3r4^9>`?AqKMCKAx9s z|4n78Xas<%M_5&$XA@6(fpto9dtU>XrVWWAdchK6-jzPKy0 zVgZ{fGMHF(#WJjc?%efY6rF3(hRtV>=bq}AX!qTyJM}^ENh(&!1k-{a-$4R>a#z37M4sR1nXJzknrEg>-9E@KzxuizW@7bE5ql%Yg7*m zBV6Ul?mDY@qF$StJJjtwUSE4Uz-7IuqWZ>*u+-b4x~><$ynlnW%6Eh@XPGKW;!DKi zXg(_vZI_#`w=uSIYo(C1x70iZ{ znmmJt7r)316nv7hF0$On zQFDad=^;j%LPA|dn@o*aQ)Mj@?*nf74{cqZAr=aS(wfrM2BEQS;LoxMJ zrVZ{uywV|zi@ot`AqXTspS~Gv+^tGYoa!=IdCKC``{IP6pw`u#_A9T-p)&uxx49as zT6@6+ig@Ij`~&1-#hiTHYJGxBK2iuSeHp;)k(5uv$)Ll*Rdu2N)sNT6@olb5`=&d+ zN&qn_o2KBeNiC9U0xCqQ7hTBu%c%-q%A z`K~o^52b@Em16!&a=%Xo83YR?b75A2zc?EDH7CuNRjif=rx-Re0vM``Ug0KlbCB-RW|5*(_~%P zY|tQdNAscM(5}@wGMt4Tx-PcTv1IX(nr&SlahY1kv?ufUs$U6lK=#M>P`rubZMZf5 z%`ZZuQq*IAqT)rivTJGjIw#`yK6a)e$^YywXpi!tfk4q)DUQUK3z@ed)~nyiwVRb$ zXT)&M^tcOGhrE^URmG)yY6x)J(?~%1z2YNFk(qQUsT~m=nmQfCJ&|)~9oXQDXMMc71k?6z{V<(hwh-gvbif^+VATKJEOyT_ry)B~jLqc2~}w7N*Mg7NDO zu{-pUljR-VG>GG20`S8m&M~#Q&O^+5G-tiBs7lI7nml#O%16$xXt>XI32Jchf7sUh z;x)D0^-Q(F%TGcg}x7IRq(E_&-k9r+ng@lRBdEhkE&glJSwSB@ctUw-Ts? z>A!Pi

=ncv}y`wn6J+J*xo-Ve!A2T7PrCtEBN$wsGmBi2{kay4>)4wRJ53%QYU! zj2+Rt@+Y&93XWwgSl2uktd0qD)pk(W`w`-T{lo4Eu%>K7E&O6g{)4YKZ7XHweCax} z7>Y}reNoI;#sW)=zWA&?jCYUm2wkeE%gGfp$7Y!PSVz+Atl-lL)%;J?1J0gSpiWJ) zY^93F6!xoqcEfI;`N#E4jXmM4*lJ*oSK{{`WeJ!KDl%@%h;IUTpaR<=jNx z%al^mwrk*sgX=7k`^Tem%24 z3zdgSF>Up$BsXo=YfNHi-h-!$X{ZmZs&65_TRea`<-=M` z@0`oS{tQXD`xeC-^P_c()=#*sH_E3Ke0_E-v3eKu51@V5;;8IMm~+~S?%O{`>}uc8 z!P~aq^?lh^{WozT6eG`&sP{Jwu$(puu;r;Q?>JsSA%~|tG)nEqAEk5Ri8#qxDX_Nj z9o_a1+FSWMm>>;8n@k@H^lks2NC$CT3gGXoDvQ}fE6jM+p>~PJZ=svlc5u##u zcLW4R%^tJQ52E~96Q1QKM{`)yx(Ca5HV>Q~BrFM<*p1ExG^G@}ZJ^k1{W~&`9Ud}0 z=|i61dBx^AR_@i33ReG!rLd|6XH$HV`Ne4m-lp5u(n6FI`ItYzjI^u;{Ho>VR^|Ab zWTQcdk4yb|5ggli8B^Wosp+8*!>yyC?fC4e0+2~}BnV^iWVi7pg<1?`wVrOj!nXj? z`S?*|`mcfHSNZ)`)c|6TQCH&&(fYz-*|=Uf{}{IIj!YF(hurS82s_SW%Bhzy)HGi(Ig@XJqT8aA!qa z?O|#4=Y50|#vz1Ta6sWbz1bFt+n z=&~GfIHkq%+;S~lnScv-HQaSYk5;K~k>HNL?>KHYpWEB7BCfRZF6>SgYnF$NHJv;Z zEUDh*d^`TaCml0DW09sU>>Mb9g2<<>x6!s)Qip&a>8Y=qQTRICi6_6Qeb_gkP6!-K z5-pn$+wtfL<^q$pA&Y`*sXLZc$XmeO5Nzi3qmm>?x7dgj`91Eq+#J_S2b1uKVPr*EJS?vC7p3Xb#?-a4WmJ#;QR9WTV@O# zM-#Tzv$;{VvX?%=7dmq?>cV3CC$t@ZaiNJb6j~F)@+>3pXfEUXWnXqgV|Gr=OV*w| z$qc2rXT79}Lv~csR<>Gl9&4GwI0o&t;KUc87ZwkCkG8LJoX_<_us zx^CXj{{tjn)0Ewf8cXD2s7@|8>6X$%pI!D;d3zJ47&7sIr~D0|xi|8?&& z%F$hTDfA;w=(gg(70T;qT-a4kBQq%X$65J914`xUvufWJ<3^GwfmHe57m15v>p_+5 zcJ*OzS%S+WAa|F8)$q}kR*&#gCjHK$5eeJvKnU0--Yu?Ljy5>_j$@M3v#J61f=};{ z%x4)kDO0P3N^v1FoZ^F6^&#nS2u+3QqRQfDfV&=H3Nb;s5_TXDK0d&0+`-?&Lui4w20)M24?eF5?_0v*^w)%O^@7 zvy=FazKJzP-wyd0jEvGN0v%s1nlZY+l^PQu$p^Lx*4T~$h^M0M7DmzH1ato=t!b+t+Hsw5=-5r3pR)!Zk zw@t3A^s~!;l5gF{i-Z5i(OCyH`Mqs?2m(qeO2?28C8SGYgtUl&(jhHQx?yaDgfu9i zqzFiZ(%p?T(!yZCq&ITFw(tA=-v9U4bI#7W&wXFl=Q6*F-RlD1IUPvuF8z(>qN}re zJ^0+7r6S~cK+WGxSAVsie{POuq~!A4W3O6EOUC9xIH8$=_syqr8vyU6CvM`i2=OLf z?9UJ5P-auKi{_AmKSjNl$y&|!*ZPj`fF{?b6BCeqN@BrYe+YyNbKhgkz4|TFT$Y;X zwL;ml&M8QXm8B+S3Tms6MuHD~`tIkZADu0rIa zh&UvXivL;vts)7Yh=?j(z{l7`dOtx2EV6$ZeX@^+q@b&%a@>)6CVB_~n%&#jt!8UY zm;>UfMk%k{Jh6724Sg-$_?BT9yvN;rO2JcaKZZm^KV2Y~?NNFeY3zbu9OVU?6t7LSQJ$+*4 z$bzSbh^_%Wi|C_~zvf^6bc2}Qpk~5FJrijZJ8oHdWWMfu&tr5V>)6f1vkb8``Pa8b zx_RFtH{-iq;g8pchwsj)RxNpxg{4#&FRi#GYo=_ev|?%8H`=}y;^cW-Ip zL%ndWwkG?pf67Ng1AMX~KebHU zBOPl@O0yt?!;5pFaZQ-{nD@Ng!DdZwm`l1L)yrR8!p>0I{EU zk#g+uC^_UcTY?Jm{~^SNOST$QS2u;qRNiN^pP!dMvNn_GB}w%ptfDwOn*03?8iq2= zz#7Cc_&vluywUW&L&DM{i;3h!j}mb@_V`mE?D;jJNx`0F`gD!VZyLWH z>GI*R#NJ%%+QPg>)I_g2I_3$BG3v29NS0QHHt;G}DGi%9P#Lr~h^V`{Qhwk>bUj(K912ni z??QAdDKWe=U+aO~U$a{JYtdUR+Bj3MWo*Xy=aZl)Wg@e7-dC&pp+Sj)rxg|kKj7*a z@QXWX|5Fhx>)*q(<22zgdF<`0fNBO;8@*Y2hg{Pi@|32B3@xOoFQW{`;3{gc)OVfs zDYUSf>zGq6-xjZeMo|*C6H6V9=qx)mTOZcOGeI@jDtvjj(H<$s?XiBzIC*hY_GhdcH??YV(j4M*RbzL3JTtC zk#}ba&{*53Y6R3p;5E%3|1#Y(iV0P!cezu&coG^vHV!XLLJYj1JOf}DS5Z? z2HrwTipR>S^d2KBXhIQWy3M8^@zcMndQrY775@S|)jDTe2M`d2m4rqmK1Ieexsm$V z>4Zw8caQl9$y@0Opx7*nchLK0n1Y_Uyqfv2Hz7}XkA1RWZpun;3LsU8C-ujgga3h+ zbk{p0i2}I6ZmgxHN`*_qnsdFDZ3^j6+}uR?YHm#?WlG?CwpiAlZ}wQHnn7%~{D2?DXEM@`^-HsZX?EH9hsg*$&w4rnT? zZe}CyD%IlxG4{ylk8lXgcpA>E&ivNhksHO%&|vN4od}{D2+?971eoFMb*5lEP~_jI zd=~N+KJ|&>qTe4)J_271F4O+YUhv4l5cm=VUM<0m*gK3~;JIA9XDaLp2HQ-$1zBz;95^(LZeMrt=!u2Wr zQ1B!RIX^I}+j{dSmSf3c_=blA83pNDF=5ao*aQ?gY7>mVTg@>k-IlrG*>9zfM$h)?ZpXe+rFY_X4v3Ib86}#3y zIOR)q{Z?}CE%&wV$lAllKyHwpBoKr6;uRUWr-@?@+^J1;# z>Kk#6H@esN?!-P^-XeTg4%7Y4&hQZt-Rg_8Q=dJiP;*-P!FF7+yy?Ij!oG@`cK6{Fuk< zA_~Xj+#1EnWk+Zh4uF@7tOmN^mrukd2$HP_&!s+O_ zHiZ|8QxT=Y`cnZSQHVOMXHSpu;WbY$oRT=+(ix{97^u|DF5Qq^=mCU!3ZR^+?*x5H z1-!%QcpXBflsnb0ENxqu>LI7f-)>p1&|Bcjkj26Pw0i3ww>Bv^69Rdl>$ZLi6%T{# zVPH2!r<*|EuWh}}n?h>TzOuVduTIPzPj`m}Quij0HhvpZ+1p358BNA!tOnP#Sff9fy6OuCag(G?(fx4V4Z33KV9s1 zKMrg>n)iH>bz%_&-lm(r-m&a>##rZwLN zE^sj0S^98}3D*@(l8#4!tZ+i9@9hSP9x>1?<-+<^pj|v9CB?PbQ-`wrBni2lsBslBi^SOrn zy`&9*iV_^($ffV!`r~NT|LDZUsl%M-ppE284YS7TI4hp{+RB_bqOkii8$P0M#+$ba z--P$&)$w++!r2~1SFCBfZqTsUhwp6g{7wgX-rvim^{j6nY!4~kfZnUXP21cxty_vO zcY6@#@5Wnl*)&eBhY;(mLH9xK;1zLy*9jKAH8-yvN6htEu50?`Z~DIX`=^-?nm+`- zto|}7aPihg_m$J#4j7*ULZO`I?^>#UE4%x!r-Gc>PY!fZJynD6z4@{G33tE7+1n=; zKJITjQ}BSno~rMX>HcUBb>eqZ_Hp=F#I=>Uer~I1{vxaX|g4SZ7Ij#gCk@o-P`kND61-2 z)FGXm3iEaEJTOQ$uN;cj_ZChgTi&@mB@K3q2dg@B+)kp zWZx|LB>>`N&B&j;DVlm+KFkM~^MEFd`XR-}MPwlb73VK#lI=EVEx*cytzegj#s|_^ z9i6ws$sYbbqD@5qTh*~_S`yDv+tK)bFN%e--%z95rJvh- zn$L*_Ty1AQF!rMa=65=t0wlKsOTz3=sExL5d8_k9pZ)!Eby1qX(tKM~Eb(2{!MHyi zvEI}ueSloiTmA417+*BPg63#u>b$lPV4W3+H$dFXm|gf7M>_EhxzX~VS;TI|Ye3!y z4K}Z<$t_d*vJ3qZyBRXAtQhoq^JL^u*$Y8!@-FQ+O=rEMmO?OKhpX0cW2V24;!vvp zBK#wzk-hr4^J-;L#n|o;Cc4oRkL~76(USQwP24eHVlz!S6m0`T7NwOh%roEs$mDSgf7(J)}KKRHv3o{=ic!kNl0gz>J% z4i7wy*o&v;eCPCJ*`9~je!+Q<=&kxJ%-o40SDF1fXx8uxH_biUM2%oha=JZT&HO^? zyPLO8evw6limj10?wL&=*#)2pxw55&+I&3@$qOuiMfX^&-?XvTIFwdd4mfW1rVS3| z1PijopK^2x2Iu_;vf|Grek3ATn-!#q-XK!@#7@Gy=;21^ zxT1S^$C?Gj#xPr1xFjRS!R&K^7hE`#4>g&YjXlY+dtUIUtNUt`6)UJzJoysBjc{3u zytBLHb7*(M5=KF&)*tD70;8*b*GUJnlnhSyd6m{yqs{eX-xG*dW+2?c8)NpF(!DN! z9oZcDuwUHhWF$iH4_b(Sf(d+-pT)XgtN?sY!1b%pzNu&9d%|;yMvC-#R+_5Z`4q_G zwtr?BtF(nFF&R_Hy}>d9}6FnJkZ$;PK4y4ZGz#`d3Ea5`^y+< z1Y4cm#@V^WV%JLGr_mlk-=2t3@bmfX9qsnJ|JJeAJLe5~E`^Ide65+XVMKmMgF%}% zWk@942&h0`Lf(!-$OCREG2q0{<$P(}m4f@$`=p299y(&Z%}AdvbZ#0>9&3ZD?uR5k z{hSF1TSA=n4Cv9W)tMVpccY~Fe%f+QOAvp`d#NZ!e_W2Kt4^PjtvuFt43|<48G6~Q zfOP&=?M(OKv%PmzyPK1Q5iN2ow4@*>G*pp^3~Om!E*bZJp8m#=29>iXTM~6|eEjBh zkcoRWA$4Q%2@hDDdb9D@E_BSjh`!`_#qs0XaxsNsu!%d59NKt^=TqAsmgqy%pQI!| z#r-an0MxJb*6647zX?DrTY*wN{1UWflV z>8^wEcZUW-ei`o{J)sXcA3?c{i+k=Oo|bsTGf1Q?7fUWs8Vh-N1X6U?%c$sTc=y1n z)&Awtj&8K-X)F)qvYSNdy4I?RT1A3Mx#+v@#)p&3+z2*VvA#j5@)az9(~|p-|2=7= z$X)*Uc!x)*Vp+Lea_G{3AiE?Wx2P4T{C&-Mx>CWw6?Sv1p$?mL`kM42MerwGi$Z+q zNFzmlmYlV;+OpQpw51W=}6wilawg!S8J~MFk#JSO#46s8t=^s8!YYl|ZtuZv?U59aNxm&7;?*J46PHYHnO%@m_-)r%dp zKus8-)L5uiB3x#v{t#6c9i=?vG4ikX5fWcfL1NT>qccOFCLnHOAP1|e9~HDOU+qIs z9+*5d(W;W6%jHREcB8W2@=_6C%e=7R#J|OT#C#gKN{S>teESmt)%wWQULR;@RzqUO zDSo@P1jMxalv5O%_HxTnm#fb(iPw1W^aS_}%LP45&O?7HoI<_6<(u$gv`K-BqB58~ z?AipzgQd9In|KgKLa(8Gl}o#-7&Lz@v7Wa?ICRvN;{hC>k8UpxlY-o2cM(@-yR7^N zM#TxgEnGGq8OzG?e;V$xe3MInzU8Flp^J%~V+GGYOv4JUN43gXaOljb4uWnmL0&Xp zRP6^qdzZ2wJ@5$_*S7~8`#MB@Nt-3V=~MXeOY!B`Lra>nAb+{;?hQag5qUt=Ax*y&g(ggG+rtgO*38n!-Y`2itZ7nGE-@hWZ^1*%+bWhxA3x8a z82?CVyEB^vGuh@32T%qRF{}pH!UI)&YEe{ABYGV+WjH+7@~fTefMtn)H?>R|SzmE< z0mJeLkh8xj-F$OBofarO9_#aMzGXk;ZUubIMdIUgSbXTdxN0K)jJx>^XM$?KIj6^C z*b-(GYM=az-B&=HEC_2^91TH!Z<(=(kve!d=l;blK-&z&;gQrmF&hHiU89CiuTkUe zZ{OE-fo-kahh%VZbX%h3kh2x)Bd>O6a848H)g~M4(tGw5e7R-iDGi5H9JTwq_v7aw z@Fh?pbA9LS8!9|wwV!)da{pZ#0*Gd+`ne7^XsY;~DOy}F^SXe)9 zs3-pZHH#;$T(%x&s3CMLp)L%0cl%Ab-ZL3Cz4;r+m84(qOBb3Bm@Ujgk!PTC5rxyS zz!%NeO4`(hlG0^xI}Z)Y!TBU&y{$q^oMMGYOhAk7s%ALgYQy~U!7yHHOWfRS)AU%< zBojZhCOn;S#1b=XA4m6{-!qqdVetDG(ixn`lV3GPytDT9IHdSF{Zb2lVpCpo2pON> z&3rW*l$MmJ6mZ6})kb^c(qE?*|IO#-04idJmjD&`DkUFWTp5jh>NQ=O_XCGoA1{5R z*>idp1nmq6?i0HV> z*J|I%;`lG%qDta5=E+xodr#LNe|OC-{{zW}tKWL6*_rHDnsAbr1!&?KqR)+VhR#c{ zKUk~wFAgZyUq_`BKFqvu4SryggXUJ<56a8pMLf{<#5C%Bag~0lz2=n=eZqjv4x#{l zoK^ayO$PP$2q4^Zw2w&Ih$5ZGHLn*&=_J@O>b^^weMd`4y2%{{1xxRYvCpgu8$BQH z-%agw3S{>163jmXD(7Ge0Q6iWJ44P?giSVHlM>a4RRx-4q5#VK9#s+)VOp=W9kXzs-_tUX`jEJ zd87uqk&8`0MmjWc8Q8ckqAaHUXXg~#i@BpGj_JA=$#(@VzbrBB3@Xyqd-bvzXI)IZ zh@#EqRytA}tFLClx%b_w7qWexcAmf8W+6Z!CZ7?H4yb(5HH*W!EB&f;2>$%8jOKQf8m z+BBZ9tP&*c?)E7cq>(N7X!-sn39tB@)INvDa{u(DuAFJqGN1U>PmBbVm49geoU5J{Dcx2NTBO6Ij zWIAS9uJ(xR7sqO)x-egc2W!i?F310T?t6;HUYx(esb6d3!VmX0*7k|>jPqB#32#r9 zg$z@+zqdZawlr+{b_;0oP{dyQ6205NTkH1zoJ9^OZ|yqT2`PB)RW3jVsOAIle*?Q@hb^my%T2IX9fkyX&lJm+pTWrT zQqYd~JLrAQrbby!KR(u=4-B`Z{4RnnFLTYs_`S@E!{F?gTJrc92h^& zmBZh2dA+n4WDCg^y^jcz_xXD?p9|eMq7865GR8XQ#HSn*C;!~FQPfUHI+sq6o*+#y zMei6MJ28|Qr>$fzqyGbehzBDp@Y35J7CaZaT`dkvB4KTib&HY)#q_WDYeg-qww3i! zfR=BbwP+yaT2M3J^w|Z|ssvU@jJxd6o*@SMoq>t(qk}rYV^$^#4L0)>mZn;i0QKh~Pc}6tZ9sK_ zf(W3j026BPq$MGrdX*FazzhC6RWHLz0I!GI_l`jH#TO2FyH5T8K*-J|=kEVNxObJ{ z-cHbIsj#r5-c8nXuSl|albSnRiIL1kev8%^Ry@O8+&7V6D*CQSYIR`!gYEky{=ju+x9Td?R`{hSzA)RXu;bO)P<4r<4T}|S*?9J>^^3Voa4FmSFG5|-z5csT z;Z0Q^5B!oI80i!kunK4NXFk%c6aDCcv7CZZS=B8M|k*D8(f};(V6%FarimcA-fw>d=POh z-5)bJ%yyXb`AQ-ZxEE`!u~>iNZ840^Iwa;uvhz;XFKDsSa$L#5A_^77^~5YqpDZ+h zGi@I4I(N3VaDA?>1;2;$+Uv_$QZPQBGBbT5hy4xqmF! z0LOgojAd>vRo7iu-&mTaDzm6mNd5B#(tzG?uYx&tK-l1nG5|ZMBFq;mX)ji1_@>H3 zmPf&RNU^yZXj(DiS+Fuu52PDeEhin2TiPI>E-o*N#vo!}2MFdyNQ3DjvqY%yd|2s^ zB`yt~LU+}nzW2(?=vp+6EU}5S&{iz}{v}3a@NQPt7%RDWuDQr(c7p7c$$H(aG-R$S zP<bS8iz9GIQ4Ym07%+Gq0@y0bdxA0&6zJBopkv146zP;`z6hO8e@`x?g9DN? zM-Y`1@gJzMaZrzGpal`t!T%3qH5}+qQ>$4l$Q7^4r99f4xTPGp(=|j<cS!hVqg+K)ybpd73?2s@bmb?M3gB?$KdYJOt;SR9?7vMR#oV?@9!Wo^n)() zma;bDFV>h8G&iW~B}UP@#}^=apjUbWW0J@_f9m_kjpr@c+d-Oy83mA2-=(_lLbWYa zPw(zNWsG`%7#jG8)`EwJ<0NUk^C{#lhsgmq4~bc-OsbvcZ;}^U7n{z2%v7XJZJmz6 z(kj4hN$;djMP3`k+4lcbf;PM)P{ao>;4N_vHu4hT+_xyAPakbI7(KppN_+KHCtSQ= zdogjl=F_1o6by{2YQg)>hz-Po%=$#M>u2)1$%BP&R{4b~{$wx-WK&H$!5Ww+o!I_$3|CC{S$ebX9w2oLBq|D~R6r zihNCq)AvjcoOlsH^hKub7G=n7^1IM5GRu`?eZJ1KOR?w?UQp4)A!X%6P6%^x! zHc+>WqeUbV_F?nb5ss(5sG|gQtn%U2*zzXonn3ZQpeSIA_-&hC+B4cKdeqQE`(WnM zuF_>*44T4L!YqCqQh`43BrDhuYlMohnl)7Q^?f70}~gDtP%{Y(BBKHTtn=YbDp=TiD#I*>a+tL%q=23F6&festoo4{5|s{0vV z3^`ttMd6_*C+mn_EJ}pM9EW(>0yTv-JAFn4+cB&tqjLs9PNjIm`Wd`T*$3Y=?vX;L z*UR0qD+|n|*||*|fz|G$eYv9ol^L=ySNZeCw4@PSWB222_KMRa4_1Za_<;d3Or@zKFDW?=c;4=3^C z?>p}*s<*yAk-r?>EFU=nz@+QMg1y}S> zmcbfh8=AR}+T?IUFIw5nTt#R(&f6P}*TwXYu%lkrO;k~r&n*9dj=`r2%0JNO`^g$4 z;s&5)IC~h|25pRR&8Tb1;x7~kT*n1;Fck#^4)W{xO9?ahCt+(nbA8!4aT7?v>C`3F zZ;yGe691qfx1IHI&kh2|4fNOROp1BG?0W9Rp3n}zkE)|qVdUq`=~xk%gZ#hourVamm1(>n+1Y!k@SHjR^uT0E zUDicIY%(_KH(jdS!GECn;-ZgRvyrwQPl>9Pj|5iD!20H4y3G$lyEg5LRk++l^?{Dz zT%m5lM>7xw7ZMKOS}EgJ07Be14m}@U*G*bQ?FuV3k_dKJ;0XQxi8r79j$q14Q0$EQ zdup$z!A`ZQj`4tRxhn31P3r^@c_a0g%|}$SAi*y@*n1pd?y=LztQeBuEQKV!y#O9B z&@JYduO)^EBq!L7$RWCdXIJeGCV*rk#=KEx_Nyth1oe}^T}^Y>6`BGs%3*w|(xic3 zBSL4G%KrhNR_XK-m^RnrhdIwB-;0Z+X{M!{E4bE_HOMoREwZ@JGU}Z8N7C5f(V)Vy z_dMnsC0T37(R2IQpHX(rT&N;z$^vFmDUs1oO%Qk<|L8`Ug*>dkiKA>}`34dml^wLz za&P`>w)-bsS@A@Q}ty&gbH*kpAw;brbT;eO8fEm!cIzklxTJ9D4--emcCbW%U~7FC3hy68#@-m0Vi zcfOPBINW$Qy+$oy3K^D5%uUO^A6lloGZh4&(Ov^{nS?s>nW`jGIbPD4HK{G}g6atp zHhs(ULGv0mp4SgW9<9Hwp_?x)o?uyEM!5wZErjL0lU*CQHN;DulrdkVyETw{Lql%h zPIJDBCC#`S1m;FA2w;9UM^fsSdFK?Nj{;aiQX*Kw7KA_Yg_-ofk5$oTT+ zA=?uM(r*eUd;O}odfx9m&hZo^8C4XD*AA~R)#>?E_=1#wozV!GVcyENY12QgfmI4b zk>og|;=Tu4)zo;1W@n`f}GLwkltglAEdD9v>L!uzJQEnGQ`4)2gNeJMx1k@Ds z-}_r&ApF9_I!bWVi#h1g*_C|}Y-(d7Dm`;FEnRVJNS0-9fi~@oH+>qs`b34F-Jas4 zw6gBm*PaoOQqusGaw_x5>sLu6I6aKzPG)jCbI)MPWRP>Bq9Ab2g@41}Yr+=qS5jYD zGhS%S9#j=rEvxa6f9yV(I+j@NdGfrQCB^n*H@IK+jny~OS)+Gvz6T@__gmg+1F#24 z?4nlF!uVb|32AcR&ZiVy*fIh|-?!91>QY#!WSh#(gbNPuJxtl#iP*E@ThlAGd@<@V zV9NqDH~UD}vXM^h<~}Lt*^&wSxq1<5&5~uDxBlmq%3iYcH{y4Lq*pf+|CS$uW55_) zo22M&<6J3R$a~*bXp`agT~|qc9^SZCd6t5!JHc16_>t+l1#=>QN}NE`kTw47Dydk9 z_@m<%Zg~Td1O(%LsUXtpvlDry-xvK#U^#x4Lb_Sb9$j^~UeA+0`9nXK76c~cw z1@J`>wettU!3d_f%~{`3E0>2SX^zd!e%e8I3{|Hvi$jl$CK>u+!N5CB>kp9w+R3{A z9Yf4^6wJzk;!qj0aT{hE!sd)XlxG$AA? znI z-#abZk38VA1$lP0U685!rba0S!++q6U0!bt2d}SvP|#Ft`0OlmgXWhGPfDU$zKg-{ z;LaG*x?GQ2yw^-o2;?^##<~N0jZUm$Wo{*ToV$=mms)R!3G>O;8;9RtSs;%n_={j{ z>FLV%Y1%|M2;!dBgMeIU9W&pswoCa;8MP_P8Wj4|3H+?)zjb)d3EmH;P_l-%tbVuch9&M zdVW67RLxje7Tb8U;qvapqgMkn&98Dz^1G@(NOs-`(D}=IEfp{H%AIZAD`oN*e+gKp z6ag>=%^S0vec%0J5vA86Upbk~Yxy5`LY*&Wl0U5ZtoT4ZpE%C?B0P`bKuAc$Ig)VM zbMj~Vtx1hc`s}c-j7knk@L+_~5q`kcfO)Uu@iC&sPKKpuIW{w_edJeV7L$ z^OhrkJK|IjLHq8!!Mwk{?#7)9ojv*Y^2x*8&Gc{1M#BFNE6g|JA%u3A6m4?x26;5k zF3;E+-}eEGjsv^A;LlX{uE_^7%4ih`ieHVOVWDCoR$#`9kQ zZk58w8U-nFCne5$QySD&YM6RxnEbvB9OiWnz3;>OhA4HK5#0&RqwkNDPzfkMCSv_$ zI0B7u*Yn5z>(xsX8{lX++u*=yU}Wyg0!bdIu40-q??Jm&cE zm}oR%pDTC1(V5cDbUubTo4Wfhc%3dgn>|U{VtLlnx}XR?3+E(Zd;TZTi6qsK5_FY~ zu14tWo5pHR*m=QxA+h{tN5y#8sd|1vf10)tEw+`u z`nPrvlv&TLXe7HLFc{=~S}7BOXDYK>({GMpp;V^)r~e|lv&eh(5ss?F#jxD!ne=dS zMe$qNP2Xztg&v_ct3S$B;KVYb4=(&+V?wuvUd^7Y3^AuCesJ>4IoV^B(jRogccl>jLh!7_+zK>sn$=~;c_fh`n@*wt3|vzxm*niSt}d@wpa_u zLGUA#1Vy-?j9803**@&2@8H_-Qb>@=neMePybmsqBSo^+O>UYQyYPK|WjUh%x!?lI zD)C;~Bqz3sUtwOm3NM?{2WQJO#)?FvXI&54rY99YFjf5)YnL9%&jX>O*@NcSruw%q z<@{y{V z24u(M=kYX|7CPxu$tk;!M>bQ%J9DUq@T001=TY;0M{z-eeQ`OQ+xvT4ymbKwZDHrZ zue9uAW&K;9m6Rzx|252OG6g1uIOfs1bW+u?B_Zl0#)|)C-t0@3Dtu=gm`Ts55>F0- z47IsE>@-N1p$hLA@Sns#Y_N&{EtVP^*FKTh!H(C*C1IlUj9%gp2&FGlSu#J{mh+yx z1>?-rM8@0glWiwcRl2!aj!>NgW6s_45Gn-&6pg(BhA_hGWwtu*X74T(Wmz|JeAX@N znK#~%KL^Y&5kJ==VRmp1J&e0)(~Qsc0pxj}QGXSR4?pS_X)i-EWX4XhdjG78*Q6t$ z_S}o`rPD=n&Ytj9NG@yW zgst*@c(zUAlV7)ss*u5bor$+|Dwgs8^H0D7*w!6$W<_^b#js50kz2nmf22<6g=^!x zBf+RdABCyeVF0^(Dd0XCs=ecCTr3$X6zYGHMw?W)@>B*CVA{2;nBgBnI4 z({y-qUKexM=?_sMKvVydQ1ol<7)7|c)6NRD3Dva#p+=rYFJF~q$nbtrhFF6IuYLBL zPp8$uh{cJ6zn8VRU*y)ixo5(g5?T(Ho6)8YE6RHVV#GkA)^8CZ=ozH)XYE$+&H{lF zhjzZ7N9(rTmSw+cS@D+1)3YrlO>vn$sR$lL?9IcxOajotb9HMsacJWiyhIre+It00 z3FItM8c)>&c#66#n-usyZ0u2?)cE6^nN_?ka9E^ z(ei>k=r{z5f+T`()r&-Xyz^^0&uG|+pEvrl@xbgOZzzcGm4g6^ALwmN*HloY$>-4} z^r`D{7G1l;EHNer6xRj;BHJ(ykonl)u;%HZ9G3@02*%jQ=E_;wF zcrHS2M|v5ErpAL!{7tK=mUzgoCqtDy#>FNt&!{|plmU||)K zMBm)-1$jx&Sph=3D0288-D)lU*RWr zAkx)Ik5{b3TM-)IyvqapxR1WUj`mv`^rE)S*Mb@!Li!UJUX>1CdP!tnE|DFho@qr% zhcbY8*nRk$F7~Yd1EGL_2DA^%0;dh|Uyq6|9xV)T*J^2+El7O5EZqNR-pr|+>k--K z_D2&dwQb8L18f44%$_GPJnZs6iw?YsGxwKKZ>TCvggX=P4i!%ajKlV)Fe$glJcJ|Hv50a0+ zk5VT9ijcRJ;Paq*OwL-&8HbC>2&3V*&l2|r(=B94J%{$`ihMd5Aa3r95DK(3~P3hqhkYf&tu4J!Sx=mO#dC--zG@`t(2f$&Co7PQ?)b;icvTI}|e ziqtGzukKBDx=*5+X;KRneIR!yFb+d@K)^8X>u1DyYcR&DJ)7}7h&F>JEvG2+zKFlv z!{Cp%9_TW>e)&RFCQ${oYC& z;2Lb2C{fgb{HN#DAsCwv9g?ueuWcg1_v+ilwdOZ9zy1y+4JF^m%ghb7Yg!*%8h9-$mgU^9ydw2zovv;49 z2A98H&A#;gK(Ks4DxtUd1uK)!lOTr@YaEB*mYzrt1Y-b+R1zi5V*R_dM2?(t3>9^C zTN1Y^BRDF>lyys9quIPu!uBlx1MSmbM~SyPv7b=SIw?=r=+!FCcg_KH7t_=DJ0m|9 zhPO&IY#urLQzZ2MlpBMG7US>hqMUn0;;bccia=+U(PUofcGPfj){B$^|I|axc%J+b zjiJ)cw_Z9aT|?#hp-8+T zx+_;M`gLyBRrHF1hqG(C3KL(fk95fLp=M@a{gPT@D z0}NC<+cWGR5Bs^Th4p5@C$mQ%6DC+a#zpA(=I&n>9Jkk450C!I;^5_vV6~r4FDf%VU$}~OvZwcGZS_bZHp=l3IfvB+$xpW|6 zGcdZuys%lU9&D)gMCKUp4vwkSAGp~!TP7>>AZ&MRgyC}#jE+bw^Emz06iR@vvEp7eh0I&Z%Fic zc>a?=Cbj>8rqhyOgl|L%d@v4C;F1aM3E&E!>zQK^7E)hwx?3eTbo(2&F*T$dsb_z# zjzu37tZR1&1swi%VLh19y?_4gPO79cm85)gZ=y#K>(xyKV7J{=#JLo8I|Jl3#ypgK z@Uz<&)~vJkX`6!G+-yam;elL&oK016&wy?D1tyO%iv}{Bkw*+T?mZIIcTf4&lB0ns zhz+~`t(S^m229%V63*SLT{^Eo^UO(YkmaE(ookx?<3Bbl**2RKy%WHA9iwj(+d&a- z^>k#wOqHXR!!MQmsSm|+e)U%$@InSky0v<+cJ_FJ$`>=5T64 zN2k3_+`T7R>l5s68%wV9H$6ydR{-dq~k#k$zgJK-p>wt|v?tH1|hf;6M9J0~Q z%-69ukT+!aYl#Q!Epn`@$Rb;6@{f z@*rgW$h^G7;#n?Kt0Oy`I#KR?qWWQzE1OA6YCn7x*2wEXmqB*M(L&qqZS#)ULj>V` zu@dL;zv^(=$Q@%3efSi8=MKF^S)J#NAVxViM5_&Fo%0c3;5<5))boEyXxN7-R=QpD znsc0Ph{uN>1^cqgSU#4zh5$jvemEJQgpDKSWsP*de8*%t5-oPre4Y+|1V@AA>FK-& zL6)($20WxZ@Cjk+ZJa99S{_c-{i5Q+)@lm^aZ;EQL!cv=)clOZEDZ{U z?8N`+jF!iYdQY_d3oS>XPw1{{!zo~3#BdOuSE~K780Aada7_?9r#vFKbi1-Yr_S|PIZ~f7VEf{gR{v>Dfn1jtd%S(A z5W+46aoRGf^JCu+}S?)F$w;;wTaqdH= z_&;9zU6B+knUexaSa5=5_zMk64o#gZPwAJd*G;Fz(J7k$N6}gMHTnHfd5%T)=#uVkq#4~^BP67|2GX#R1IE6;{r-c!_T1;W_jB$!@AIb0 zLh*5lsYC>a)mcQejGHAvYcutofMyPq;rOXy^*>K-EU-~{B%UDY6wN$~MT-O#9mB1(MvvW~`haHbvG zLq^~Lt(lwhVPT|+9 z=s720LS5w(_}#ijn|PG&$lvvf9FTM=lfCh4tt|MP_B>%Fh-+bpW(&-V6PNA^6@{ds z*^sW|3Hvcx4O2{)|GFVKWU3-ioco7GY*-GxAT6FdO|J+r)J)`tN6Kn9ZV+QTxcl2V zU6?XD3hVMSuF`GF8IXM$ZN=KMXI#O+KmDy}WsPl%d}I<2Jl^ETjR5vvd{<=Z#iwDW z+n4GIzb>b}kn(&ZgxM`#U^7VoC#!}}Dyn3NaNlSD2jGa+HCubL{|`XS2L%@tN8-yS zJ`PF}?0OspXKohnuQn^n&{%!3ofi~f4j?h|aTf@8TJauX$ich2F56wJ z`l!1m?>e1ljJY6DjV?dq!{=?m6j1iw+?zp4KGibkHxrAP;5wfx?X1I?pWqpgPx`pM z9B2sraRH&3k|1(DRaxneiF%#zS5HAwr1wAv1CsL!%?94%f*%!X^=~tWYCCr%0_K)utW*8+f4oqE;90k9A+1N1pTBEp~Rx^p8 zTuD7TzZc^;EXB=vwl6`9p8u_`i}NEPR{_#(J2CfZE1_uX^cd;fTcXY!W5!|ztw35S z4-Hql)8TiXrGAphD;L}c(hKf@sBQ0av#7g_>;H_>nZHZsAp5{1Is%JANnzTlDEz)6 zAqc3(Oy|e;=u}O`29;>~8^>4f&ni69fI{Ev*TY*5@=jhn@FOwmIAtW*s%FATpt84+ zR&hCp6r%9WR2Ef=2XHu7%3*z5$e|^w_V2xVNAseC(ZBgy85ar|$1<(1g9bF+ zPmJWnb52);bXu%Lxk`PkQq+@-fd=3{Im*mP)MHCRO&u1FG|%iPj3FBl_BK&9;K7Jc?m z|CyG<*CI@9+8q+n2wrC00-lsYmexUYxx)1gsXs?jQztJCzv$2gvEV03 z3>xP#Q;PU#^F`<9W3rXOFQ0`X-=_Zus0@>mH(Uh}U!$nJDh&||LsJZP4DaR?^2&}D zHH{{*CTS*bv{-Y>@U@1$^d4g||JV*_rrzroW?$Op{{*RAg0uvR?U4rcIAo(bYE_M> z1A9fF=_IVwcMoU+ao%1-Wtd+s!DGSCq0R7XT|?Gy7O~bhzg-E107<#RFS3b!7N07` zI?8#??&(N#>@{U>fZv$&#c%S*%k5s?k-CtS*nA(5EROoSxNjBiG2%TYcKVzTUeSd)7IJ)sy44 zzw#n|{m!i6ropTIHYU8m!OlK*=9J{ zOaB3~uO{45UGUGhGH+R!A2!+E>R=dxqBXzNW+jBnHvZIg=uxd{c^NqY`eO!Yjt}*G zKlwiUdT2p^Q=;}aKtisHtLI710< zJ&an_hnZ0%FDlikygAjp1OV{7MSz1@x-RpN&oL(^MzHx1JUrm6`z^9!`PILJ^leM^ z)DhY&y4Y-nwMxtNHM+iz?B|-c-#P?0H%4ml3x0ovbD}nr>3dgM6M5ygWSY> zTD?RQ(N+}H>7R=2WlNeQ3e|9t^~6srS-dZ?)|4(&VF^i_7w38lxm5G^<`0&|F^+T} zI~>0jNw(qTc6tnX;TTg%aad;9HVjY zYY}B^AFLTGc5@NR&6s?Du~A;UVe=}w-T#14;EQ@1XB&+wHGk~4;9-0mADt`ATY&R@ z?%J5ht7F*C3f-geH@WyHJ~2Yn0#-1*g?}3F1rb~9WJP%16d`yjA%2Dm;X3u*nJ=4_ z@vA2?B1gW(@$L1;dVV%1$-b!KTRu6pFdHxZ-m!+_Y;W``X0J;I5HD=kopIC|Z(}r~ zAnu-l$gA0BFJLYV@VCGO}aXhyWS$v)z6woEvj{Lt0mT{i{Ba{QR!A7V9=} zDJcB+Co>yx!(>a1aY;>*r=6?46HREp=$O69yV2+%*WSZ(bvb&f-+yMh384CU?;Dy= zVsTYe=q`BInZX55ZFVXDFwSTUhp+Cy`+EO z!2?}GN9|mn_BH3wFz{=ogyA!lF*UQt5c(FzovS zW2W&hcA!b4*AY3L=_>8dYf_77#CoX|JQjfU>WP-7?p7Kd;lCJ z^=^j8J)Otiq^XtgRdoC>P7a9-`ITa}E#UT~_fFUOmJW*I*ETpviqQZiflT>rAXB_- z>-bWy6KAY&h2L4AmNY3EK=7hy%Qc&5@lpr3z}Jo~k$}eIp8OHNQdlqNrT}xr;?8at z#+acf$|W6<+jclbJ><80@k#@eD^%W)T4W!nVxT>$^#LBax+2K8p%H%E1;^cZi}vo~ zUZz3E?$H}=ST4WR27(#5;+Bs=NgFTj~h9q2HYuwhpmbPe0AEe*FFwV=Mh1) zIhX__?x%-Tccot(aKutW{5324?#(iBB0^9AGy6S;RQa^c}VgoUE+}2 z$AoN$0ka>gosSry7snI<4o9=0v=QM@AkfBTKr%!qMxvQ2p-Mx=wNpBErfd{T$190; z_2091oJb-4HuYbFs{|)KY)2$NiI-88x8Z04<^N*|k#-NXNOEJOJxo#xK|83|RDIGO z(^Ms_Os9SG3t!QcpCFrt3VimrE;|>wbzk@|I!|sf^{uZkb4X#?3 z4cpgFJi1O2VHY?Rh|Zw4FgRW96NPnw7{Pts-7JTh;iq;*esnXuq4Q~&l!2X%^DCZN zM=zi)sVh}oiR>Tv;uSn4pyOL*!4*(r>p3Rj&qPZO!kHKWNEmR)bX~c07PARdpZW(j-I=Y31 z+lnhLZ6c#r@7FH8A|N)U92ics=s+Vp~4Z=cPRW#ZReapOy2=8+fTjX%BVT=SG} zHkT^DSUnbQocZCO{&aj6y!fYge7{{&)aL-ISx}@@o0#8BdYY(75XLnn&Qm3B%f%35xbFu2}r|=+Tpj>g>^SnvUx#FPYmH1vmduU?=a&$+M83{CK*Jr^S)34;>cvH55uR$yBQ_(Cl%xC;-vvxSa zztqnc>9_H!(NIm_AFN8*Tsdo!Oqf9cdqV4xD3?uCBeu18Yx`>a)9l&xuY&ZGtxQh| zm%8Dpdl<0V?ir>(vdN>!97G6OmZFAJ1xwJ_mwH(ZT)f>ltv_PZ;$HdaUsX3Ob@`M= z+=(J$isCLX^b0^#wTllrO>$^74g;^S?t~BJ5n)VI?`!;1H~J-I4YdkeT1Y?7jL?An zv?Bb=e4ZNAj$1{0rJF~#)D07Zp@&B9Hipen1-=G7H-U8EPQpePkE>wpB_FOa2*@Y8y1?&~Yc)z4g?6Xt*uuEuRW zaBT?HsvqCuFRK0<`@LV~_SFH>mt#2N!Erx*iLW0NLXzi+7=-!2mO{qwQJs(ZBH>vG zRzkQv@11{yX5vL?5BAp7GSy8p!Vbv*y9q>|ZtKk3Uvr+H_^QY+Y(JeC&?RAUsa5($ zAD!;GUi+et5#ysgHLhGn9xEZzPMx(T~*s7^3*?_(x?hfjauW7<`}Eilja!@@m@2u zy#M{nc;JM?cEZ}=vrr!u%rWbeb=*z`F8=zBw-&%2bNpaDrAri{fwZB8F}^CD zle-521w_w~Sdx)f+Ro|0Ja4WIO$|$~sP0QHMP?4a<*6}|D+&|}G$~Cc#f1C?Qwwi0 zPvzdA<=>?6Y9L8B^`h9-GEoj@=i7qoNLF5LLeb*Lt_Rr_nQG*NE_%KhUfrl?7{XT& zwK4ppq+bDG7WXd5NS40%dN>rs`0JxRB|F)_*Wp@eTw{PoHO@b)xZYR2tUL zfUs!EaW!~wWu?D}ebrTAV3YBK=^=B*NXJ8(WvV*{MUsP&O+$$)qR%(79q;IYP!c5D z?Wytu>46^i=BeEF1k<-XEdZ9~zYTej-Qhfb=L7vXpXx0~ByZkH2JFRS4uV&9Uci5g zlZ2f&exD9~?7X^~tph7XQ8o;M-bugWa`PRJbmYFOl(B!-korxF=`}Xp^$|D+WbP;Z zm?q&2!>#R_A6q62(|#lOFcg<)zT`zsk9Fj$Gq>&MIB}?Hw4tQj5GDN#3K}PQ?rI>H z`dz+;!S_<5oK63)AIIjlbp3=H22lrBfUE@VNCJlza!I>8lO12I>wm%-&)eZDz?Zll zJw7+Y8#qU@q@9SDA_r735=O6~j`~by{{`(}(@ax&<`60oQdb?EyyP5|Z$^V5Bt3Bq z1vdy~Y*#uyS1cX%W#+4LnQ#)Oa*nze%9EliZ(@Qn3>RBfHVxWM!ZmV^vi)c&()UP!&uMZG`dyJFfo ze~#p&9TZidGnI^aW#6vp;E6uHOQ|_&_K+@bUhS~%rMLv1Qax~?#2yQ-m>jG7xdpA$ zC|5$1BnGc^@WQ`bkd=3pcd0 zD_difZm-kC$R$wuHLGsB`-VuTWp@Lng7oilyH(&R-oT7S+PzLWWr3{~_qUO1s-N48 z9%r;0q_L%h&=Yy2Qct~-4|3l(J;#Y@Upd6Our$_^%6HcsfdIX^JEh^5Lq0j_?4FL# z(?b(R+%8!-JW?3TnS%T|uYzwdm&QTyD_)nqEgKZ@v>^K?LYsu<=1Nu$UokF|cm?$l zL1Zw-C_2>5h7b)m{e9MaUum83kYFEZ0t>A=Zxy{-=e?Zt<21@z!K2>#+%tDNkxI}ii2B^ zzXEX$u8jwS<_VV+^mbSK7{5xLQTfg}m7Z-b)!b0hC;su9G6OP9y|vurcD&3^PckGT zGi6tbqb+q|yYS+yc%YJE=^^X>9lloSk!W@X1>##aw2Y8i(XcO%HY696EZ9UaCeFxtihB!XQSR zmk&F5C^CleubsYA&uvLrE_)v;F`a}xN~m#xFL(u3>rDxU=8sVHx1S+@6GDAKQ8NH}nDom70M!h0MX!$DF}#{<)! zoJ*&ezr2ZcZgHN%W-9W8>fM!M9DhMWASm!rDL zo|8h71k*10Yzbp1-xS_Vz`p4j9>9rX@Iwo|@4O=;-!5vP zpwc>BL?U6a3EO45S<`W1b*9`nj7bERU;UmeHmAd~%vL}1`SFAssVQ>+X=(Kri#sn& z1NBF;J3z}!b)S_eR)b;f(muC;e&CSKFL3$Tcw%y;^R3ChtBN^{I|u->k&f z8WQT`FSwt6X4RK+pX=c8MU(O!pMQx-38aDEoqn+q_hczez_Na7gij5u{@e;=b)9PF z$j{}n-(^6a*|N69h~QD9Dgs)^14HRzTP1CdbZAg`)fP=7eb~oeNB!isCGjZuQhHau zKZ%DXY0&0+VjEmcaMp2Vn?yC1U9fQud$E)~r{P)FsoA@!s87zJVL2FRtt7NdXqQ#R z<=9Um)u^0{HlML3Nd&$1@~=L7^?4Ss8|}LY1(J1&v@A?WU}M|t)AvGVrs%CBJx%^l zd0_qPevi;j-n7abZO(1o+E0Q~Os@ZmR=;zE*qqxqvrYQK-hP&v9}&B&!rwn~y<6-+ zsm?Gg?8UD6Ewi!)N#b($qgr>lu_V2&?t?e0ZB##!e64I15qA!FKQ$BNQ^aeq6`aa6 zmpeDgq&rteGlk6>AQ^uByZsC{ZBl;VJ$0yEWC~ex8z9D~W-U9y>*4n#X?(Kz7ghup?c2uG;YRLNwF#-IJa(kd<*q$ zb@=(Aj_enmBf2cRF$2TDWx^P-I+BhJg$H<%T#(bGEqke#a}a@Q5BzmGo+688OYE}C z0x!7h=9tJ-lMmiW-~*|j*ke=Y$IYiG{hez#sPbK|KJ9TRuid{wr+R?=mcn?zK(r2K zqi%+r{J$jYJ+cAVZ%l5x;uuMGGq?Hu=+&2DUFLu`mBdOmzOiEZ5!YdAhWt+wdPc`q zI&&4mXT$qPw*ym1-jf-XU6cmWmsTP6?F?iX<%ug^65%9%E_!b4hr&=?gT_IF8={RZ zaf6=iabY|>^6Tw6*@bMQCyVNM0a&x*H@WXroxm}_e9g9FWPTt%g~SjNQP5y#UkE$r zIm#IHbw#aQXQ^0z^_DlN#JV=}I@PaIJ}l3!Y#|Qaxq~7`&N# zwOrbmDf?Kd)km*^e|8szJ%2Vxm>QT7A5cHI#z293poa2I+fmxhk(qR~de>6Ql*O9r z+C9+|&O(t$K}%;-r*h6XghJ%?R0IQ07s4tcd)@dbjo)Arm2)w+x=O*by-}P8=NNLJhZJp`GLk7@RM(Aq!CqzY8Oz*TEoL&&H#oi6tp6OfaGOKC z&3qX&?MFFt*oDVu?<|F}Qif!9p z%>7q&*khJE!|J*Ht~#3J3k(l)|CoDS)BVLuck-;5l6u$UuI=i6k=EzHhm)kxQcPD4 zZv?>dzIO_getHGH6ug=`>40mT!&rx(^Y-63`JIcgFW-h;h;Swxj-rnDVc5+UzpQa; zJe>%RNB(s`KIZ)&lDO>{M0JygRD3q!_!N3$)1livz2K^<6q(7FOLZ15`i+@ti|j4C zP*sqw=QMg8P47i6k2Hkeeu2w}H!A#It@;2#hycY+z>TiPV`(S~rr~zpVUjpB_3s`qUl;Lm5dZvJPFj2M15)YUwuYwJx$6pwKo*K3aPw>upxL5)pl$%;V zy%>s9Rp)T0iYxZ21HOtTSbos;`!G*62Jf28jNOjDW#0?^sz4h{vN-Kt{%ytQS@T0}JC${EHoRt;BN5fGUqVY`Y=)b3 zB&W|G43VYA)7k6RD_nWYV%8D#g&Px59c6T&3l~&ufedrB&OSQHl|CfbJRt)o1Nuis zf>@?+*JtryA4NW}RSkjm&>{1b=D9U6AWanpFNkS!ATw$AbjznvYW$ap1Mzo^QOGO< z_+$oElsi4AV!M78b6WVs;M=>&kCWZ zI{bP|A}?}U%C`-Gw>>#lbj-PSc!;LIuB ze<((rFCH3Pt=O%usn|=&$!`iv_+TBVxF{3;4mWVNM5k>NVq&(<<&FZjy)lTgw0Hub zrvy0^Pw+~(uV)!%fXu1<#1LuEwO<^V5YGzq4bDaO(ZM9#A(>bI=B^f$bAq*|d_+lBfQkzk z>qIrH_$U|X!EdW)xH{lWGrVg(Iax&AHv-GwF9GZ68K1;iAcSu~aLW{g0TdW@X*^1W5%e`51kp>m67{o8%B_v3F8>IMtT-w9N6H?k z{f4A&=IXL}4Knny()OdE(T3a)Z~|9+#%Ac_-2g-K@sAuy%-Gh-e>-OHrl(VwnR z)s0S_L}cDgKJtf9+|!MW?JoJ5>ks@xoHESZkK5$KLjg<$?s(I$5P2^^vzZ&^+pFnU z+!Wk|^a)AA=|={qT!U<*eR#7JvqbN^|MB$5jYvr!dXQnH@UIA|EQblly@=h^7j2-0 zm+-q@K+TL#Jm0bLyFYrLh?Mb0MCOmq`W*^pMz zH=`tE#bC{bZ%t7+i;(MAorXMq2$fj_BbnWP%41Zcp@QCYW4fTt&#n2IH;swAvR1l8 zrB>-jLTTSj2>~)Iia4h2HnZ}?g$nf&sN z0|OxvzB?Tx_)CV%D-&gWpE7UMpSIU(JLYQOtA{X>66<4k{p@5Qo0E9%SY*>IJc~>_ zZM*z7{6omt>MPR=HvWvxouODI8~}jUxtf)>lET;4Tl`}u8>8>PtQ+Uny|hb6{uQQ@ z9wuM@(~-MTA)4Vs>gT_4Tl#Ust$Ac9W@O;jOy!Othn?YR9ZfRza%3;oqRWLBAYRSE zj>L3K(+V>PTPoF6Wx+Vs;9F?37MOZ<-Dxy~g3sJ5!`*kIP6!E8p_PX~EQ~J*2BEG% zev4EhmVtgDKR=vFtMh$6Ro9i@oX_)`Pib4&Z@}XNw&)gO3SxW1P1P^fxu8}fEvP|oGq$MJ3vY~=`bd=y+n#kkPg3!=OFX@k%?m;T2;`EloU zqEcB6=THjdz?L+Un-%qvsxPM5m>&FdfQIImPJK%&jvI}22$2Fq+byI^iX5{E4|WSS zzSBclA^m?;6woB@e{S>r?gL|?4dnwU&?)y_*DP7S``Q29@H01w`4G;g0mU|@`wI@97>Y6>h;QpvCb`EB1ET@ik%1Zy&Bag;l0s6k6UhF_Z z7(@|o&%^dx7g5}%K`Owsu#=eJt&iiVPTa z&(gA;u{EMt++s@S;-ui<FqZELEd(i<+VtF1S* z+?d4Xn5}!wqFLmzsr9%nxpQ9(ZmZC0H+3cns z7hV(+UZZQyElh-cr*p4%cRFp7epc0(5gvSi7F86lO`Wb_U((VO6$}2YHovZncR>!DKuPTt-V}!w_LmrR8Lh6 zZ6`M|wXsCtR0HMlL9n794}Fg-R`@@VM(Sp!w4wy|c84?}Qd}0^zs*$N(9#T*ee$Lp zZT#rB(-V`2S_R&G`emq#PaXgHh~C(LV-DI6heUk=7!h z(0wt5!9XsAqTk<$A=JCie^=Jl2J<*nxL$t={f7NGe;`d0Dk^U9A3y^(PQQ%WUPapO zh-)WOFj81fp7?dCet=@n-5eWzaxGpPEvu+c9cA8UHoG`BZURzc@*f%h0h*`=%Jv#( z1@Pv%O@As#7I9S^wPOF~=R2OFxbzIiKmmX&P;CUx*TY=wIZM-l3{v^FFp=xYlx2rBg)@L@8vwSrwySJYT0>BN>=>pD<(ge0yea35mEbRxTf9 z&JX##itpt4)ClD!O7D7#=^rOX&w-mKQ+6=%$#Ch0!P-szDz&mrLgc`Zo#Ri+_nd#s zqbq`B-=Ox=;qPb}KEWP1b3PvNlAUwXvcs77u^GC19(^8PVOBB=>W%R$J7bF2Vr0t$ zL&}d?9HnZ>0du!rGH9Pf_AZg@c#Oi!ld0qyG(E;7S&i6KLr6oD(F>6d8|Npr zq%#{|GWZm3TR3Q*)zK00teIr~U6gPeM}Ups3`IDUI`QCWrRv5_ z-OP_smPorD59DF_(J#l}Uf+Z&M#;#T&jD|luCR(%)F6_acW)5JgWwlNein0}H+N^Z zX=%4QiQ?p!otFa9#IT&=q(uM`RxICuKIeW_DR=6~!%s*I2$C{|B`cKNFQ|sBwoBa1! zj^fI+=o)$qo#8W5T{X-F+hmX*9; z3fMTuI*;=AwT0V_OF$TvM|hqI?AOfYNO`4&u6zKPc9TXujnsYzSni_+V9!Paq?Im7 zf_OcvteY)&))ODJtx~CXfg&2hY~po)y#e#wjLx^YpDQc)q-TlZ{(GBFBG|4^C;VM^9-6~tGPWOAU*5@M?GnGgf@FiuH|db# zeR*U&SLX~XD=PMtQ|8s&b3q~ruXA$#PSL90#tga>UP1Vql)2R!oK*iRV3aQunZga@ zV`h_dxY#Dtcx7ebS}?0JV}EwRI;DEM?h~`92Fa8};1ckR!T{BYCIqcBaKiB-z}Awk zXbQ{hc85ruN+Qli_Jn}DVhcJRnP)EnUV@L_py|AqXj&xe*4w@HrpJ`2n-DVnKKi6e zp7kD{-jH3aS*Dquq`2pxiF?d$L3sq?OuROk(e`{UeLuk5iyFx|ZjpZPff=SakN=iX ziPele7zBscQQyP+xANEWKKgws#-w4omg;A?|6GdpS3I8xgaTY+@2+Zkbm8DgflrrB zv@9W?0zBD`@|}F#&NCm!9@EjZC_W@-k5YTshVn!Da&bp1z;pD|)H8|?y>!{0m0&s; z(is+^uh=r%_t4>B`n5)fE-!%I~RxVcNQplK>r8$1v1 zAwaYFDTe(6V;{8m6zVlI3za?V|FC}fj**zyIU7djYV3lZGJejBV#*)Il$@?cxD)*AbPj5sug0CB*WXwx%4qQ|7I$21hxmZ6wvQBxxRbz9aW+qgt%Nn4(6 z9KU9wDn1V4>P~KlrDXfi(ZLEnKvVd3NlC{6#jDZ1OFnJd{hI^cA)SFxWVb1Q96(Ra z+~qwNC?wJUtg4{a+UdL4HVj+D+vxUw%%b1imjA`#nneo&pQbYp9Sgk(V$(d(SPMrRm;87zKr|R`(3Y_%u2t%csEe3`(0S% zE5?Ng5zT^%2^QStfQ;^d5D9IGJSqvvSE%~mk{D)^`iClCTgRV)Q{@%6e$d+I^IK^^ z`c6JuMc)tu6L)$wn8Ez{Db4l^nxWkf#9lwpf}K1hatGGK`uV_6-Hl$8XLk<36<~kW zp#N{_bgOghN4xw6k{LYl{u`e=uk zf5Bbbx+>l@5n9>P3iBbp+H8LL<@N~ts(?QEk0c(*g#%o-8^_nsxDUT7VVNdtf)V9r z?+cV{#zPadwHGKP-^Up%b(WKUc=t|PFT=JGn*yT<4WvHW$(Xc?$mOA%3=InH0VZ*( z8I`Z2wiW2W39?-Qe<)qv)2}-#-+a^_@TkU(FJBQysE@c53t@iuv#(f8G2~~&U7#j^ zpvO!1s_SHqT}0B|H?$M>ptDF(1#qPix4{YSuFJ`88yHUR0 zj6br2@UJjvgg7^xpwrIAk<&ce`(W1>&E(fK5K&}cQPWu-b2H4YYzjD2o9#X~!vp=7 zHVDC1^I*<=Ir8i?fX;PF2{|yRM{?sgMuG zC<7*;?OktWPce;7l6qkcBy8ke-c&#|rV6d3)ReGkFL3819;+@%T{#3$mmHNQwVKdj zM``q}|uHrmi5}1nN+pJSM;rQ23hS-v2j}O1(CrIQvaEfD7OB z!wEH+^Qp$Nwa-i8h+IaMzmzMx+wrk$FU}7$y%k6w*j*+L{97W?c(Z@X4Ber=WxW!+Bof*K*a*(2_q{C?i1LP+D$w%2x-BJv@-qto`;YWn^39f?_tA?B#(*9NHOv#KFWj_|Cf;xA`Fp)c;#z8} z?maCrmWA^x=r{iu094USk|rv6QLKG(OBAJBI~K71fj$a++a|Ctw1XgGXcCZxFH%e=QFz|&wI|;$9j*vKL&oh%V zBYU!o7mU~94%)n3a{v^UaaA`aaS$|&9$tZj*`t(q#*In6JZ3yD29!%B|IxWNJ_f8s z1H>?0&FG(COnMB7nLYQQCDhC5&VDM8!_B@ClqhBJ0 zE4pgx{ORn77G|k4ioRnjzxq=A(}vuo@(DhxD7_sLfDE+R;eNHVf*C(EX*=|<-^;|* zD?m4B>F7h8hxrZ<4WWTxYe)>3`0C))4{yicSe|kazhL&7w!=E`aFCNPn9k+*8)DIy z=*F?sC&JT@C?x#@uHUz55aah_5asN-o21^%j_9Vw*PF|7dF{9RI1(8qghk?!V()$! zW9HXB3k)bcM+dfe%7oWfEws0)1b-!%97sSQRm7(0&NJ9RUP@@x!1f zG;j8%J4L+U zj=oks!8%+Fp4%^>{+(PE8eYUshvSi8+#2*bN6wtdB-<=VJO!}7(#QyR`MsCoH-x3e zIlBfcr$1iz1^+ ztmar>MAv<$@&8731i&LLmWNqe4(uCbKVIvRNY}){qrpY7DM9+rozW# zbejT6`%B@2mcex0yeM_dZ#sQjVuNOZFUFog+%C%wwe3xBqNe%GnC%5d5JEG;7P_Ke zv2YTQ`wyz1A!9m>Mc-UJxgQLKv6TU;8rw+Jm!#_}Xug(6MzF zjF%HiA6eE-j*>#$VuG;rhu!$_u9)GTw}nkz)zz5>e zax=(nU7rPx=)R!X@%KhK0pui?#f95oi1$FXFWh%TX3n^a_d%ZV%<1+f@~ z5mFocYMQNkk!LD`%x&=wpHonE@k;>Mecq4E`~91FBtfy?6J!T4R6?3*+{PV0Rmgo9 zSsMjxK1l@qG=a6@cB@~MwCFUp#77iUTdYDEdLA8`24^Ix$IH#W{XG@P!v8gab76qT z`L?R?11>H_@9+!>J!iVszzGg7HX}mcX(>*6tWCQ=NR@96EBI<=Kzj=Wh zij$O^?S7h@5|Jd}Hi7+h@h{hvuVt!VgI^a+eFVE(Y?h~S7X$T<_`dthO!A%RSVF98 zEQxK~?+N$chIg6fAye#ZMEU^(bS760zA)Ub@PRx6lxr0-^Eo#W%gycwfm?n+;@Ubt z)Ztgp)2u%h+v;I5^p&cr1EQ5`fxwq%D9+!=d;d3f{=o04M;rYY)>A32g6UFj&H$RV zf~ShBwbEnyo)kAaC-z&$1c!Q55fX|RB5KIO8@`q0h<@Ba=;r0ejMse8FUQH_L0>s< zr(iuN*a*VjmB~yh-tPqN%3DLa=0|I9{ozGjdpc&SS;D=hcDxCediV3}uPnpC=pcWBenrRmD~n zH%xTyES;O$2vFe9dhaxkgFn$A8!cb+Yev{A1$N5ExIfY>guTk}+hNFW>ltO9Jg+>P zCIyf9;nHxqr0gP3iG+nt*%e*$*Jty|#KH;zu1hc0Kux!6dC!{iR)qc_7yDa+^wS|0 zjbS4LZyXyw4~%1%B5R;Bwc$w=>@6Wl*8*=|s6FH{*`9HwCSo>buGev43FCB5ywPQ%< z8#H#N-7mX;xSGxK33IYqQ?lWrqK9EPKCd)>XJi}3?t$o=OP$hU$c8Ic70nF?sD~F= z858F2b=G?bx`~muL(*7Myw-Unjoz#+Sp&7u@+0sY8LQGhzSM`wgdCx}={Rno?A@f` zUPx*qYum_oc(8{e$cMNmPw7$XF24;Xga{}h9TFmp&H-accMC|PNOyO~2mxv77@ZqAVeI$r{bzq}pWXYt=brPN zCwzxEBQw%1nLi=+vMCIQ=_u+!cY}2$`GC;f3+MH~N$TGtBxIg37!|bpR&1B_&SfnI51s=(6yj7|gU_~X&Z;(ECr(a1!c20qcFO0=-Rz=BNc zy`fipMbLEU!~z`{bR&Tc^(Zh2VglFm+X`rFH7C1vwYcYB7u<4T69j&oFUxO7!i1OL z7?SBS=m@rN4Do_{@Mefn#Jojsvx2uP(`QuBuN@@-+ z9zNNHFrK+;(KsQ}K4zJlNsu>RtY7FCLfrd-AHy7XJEi|5ck^+KNaBQsJ*G6W$c zlJ|WGR@MA1J~W-h*z!1eP}#vr9iBR+U%5=U?D3^UXch)L5I9YRE6G08_iUE=0vmMt zCBv^l4;Hfna=uyjPb^PP<+175Tk4ncZgMqFdp({=_6Jj*-c6g5j^EQ5(+9Ex0c`H$ z`it%Myo;OeG2t;qMomESFjyEvu6J*9czZJqZfkU<9bg<`IQqLHZ)M}2&iAQ9DT=tY zX4*9ph;Yjvcwm?ogo;2UyIWcfn4O>AE!*+6k-GiqVUG|CJigGukdb1q$|7n4`?-XS zjOgS>HajaFqBZRWZ}M)idBGxbg&oDFj_KY8&i~ zK3q(=Mrl?68i5Or#t^`Y{msPYIZ7zw1b-Wm435$A9iW=2e7SLWAy=(K2}tsbsyG@% z$SN2fNC)?PIbRCezIwEVmP77ESM#@!I|n?D)ohy6ZJnNFI}{w_ z>!)u|^R5E+PI}{#`+R0- zsw{$!FUBwySd$pPfzXbfP}^SbK&osR{5A>Sh^o#z+uJslemkQ+6k(pAZnpK(xwL=~ z2Zw*BW`*@FvS&aVVc%~V)!sUP9Z&rF&G+-mH|=Ix{4lCL`S0a8FLjQ-KGr=&1t@*2VZ4a>o(mj1`9d#XlYjjQq4c#Q<*Lc#hrddscv?f7o|*v?mv( zt3AV=!qxtRSBisEh(q!5PgXZ9Q;w}mM~6`pixatQ_8LQp0I1v)Dj9^bw{&xnPf(n6al_b7W-OKWXkTd86Ia=`m7RJE~Z5qlqD%M-24mQ!9Xw{y>74f>(Xp zBvsBZiXp+%r|*q|LpG#cKP~q#LkUqCgBW^*bZoaA*yg>INq*SEl;;zvI}4C=N;ph51LuIKP~~uCgDz`<1$Gu@eV-uJyZYKBg4M7B|s} zUPj_9>Ral}{=x>rfHP{jBn)W(9Kv5xhHtvwLi=2nrsO5bH6PzhPn;k~=iZ|E=KXG% zRnH3z^6M#`%PUOI&cjddjg?6K?uQH|?t_Zrqg#fC4F~BzXCS{6e3p0h_LR&I+i-%= zIgVCzK5G2_F~kT(Q)$T;?N#Wt=H)L^Ys4h}8>#~>|`7_{HTQjm78_ z5*U{-{vYag>e90S|HVI8c%r8FR0nHKszZhri?@yT&VBVvi0Ac4#1g)y#|~S0D(z#! zdi?h5N$Mw64x%e&5{uLIVh9yTVS?*N+iIMIr~3Yf<)2r}hQw(M^HM zbhk97l`en;V`|)`7@V)^3T#%kyp`Vi74&p>PY{+T%m~-MT58(YDdrl#Ow@0Fetz;H z{b@OjU7JdFyXSEy=#o4mP=jiCq z$!$0Z0UZ8UhnA(#XK||zhR+vCH&Cr7ffZX*^e7ge#%O_0e*3MEubDO}GPo~S13ecL z(&DNb6bZ!_f<93%UH1Qn!-h7las<+yp9^#fZh=hw_GZ0?!M}R4jx^GrJq{^NE(_1o zCGs<1qwBb;>6hah7=@VHBT5F6VOxRE)IT+7e&rN^$=I_qNAKK9P6YL_D6vULDQF^} z&YCITdDZwY$5U~D2YyQe_)O+% zYEd%XFnOkLcy7vYkdw}nil@4c307aPX>)ZH;89CJhHuZcW1Dl!%pE%0S}82|%t`1( zOnTH+T-8H7DQuseA8syxlZ+&)@DhZM1n<5e{x*n5jD-Xb#4X*?qBB?dbdKo@{wI1w zbK5CQGomR82R^RH!(!@KOV$8EWARJJG=a*gGw~bCZ<+|#fril0*{Vd$E3*f=#cAGm z7lrs;kfnQ}w~?E$$hCUX+Lnji7V@)^pzqj8~0Wc3#d1qDoObj z8Q@$^Y4Zs8=|e#>K-Qkk3Jxix#H>R;`N=X#+tBZS zYjg2^#7tA~u4^WR*&t@9M5NHRX(FrRE#pxAYv(6e`t`#qj`&KIB#~y8+Lb#p6hl^o zu<5%P2YrGpf9qxA`F@GZg-vKW!}N^xC@4J%>N7)wN+l{bPq|cXo3qQrg3i;fuFgOg zcn>qv>?R7*x1*bPxJSe~{(H7LrnYQUVrv)jK@pVRdIPuOX`n9ZRt00M2I28Tai@xs zp;5>fFZ081qh&>9z|Ma08!(!)u?M!nXeM^F{%np(<3AiNDXfSNV%_b~>c<{ZBg{4V za`Q5eh>DfBJqT9^coUaCqvSy}FVnjUR#a2qpuVU`V|AhII`hpFLM0=$nciivoZgGq z_T9h!3N>v#J-3v0%%|)0x$T$r?zs7@pL$c~bG=`z?KcAFBXcI$GB_#ZrQun#iA=sM{-QG1ruBdzcp7P|)U}2AysVq!s{`dl|j;h;g zNtsqq4x}-ocU5{B*l~TWc%RjVXwhn!owog}bU1mw^$@VYmsl;hqML4S7I6jRO91aY zlJ`2yT1m!puERkgs3q)8L>$%C z2}J%5QvI702?Slbj2eUq{C?}j2Z*l>@Xy;Y>0n%=(M%V7^1^5nu8<(_vz_sjMq~+hqEYmB;fRcz8I%q3=@Jj(tcGyvUHOQZQeoZQBGT2D ze7wX=yX;bxM24@&q5xxj7iXCJ#gY+iiC8g>3FJKjC$r(ujETklhvTg(e)>n(?L;>d z6YWnt$S!X1K6$M3X2KV{py}%06yd970$N1$BustfMCb-Fp{$oB7it*pMwLEZ8vQFL zw#@zkvj*L&+<+filsM4_wQ&a-hx<>zBHGBGa%@EenH1ltH(UcJhJ9xjbfNEC*()X_ zs9FAkXewTA)f4+~w9d~6#V4r|7ulEN*Iw%Fj=Mo`o}aoi@!{w1TLdxG0jgiZwoGrT z1U8*VIJ(L%gF9V%$MOnusMI8l&t6(TzKol-Zb;n~5OW-7xy; zdXHS{`Em`((+^>XdXStKUkMF`TJUfme<4WtOFBAXC)H+K|NT*DLUBC=u$l;vK(hp8soO2Bj4ThGGGnsgzq?Zn#3B6k(5Zq`s11gs?iU=SUK|9{u4Mor3k8? z-V}MWJ9<4;Te;W!4>o+K+}v)HlRId2%kF+%6A2YPc*CL5oK#5)b031{LR68 zez=ryKKP@2x3$CW!h`e2NAZb?^U}U^W;1^5R!Jl77T-XWzx`dgt71iw`|C0RCHWUz zs3RA6Y{ME22=Rq-Ewb>A;8`gv-Yrb$rQ=q0U~Pk{4U_-rQw^|Hs}fO(Pg!}Mel$kF zg4TA}e1=60b`mrmr>IgBv(X&@@2*yADN~`Bbwo-bg%9Vqh8K?~QfhE;Ph&)-TXsME z{`%ja>u0$Jwahw9$EOS3QV$K-zYXptfbexADa$JtCnH#mVy#B`@x!NFYaH)mf~ZX- zaF%V=wQ+8^uWFuRv$0vXHipP;XEEFd&C88n#F=tcuq!dpIP`M3l?3Bw_4Px@2 z?5G5%-@px!q~fb)b!j92G<^QW3VB}K;MZ1v9tI26e5ke(#<4PUd9e~ut)?`lrc)I3 z(LxwIr`bctpifluRt8EmGJ{zw?ZI9DlrOHYYrc14D-S^cf;>H=cl}vg%iq3!^TE_o z_QJKfM7@+Z{@<0j`{!qF6wrnQ)}=>j(_29eH79!8z=V8qy1^hKC)I|^PHQ7)1_L#4 zpL}6l8_mBQD?ELMgO_{VdPwQW>wG+L^<_VXr@nPol9e>RYfx`k_Y03@XUgzu2oV+a zdu81*W#F$3>Yu2^dvY^u>MI#GhBuG7wa!l3za~WJ#9NbpWE;Tj(im?-o0N(F`GaeU zdn#9NO#;x7IvT_I&03H$_VG(%ZtB~e ztBX$)UO*S(Qh@~!A!N-xG5Ixx9Yc!$7ceSPzcIde_8042eHyE&uMbmow(|6~C6g&D z@7E_I0%L9D3IAk{XRoR|w)T5BqFPuaNQ)&6YNxzY{8wNuSjTcInF&s&b>LLUz6h;{m-R;4&?{ahjPE~v^rL%ZkX*_ z#8yND{5s26L;;jdzOVm|Nlmw@%P<#Nim`gO3w8{PXaKy}WsY?$NM}FXgQhdIJThn+p6|I9EY?!*LVY{2eB;tp&FR$ z@DT0vDZ{-qOHwW>WyR+FYG_D<=Gzum_hCGoj<=VIuI`iWCU-8`p5Wh~C?*S1 z|48AE!Vm8Z*|Qa&4T2QJ)ic<_Y!>5ahCPUDk6}7fH&ZukC`v>>kosVQ5p8{`$v#{} z*wvY&K7x2xk3EKkT#*_gF99B6Af(jTV0qMZ&YAUqYnkk(4;$3r=KLh>UKjG=A@_P8 z(dciG5d{I3Yp0kUvVSJN4ZgduYQQc# zkUCq2gF0+S#6v8;k=)G=KY$Jqvii{gHieiUuR>In-fxJqSKN_5G<82a-k`zI!r<&L zS>=swo8krFSsG8nL|8*I0J}YLn|J}ZLy!#O!JyFSpAO3w**yKq0WJhHuM4`Gdb#W} z$~Xs^wM8w3b)xOwT$t=%6H^4Tb@zlB<>>9Y+9snnKn#o`mh4K0>#|ln6nYV_zHgQh z|6o4M@xHB|+G329;G{v_znezCn`w$meVqaPy!SB_OzZcOB7=McrnlaM73JOYpb1eo zS;bXwQ|hKQ(|1VnaSaZ_T`UbPt(9 zb|gWdnx)(AiIV8X8dN%98E{Yq&R^CYz>DIIhds*poMs=Lje{Py%mUWIA|Ql69d3hI zuYJ?ag?n#wk69XZRXbN-?-&ix1uoK!hy17=U{X{C{yJaDzA^mM{R}f|=r6e#UJX&) zCSoxB==+5tecje2LV1t!u<08;&)3xw>}a+Nx+y^H!cO3DN|nvT;A_oR=O%s-`P8FB z@(UPI5qTze_~f6d-I@%s5UB3zjx+xJn0t!DCHDo}21VPqkFfA{M-x~)#Ih9JG3eB= z;pi)FzAm?$F_npit&CdzNEq7LddUpW>+fGsPm-SKAj4%+pwgC0joFoOzfspTfBp(9 zs%D_J?lsTwXtXbTt#EsJdAR7W7*CojdpUbm74B)5FiZM zhx=#Lq3awd>U%w~&|N@2epzF~f&^;ez|VE8Uf^AeXoC}x$nwVdp}1!=L)yPm8j6cd$ovJ8OPEVw|72I+;R9hW7fSP+ zBsBm|_Pq59)a!$a*QY74S2)}?b^iKQ=IZ`<%sr<9mO{$5BeJ=OP~KvV59-bEG&h!C zSzR7`pP%_ow}021$!)ARq*9(O1efgtst(C$gvv)szg_60F7#6p`7Yt=Tg1@P+L6Dz ze7_CerJ^AL$}q`H_=^oSRVXYo`!@Q#!)z<4-Sc85?}nC-vd#ylsHS|AAbYbvDAb)o z-hL&W;(}K}K=|w=kaqln0A@Zz&=@cX zLq2-1HDx8y6U{;#0nsBkDEQ3WxbUyN@I>0ZP3HIlK07_YN<1^%B$k!z@91xTa*g!7 z$wbK`K?A~{;O4Ft&2!$*7C+X`3*}+fx0gRJi467me(f*%r5gU{`Fj$(k(#NE6@K_a z%l%8teAewL=~gsLpq7GG$sxz%ui>`2UTx^okIMO3(r%{%lw+H8bJXSCFR*k3O9-`e zzo73Mlry56njBnV(U3K%XaHzV=DJi?O@G>!maF>q`5VG+B)$ylKb#vgL`3K>=pQK# zex&)2i~%5Fr@U~iWEu%Tr)gy%+en$uz0XZjaR5x=xyMy7OKW5RiCe;V_4evM zzaV7|xT8A>BD-hRuJ2hupPCL%wzTJ>Ydrn9snbm>N*vCNwQ&cuu<9J9UKl++mT9=t z;P50u@obDlc#3)4rkYq$@i^Vxkk2A=Sju0&T~F~!RCVg99DOE1ly96ganFx^qRg#U z!A56CLDf54_Z{BdgjdR|zaFi%SvrNL=J6j>YWA+1edcze8lpNY1leB5z&@OtHA2a0 zUhzK4@cSOg#7ssM^xo0-_Xgn+okqkJ^2 z&gLez>jR^F^^hd#``U;~+T%<93%ZlHbxXqpz_N7=ugzO!|QDJLF{!*7Ry z5j}|a)Ju9;bcX`?+1zX$3|EesHEH>Cwhhv}&DL(y{9Y)s>P+}q^!vigw~^d3lIVii zMr30AUeBDky#ioJ?DWerGybEkLT-=tTKVJ%eZ)&{`e~M`(d1Vd0xr79OGi0q)H+L> zeSm&kxT@=#^G3@qcZBjV5D(PrB}j2hNB(N84v*fAXx@BD-i=CjKkH6>n>UvsgWR2sB>Ah@~Dh3xf4l$s8rG=}%-v(voI)zuMltA-PTeKwmClZRmJyVc?E zaYlZbb1q?5mxPbwQubFQGGRhMWzqH+0}?%^Y^M@MzL;@ z#|jhDxUHNE?P879B0d1V4+sO29$y_Mi1tZdL&&<>-O{5j-=ZjHM235*&h_SSrz}k_ z9499aPJ9l))I&PaP)^i`AAof()wb?-fhWzc2*QFF@pnmNC}2Ni_I^I3HL+sTa9CmK zCYJG4*5(2NspHPfFN!7gl774W#V=*!2u4jmYn7-+e6O`+Y%wbnaI9LJy4hZcNJ5`#f3$O01e-pUw%)5x#NHN;v|)? z5U>wkl<&)cFD?f(51pleuX-GGP|u}Lo*;F4p)3ek z7}~S!m_;eAbfDb)fYD!T&Q~um?b`req&@}vye~tLpsF#J3Yd~lhv5ccV=P6%4e*{A zD^v0*h9li0;AhIT7NTbb36fLhNdrs*;%zN7!=h(B2pyfjp*Q*uKcRR==r@ZBdI9d+ zr*E3%Gq2X9j%&$5#-(2ckdeMEG-5 z@D@q5J13Of1VqgXIV&yKi!HB_EEQ^o(VT(P66Wm`ne1#}Ha_U>5R-5j)BMVmS(gncO2ZZSD7wupR!tBM4WT*dk?b z2hKcH(ct@0lqY-E=#p;H^T6ppm^h%5xr!mm4nf=t#X%U(@Q1VGD~Yat?093>cZl){rU(x=WSdpBguH`I}=m zFQNCtF$=uU09ImTrMp`G8E6J>_+%9#bvTIP+LCfLJD`WmJg8rTrC7-~ME^~EJrhB) z3bzy~8O(+1#o|dac0%~@5avxy3CGtX3GEr zr|wEpCziQ)Wfz_CtC>F(d_MFVBlGYbB7UNvgjuLUT9?n2KCsrK6Z@%Ag10c&C`($P z^MtDwvgqor5<@Z5*hAIFjbziLRXC$@!;82yl;ISAHp&A=8Qugwq$oXu&Su2A|7eu+ z$t!y-NCo^u(Ne#99YVB#V zx;{Wn-ZO$_#-W4WD)dI-f3fLU)+9!epsi2UumI^jqK>57e(n{f1pXby69!Q$4mIT0>e z8}+oP%@NT_{_6@DkVdfkDT?E^&woBnDq}fJ&>4V~dOvuiOp!pfO*$5u6X*y-)16~T zkBb~&x~L}a^40ZK(NwKjtLCq;-Q91i?=Hk2o%odFw33Esdzx4^$R%q_!av(=bK=`w z6|z}qDLLwB%};CIJYXxzC(I}(k&-x=vkzE*9{+jq=bV?8%8*>Y*@*2uL%!8}UUa&v zoP!aLoHK<6fl!c=U=z~}QT!8rI@}Pb3$WuF({!hUgm1bgD$#%}X)sEwa6QdjK?t2A zj}@R<D1uI93ao$t(R-FZ0ABoc9@#4=c4?5rE959%1A7S z%w`F90Xr$%^|{e)21D(yeS4NhSU6rMG*0cADl1#8Ozj#uJJ>)MQ^08b)nR%f7d4dW3PP31H?&+X^cqOGbTaROA ziQ6cX*mG5n0=Nrf=yJFJy!W^;PEemBM7oj$DOCkm^tq74_ql1{x6OrGPwWOKr=}k8 zZ}*TuVZf%0Xecvhynj%LcSR4m8TVTCFRqL2EHQG$e%BXMbk1Y#A(5pcd(m_C(+RnN z-Ev?V^-{)7G4}R=)*NB_C_gx*(11Z}>=-{}Z++`Sj-Avy{AYqKTvXcPmZdan5D8R# zv0_oxUVi2BD4N4o?>WG}SeuI45$nri9%LAVQv3UcOeA@jIfI+~4AEPvaM{Q4Z6i_| z__(mCbH1A`S9NSd=P4*VUdj0MM^uu?iB*aS364z#hx|us`ez5enlE%Uih~L`I_{Y< z6LRx#M=W$Hky-qCt?eh%DAS};P9Xn4k7GWzccDc;L4;}{>`xklwjMPl9DeQ&%vf-2n zyWi_RL!6@-Gj4t%&XY?}@V9@^%ACG$vL?RU6PynAJ_0VIU%;c|TGWL2`Ew;buPrz2 zVZzJ2-Ph%7?fXK$YTSQ7 zjk)WCCZi@wVYe)1l`;cj0`@h}&^)zS`udDk_u;fg+q++4%Wrl!gv95K^1snMtXi?% z<^QPZ1X^JmCG7WmBKfx&2d|o)?Nu5hG;uwY)KA7fJ3w6&24t6YKCo1ars(vx50?bG zdjf7x+dqEx<+8#HjMP??Thv1mUUjM6IL`9Uo~C2TNKO0!k+Cl>ips;yTM zE9;VIkTRc#+bLYt6bJ&br!CIJHU3nA9=;nG^k#uaQ$DKbl^u~UO#~rhIK_qtm(AfD zSqJMEvkhvS*eD24mzv>IlBw)H`s4td5_Zz#96Hnke^S?UQA6VRHyR!^R5uWr$`$k!5M{V0x8 zH>FRSwsa!$h-$mLS`q>soHfnNWGGbHY43HM?7t|bp(^g#Fa!CG!ZDq`b`OO=HMeqE z*7wMBRSf37##M?cUD8(?Ujov#e)x*KdAV{c%Bpj9>JYGXydo>%%yIU-8K3U4w-YT% z-%3`gP#k<{Zqf6K{KmQ|8cKDLA|)cQ-8Tsg`v}7l`(m)}qKaWP61`&2M@M>ZYjTxn zAtsH8+g?S~i)f1yEM&VGbUJ!(g^C@Po1Y3*ko2-{jBhs6Wd4^Enj8AZ zXVQ;;=OWDpMuT?&aCsC^& zsB`6E{!X~E_%q%AE_Tru>+~Czvr)JL;7$TrmS=@1hSX&#ljMUFRrgCgK)LNvX2aZe zPcn$d**KJ^WUq(S*!&mbzf}W_{0N>~zud$P9aW4veOW!*z`QMA`OZ3BnFZY=?UIR2 z^j?~9v$l6w+FAasIzzoar8uSA<&HAc+$PWVcA%)Kd!2I%$O%3Zh1pp63a9RU{|6LW zeI%EsYK*1P1FKxpvnW-E4$shCd7pPJ;wQxd;Kz%S3n;1w`*~Z@dM>AmIA8dc4m!Q{HTIr-Vw=;v?O)b|w&2VI>3x*d;p z{e_v?yk&b2H;^@a8^Ss1^|^&#MMo8Tnb1?a<_s;>hZjSw`K=^Qcbj&B9*V6sBCd1} z!eakspZA&7F*CzkkN;wF%T%nFyG!OVB*uUS+Sk6aOl~;6eejxpd##C_D**qUDrT#< z@qaP5Ehu5QIqYlGsi0GBC4Dp8W3&1t6RhmmOgO%&N=(b@IsfHztIho{>~2BHiXbDG z4CVX^H2Yuomkxb$LbvZvi)ED^Nl17|@Yo+2Uvl8b8mziRp znyIOp%HSs)NP>EFxRog6+#`tGj~5ypn1BEIjJFN~*P>~u)VLD-{jc|nAc@-p6uzym z1w(YkaK`rw(EP`Ytx=|CB+VVqmcHW1y6h|Do5lRo8|rE6=9v>(aH60Y4tkQ%ef2Gw zWLF~h)wxc#lQf>-O7KfHl@*1(?lP1Cl68oKqPuw!E$JzkyW7lGPZPnsOL7KGs!6Qe z45%3D)a}TzI_u?Pv*Gy1(RPTs_YK|pKAgNxTOe(%N`0@EJiB;ZnwzQXvVZ;Io))vV zY&obXD3SPRV#m>K>vMd9w3~>2Ucuessc=LSJO5C-Zl~^Mdt$ciUQgH*2{=O^Aynb8 z-9`9U%XZA@Ij2~e?8j^D!l2|K0jlT#6-Pj`%W9Vw)pKlf-2ZT-Scme(0Q;w{vTaciA!yj zn2DgpNzEiqUdLCJ^KAxfaPHI%1$~bVF1^-Gz1V;PNe?2DsgjmmJyH>Aj`xY_@Z&P?z|qg}6hFdFeRQ1sMic@;dy1d|es{u&R6fPlt0_-QebRKJ{@`TPVjk!& zD8qdZ9%-Rda(HYcPj~_qM_VKA9kP=D;lcA^vxk<_Q?!+t+!t6H^BQH~e>nFl2V)ua z8f4+*d7W{AfuPNbL2_}LFxV^A01W+y`Z=oXsLk2Eb#}yc z$w)-df7ADrSJSK+R(Oe9$5@l5T>Btb=Db6Tl}psIl5EMx2jwcR;@LZC7nM5&!kv0jE=xY0KDSNM0T~V1W`Ad3Ng4&-g^q zA2;iod+>XyBJa{(kd@U=en$mRNg{vAa!`&hq7Y>huwB}zwRKExLl}_>r=-(b6cn6R zrH2f#Nr!Q6PmC%?@NaJ<<|E!=^>*wE8q_gxq)wzwpi)1((yVsK0$jVUxur?SCSl10 z6w1=(@s_qv8)wrBa}Z?1{_7h|UW0QeM^`#>n=;(I5}WN!x4PYBgzSE?;DRNO?u%M* zTG>|`WTGw5st<`h*oziUbSKOR7T3peX24kiUxrp$4Vml$JSGiL%R`Uvf^R|lnq6Wy zu!)9_=%4Mcq=%l$y)DFd`;x<74O}*Zuaw*d`EFf5tV)%*9qCx)Tqt$%4`7~SE$WGs z1V6*KOTr}{KIsYWne}#zKO&|o5OIAazgVM|;LtKIV}v*cdu`XK+9Or`T%3}*Q}ZQ~ z7|+?f*#kVUG2YgIuGet{f2(nEd){Hx?(VU+f*jJ=HeU(Nfh7FBd>+xMTz&v`ibI+R zrzw1(fCNM4gnDgKOl6e%d-$-1`q->yVDHGzocAdJBxhZ{(=mg;_99*8-xm4)6Q%K| zcgdD&;ZxX7=jYV7A;cta=z<(4+p81+e*hN|j>sTKD~IhbVQ07-dj+c+_FFx*>Gfx*{H=T@Ffry)uCA|f@_d|~v7wi}t3~Fg z)%+^Ry))vnzjp2Qf^R}y9d=L$AO5v(p+B7Zk7-VUlT!-b(04T-f>=vW&Ymrep}5GL>eEZQZwYU0F8JJD^J*#>#O z2?+iE&5Z*qh#D+%WJnP3kwlyq&~k;S|V z?ci5koR#2GP;ayIB8*AQ-8MpFp70()>j91_DsPYVDhaE4Ps{X^l zxl8NR!nXI7NLarm^+7lF+_EJlDq$&a#+iYf->H$u_*1L&yF&+Vw(l)Y@wIQ;lNfqP zy160rsFf|9IR6_ge^-6(6r$|lv#*bt6Kfi2wPNaQ5Y4m|Dl)b;wpAl=cJ2b&p;hjI z(nA|j3m8h2=l%OH8?^gblus8d$w};H_c~@Ju1urCn*WS7dw%D(Ptih>7LF&Wl-6J= zW?yt-ESrdjsAJnpVygwi{Gq7E2Qfj}zLtjB6T^|_1ceT5L!8l!k4_!9!-UW}-MHsG z&eWHVIs3B5n2N(N34_==%4ZTT6oN}g#!m^ky2mT zOsB%d4SH-v!jVa+Eq{rcFYRPT>by!PKc{nWwXyS$P#0qT6g-yWG}h+*?S>HNR`QA= zc8eU)lyJOt9#_4&_BC2u0GR-0`UpQDKDG$8FNWA^7z?>JP6TqZGV|a`1E}D;12(Jq z{*xkS^!y!Pz*7-d*XpcirvKX5%-#Ke=@;J2G_m zb6@h`+@K0KCp2#kQ1^wHnLN%&wYCMcir_+G>0!EuPG-TZQ&q}iu$Y;1^jm(ewRE7A zr{!c%99kG@({K3kKb%LrvqD#JI#S30-HT$km)v|`Mn>2AFqYGtFm~X81~K~ z*xf)ryQLw#I!6L1Fx+?9(1FNJYh?Im6rJjrF5JfqXWGF(p74=#?#^`geCk*}L_B`+ zsN>azI%Sd@NLZ`+La;@weA71n6U@?oNi^7cy3JM0*MKiHd~$yjz!4g(U8M~Z3$|XL zQq%k%esc-pKTFC;j*P`AIIK#sVd~9jm$s;rV6h zuqdhtuv#bm&y$diarfrXz-L$ECV+}NFkI+xw^0f#(&EGrX^4p!%`+}0(Fdej zvO>HN(lHof%#4Kuf*u=mbd<&0#M8LQkgC`bsUP3`uQn~{TQ|-mu>#9+K}W*-S=AuZ zp89+=U57bJ5t-ncm?zX8=NPJyuMtCT_8nc35x?Wd^wkJ+=mTfkN1O#YQvcrobM{{M zC>|@5Vf<_Uh2zDSn_Smd$<9J{n8S`lBG#0yxKdL#+Yr#dLX^(ED-_#LlQ#lpC8%Ta zxMvkI6{e)NPb{DGr*N+Xv5)-K`4pO$3)<);#2%@ehbjoC=Z$NWR5vR!tzHN?Bgj*m zlh@ICY@ey~=T)J?ew?97jW&zu^!V}Adi2#sEOxCL+Rc;wL3ztErhEY?n$|?g8Q34< zf%lO2B{eT{7YLt#C_i8c>b9IHzQpiKs5rzIvy3V$9}l3U@x=q@JTBXIFfenR~z7xf|@!ko}86rv*)#K5bBO?cObos@g zWegt_8+M0ym$@v>cInk-Uw^w#!T0vRqBz1ut>;w71hj)`Zk>-hpCz~GwxDuOYL%ZD_<}S zzTV|^XMa+-wbz=W(}dPWYFBJ`1iwh!aJYL_oo(&mdApzTyib-V*s9mMvBn!eFN}M_ z=MCbgfiUGac3L7`Lqn5{}1Cy-xNg|dX;>tAj*YLf$3wAzh)^tsEXp?Yw#Y4Q~C zJD1fW^^aqrc746Cx`7?~oAk?_LbB&^!6-v^q~{=GyUxHdtOalBXNY>{;_m15KvwRA zf19{}7IPI(yd~N>v&AgTz>C|I>kYzFJlAtA4%|F8hsJ4=oBu|RR-P?d)4PTUg6G&|CG~PaSXfkcOH2)NC{FttB z7j=t6bH`>l24r{5Rgf$^e8m&TwA)EKdEQO5N+s_R;EtuAU)MxKd8WNJoSS$xvyG$q zxCDN**xGXws)~+`9%oIWnkpRDMY^>tMtKsJ8c_w&oS}58P^aMDNz*wS_I9s}VjEJ6 z-}mx2VAMXMp|_j71(BH0DZFj^!-i$xq3nmH3TfCkN?zyU-?XBs`C_UB6uhex`R&kW zn2kJw1tl`j1_721u|{?w$T-aMynbF1_-LD5cj3Z|=B@L>B809aU4%KtS>SC44k7gE z0gFWyLsW6UhD~!a<8Nhdk{zxf+Oh%9JSLi1`qOTTd-nAVhGc-_80m=a7?t{1vwz+7 z;a7JHfS5m7Llx7nsTolW&t8*Q+PAsNhpc5q>eZ0~-6T5Gu>$Aj{6vk48H88!i zl~*DPoKk6}#%tf4s{|)=gUB=_S`;KkB20S6&_6iV(gMRK2zYn@mB3qvG{}qx#82-`S{S;Zc0?gRtWy)EJbIfTUtQ7(Q**`l$j+Qx!c(j_c_`iJ9Rvts$NaGn@ly-WjO1=S zTF&|przOiW`QJZm$^DdViaNY^NDRZUa!p9C$8J?vkIV>2GkS#kvFqgvDPlk#V&$r8 zA1*Bib^dPLyh0d8alSziM|V1us}ydG+64ysxqiCgKXlp?HB(?X;?8+#8(*l?(WSaO zxw(HZ70Qx!JA96M;S*bFX12|Y)+jsHQ{A{&pcG@)6}bE(8Vw^zko(-DgAv1`98wT@ zq>5gv4mpSp40dFsmRNu1z&o57J7Pnf)Mjl-%*E-_&B?gEATCj3TC~!v8 zM8UQ+h2pA%BbBByll;R)_4lva&X)8K`(y#v=t%lY=~LbGJi>=x!l!6*el6n2l6(51 z-`^bon%2|A$*_+}5o;R`SI1Wtx$q65V++#6!T$Rb|1c(L5wV9!@iguf(gQWc3i!dM z&D&F#sY8K{7*UyddgH^#DVnzF!)rBna()T>!l?RM87Yi%zW={cNLv``&e`X%e_>uFN$zh}IkSAB+mNvB6ih-{_;2t}g6gQTYI}QgWcXA#7lNo^ zE4Iw5O-N!m>x*q$%!EsoO@fs9t_w}SJw9lM(*zwjeHHtl8}MbT`Pq|K+FN6^VvKQd z36XhCODqb>>X-D|ep3C+efQ4&Y&bZ8+WoxNVR^6WfI&kXWBN}mAulcdN6~plv-SRQ zJSb|E(%P#vsp z$$jqgeBR?F;%}Lwv`~6D^9QB14+IylP@goWSQQB z8*!Tn@^;_1EY2yB+J{~hK|nUPChf~-G+VU7Fw4$2@isx_I&+SQH^HXh#pCn@x{PiA zgzbmDJf**wRB(4ULCYPqcU(aTHq@K{K#y=l7$>RfanEI*N#!`TJhjcglV*6@sl+@Q zRi9VKXV18>d_l`VL0jL(?X&$8<+~NsSdIt(+~k|6q&~g^z#4Ap!k<}9p%+zo@{S_T{F-Km zi}zffk43;{n8y1*km&Ucnzh=+iwbqy3bBb}X2;jq%y|h7TjCiz@ z+~Z&}y}5yInFT{2kIuG!r1w1N-)q z$Vbe!KgYm;lw698X~lVsdQo?k*f7JqOnJH@NkUB3hzET1%a@q#4t>kpFuqpBHGYCi zQ-HWrC+l(#6MA@=<`?)qmZ?@j*Y{mk>=pSJpD+JBE~->tAT}cZYK-90`YB26QAZAv zQ2E+wTu%TW2IvI;+D`RFeAlABb?O7;&DW5Dq~Cvez4;ziz8n*sy4OqV3;Sw@%W2E;(}47RfT^7XrK0 z+nYSNVnYqA&@~6Bb8VNct86}hs&g?;>GB;fyVW2Xn)DBeDxcKYL6DYWu&|SJF2UCZfOeROjV8#dPVy1+YMtDVoKBHp-ZCKjSBNWj%BJ%n%Sgq#JAOe z*?+kG*|dNh*`;PnpuU)9nQ@&9|7OfXPC`YVS6TTFRX}^I=kaUtIGVC9KkEwCIy47z zP9*T8&Tb-qQ4QS9%wZLLx64wq(u%zVzT^LEZ!l(nd^^Aia5xp$>sBAYH? z9YSp8%pxh6_6Qkcv2EUHuHqdJtnJ^L0W5bF(9%m`+}G^D8_Ay!g*+c+BYrSmm3!ze z6KXFSxElz1D7;l3k#ihTsl8Lppksbj&n>0ZAX{YN)97#nO;NP>`(Gg!>N zcbnH?4T!U;FZ|cQjCKuW&#&>9`YE(zX<6&;0%#ZV6W55W2ofG=5)sGkG$7wcL=1|` znQ47&O#Hy>e5i!i=(i*9dt^ZFrF>k=r=?6>Apy%Jh6@4*nr=5#jSgxx%*!fHa~dzd z;kz?$W(s)`hkU2_H5IUdgVln+wDZ_y5C?NKXWwgy<I~0-&tDys=VoPYeUMuPr5hK9$=e~~J z%KcQQ5g~kl5C0`eYbl$zV4dv)w2CM%&*t1ous7D{6~@#DX?QFuM{OeT4t=K98xtq> ztb+?`va+XldNex>LdH!}ZlQ}uZUG?%v`L_CHdNTcBP4Y^l9l z9@@r+hOgSbBE653Gef)NVtdbUZ4QHSx@gU}|B{D7w>_?2WinfC#JerVqZVY!=rjuJ z<=s`oY3v$G2{|I35X=?7pSr7yq>C1NEAh;?K-rqJkx!fDPoQ>Dz!`)M`g2|I+eOno znb(3f-wBATfcmq)s@GRtbtu7jIaSXh-5IS3yL86-T$`^0Yj_y$+O$8 z+#gsPZn|^%@nuXQqMGGD5VP;&4(id~--=Y83wjb4^cVEI+9u~X-hZvKC_&8_xI(EW zv%C86+Lb&-pcJz~CDb2@_$oG9e~E^lKBuRbI%#Bse7g8YBFms5sbE$&Bd1y>=DKJ+ z(8x5?QyCBbj!n+)&n!8}=8`H9Gj|C@hpF9`NTIEUd9RyM2 z1F?{*k6=`l!qc}69tk5A;U<4LGjm?bi(VVd)2)a!@Ff|;YZ$oVS9Clw{Vmv=$Z}{> zvwVq!K6=qhNnIj-6^1Xz6Vw7zrG6H2N_IO98}i2+c2aN?o1)M9X|FNWO@+<3XTND( zz6XnDe#s2to~5sHj_7~)HZ?KEwl&+GnB^8F-Fa0;w!Y}g|LMlCp4^OLG|8WJYKz7{ zH(Sxdcf;THw=psM6U_u|t=2~|*7Y3dzN4h#j`~DR%5;;9&V7$D^))uFloiFQ@AY=6 z?|R~*{I1MZ6_)O5lUI$dvCh=bG74#{b+6ZvpO4dYCSRHxh(>h>Fg*igsC6W5m&kA%qIm(8y%(_=~m@nda*>S)5O<=@rjcsrc4BlWBg(Qj{h zY|8S~209~H>kf4>s(N<=kQ$>cJ%4EpSR_W z8Va3hcI#&710!iwZG0cGTL=v((S&uhnlZMuR>dxQdA+Rdu?<1nRJKX!mgkBl0=W9|o2`vKtK- zRf8@pADLLx8`hHMH{!c%2u6kw|{*8NR>FT>t>3h;AoNJx<=4Z{A^u}JF zJeQ$J)05(Ug|;$-JkUM1R@JQxNb(eHRs7KlJ}qq=aly06{qyStw*MxuP?P*}TA`N& zC3~Z`s*kBv?#Zi&nsjDS$u$uPfeA9|F6X)y@wh>*ZNiXY_Z9fXvf5s5OEHt(I%#hi z-T-(f3Q^6=+4(9j_#?q&yiqmt%oaFE#SP(ZSDz1mMnuO=pPyUu)!2`5eCf^Bv8kTA zbocq5Mu^SorjHnbO7H29mt*Ggy*E~xSrjz+hn-v{z9gA=-ROq4)UfN;!&$t5gF+w3JASgj zO!YH<|D7$T*GBPnTlkeh1NPBJL)BBE9%>=zRV9TZJKJ}B|9|f}&slgzcgJXIiv^w~ zSq8R53@^sp_uP#%X83$#LH83#cnl)6VSa}vceYoK*sS||=jA^(vpuN?E8g9mqO7>vzZ*M| zI^*L%F=x!eZzvb4KuejKPK=Ge|x0l|=0UrUnH32AkBa=KJ0bPTW3kp z@-SlxR~lEJM{^d;9tWl!;dPXh5Qankv1`-&D!Y_uTpOV75HVe3Zfq3Bym% zI3QAAwnBWL;GMY{b$d0du(G4t)1;R~xmqDs$+*t(Asz{PZezwD802?a0_l~ET3JO-97N1J^+);DH)wJLa8dfRK ziz^Zjd+RM0(~={#`-u@_=Ub*Wi?)}c1gW3~xL<$nhl>Q??W@{fIB|69stW;6hLBI1 zb>A1qSf81AnQVmvSXli}I0AG>IRDdRJ(OVNVR;%E=Slvj&-5rC$JoF5Udx>a2k{Ep z5qE^>dkxeJCdT%f&LeT`X5kEU^tv%LZj*M`ZOUX0-CGW5wAF+yhyUL1tjta~<>esMsC!Y8^2`}8IqnN#txFWSka)2)X zsCDCYhVZc5u$Hn2EPWIq#|j zOcBMX13C?cF;=}hLM~V^^Yml?VIWrZ zAn5UJUOU@fyOgPnp;eu!%-!?KCk<1H&b0jhh7x~tI`(&eNCG$N!NsRB)Qj)h(Om6` z70Zf&q*;S_i%nTjJqtKt<4zkeDm^+v&IfS^&9YH|t=WPXwBr8*kr;-P)vL=zs})TP zK*mCbd^L_a-jUj3|@=RbG}(^9HNRzvP+?s_IH zIuaaHl}VrOIJy-rzZ208Qs2DT?#M%cpz)VDj67<#FNa7hejf4$zQmJgHp+e~HasLY)*G{;b;M@)`imQX8tI8KTli-6!opzPaI;+g85 zKRf)65T~+&=h?!|>+gP*>_5hT32&F)4dm%X-9K+Swg9={3%PY!%Ld8{N|j26C7DUY z)|WNh-NR-62NJl*<0~OEHk4&1JR3j|_%1XKoDYaCc{Q%Z1O0XGsU1uKBs7Jg;Hbj7 zStmj8p9=h+S&B!LKOG)4c@y|7=)BMrUMP)C!W*~+5>O$4jj)RgYzMyCutkXwZ8d(^Q>P15b%%Q|lz}Ou*R)fN7qkUU2VdjFh z|L(2s?&8Gqtt4rl+yHp`e%?!V;9YQ|xI=JyMCnBND^LFs_A*-kAQ9&8S$sjQEwIE_ z?Dn;j)Rl=i3b?J-B@ch1l1;{EUji%8Bc;c-Nh(p_7S*~kmZKY{a?Cy=1TzVF|Mt_1-PJW1zsUYu@k#NdYd2cHYWF$j1QB0ZRR+0C%TtGc zwI|feqjt;^Zg~TbpT-U_{k%=+#SaYEt_x%UOper;!Cwb56|-N&O2kd6#|-7l3R1;w zzKCdwS(f1wuiP+uSFOS@l7dLe&OP9&*! zC7k)!CjI6YGJKJTYYEcl&)4m=hV#_0`$B(`w*ZoASeZ}2Nx;>&P?m}RhC`m$X2T{FY+b>9M_RIe5*b8}NPX}~uAOw#$x2?6-O8LIx*+=|*gVECizqDRT8V4|y_!cj0o#oZRhir*{i`2Vy z%{+$xK$YftF;w#}nL)hszo&i&5V7-X>abBl3%*5cP1T8=xW_|1WClda!9(3 z2V2Lp1=vi<>2mi#`A@VX`0{)iRZo4yP6u-JzL}Za|M4Xe?sxYU<|HqA`FbYk@muV@ zp#Jz@dl~F=+>sY=jSP=Z_&uFOHCyQ#Bz2b5j<`A-lg&3DA{tYq$W{L@*B#%63k2Q2 z8)9Qx5aBA^pvsrAD<8WzfS_dl5IfGjwk#E;dq`unaw53uk@F3#moer|Ac z;;Kc{7pMynJXOI<2|s-3?*XZUpvA zQ5Dg!S|`v{X~)Wwqk+j&-0x$+Czs>&p&fVzDoZ0A?!L@Sl+ja z^S0m#P-^s5Qukkgl8cLv?aX1=eM1Y^r4k+$qIKa+Anw70lDrJY1QtWVCTOj6B!UWB z;WX6cQM`9aJ!m~4eZ2vczn%S7N?Cqrb;mzH3cZR6;tzO^iQcGsV3(nM(aXv*b>VW@ zW=`i6L983nESMlI5~;v3c9IPZ1%952}*IAb=mXJ?bP@fdT4) zjPF6P*{9NeV(XZ?c*I&rxR$-4JJ-?^Q26MvhDEPK_yfcnHeiNhkC?}Xf}B;$i28BY?)U2RW}< z>!2#OG?7lW&?|@xEgQ>x%t3cqWo5C^f#HILwX-1|J}qbw`cp-TgQQThhe!t&u4;bUuYkTSy<>L(leB}Nq5XG^F6=iPc2>-t_-1so!i!>SLQj57 z4}%nUc{k$kVPwE_dGH*DJ3%`L*!M ziEwYcmwfuI>$7*H;watANVMH;!X4kPq!C}cWQZn{-SmvVP0IJ?XEK6obS>}u(rIX8{Y@F$5i#*jy7lMK&>;tveDbH?I~|pr|I8;qG`FSCzom+^ zkNCABQ!m9pz))$YhUKA^yMz$g*SB*xNvuUszoB7~Bs3F(`6Nm2#0AyeiUWHXc|g6- z>L8PYU|#^mfP&E#mf8;;X6by~mtNhORQK$N^f|gE1k}AxSRQlby}rVHF0i{~6^Jr* z0^nXz|jph#fKcr{AubmJl`H%m>Z10>) zh0&?qoVN8-wW}4CpG-iQPi?B@`J1@BEihs$CsO=}+4tSF2iTdVr%}q0({ScvdP{|+ zs9PX-7_y5g6vb*nb-UeL?u!W$-&UD>jTHsJpIm}>mDoGT$}7hT0-0U&Y95Td!Zm_6 z1#$N;;B|IUr=mTI^Y;FPwUbNHi=+DQIF;!iR@3u$4U?b4rMLfh#v1e(7y;%Gf2Rj^ zOVw&6{@|g__?E|<7YMYwy42=ngN0RY!xv}gfZ-pN0$d7~LuH%&?~t#*Cb$O*PnL*p z`PJ8y?6cB@Z+jY=2iLy8d}m?a1hR=;31x3;`uA^e?rhUxv8;z>O}N_aw0O|OhAqNm zqoV@$A?HuTAt(swx#*Is>acGk`_$^B4L5RXn_i;2pGxoaLGAM2hMhIhKgQFe_~Gn$tV-spSLOPM^$Rxy*kWAM$fsR2N*ujXrp2h&u>+ ziLDNxm;!waswd+TW~ocBqo0igl=}sA;&n26j9O#zy6>pbrmZ4C#@!sxy(j$M1u)Q8 zj5^n5hSIHH%v4B}AYqh?n2^3rmla#al!{5SB=`686f$N4Z(V8c*g76ILpxMECb$h2 zbl){VKPKMJbiIZndveLmF2jJecKPd`43_4==aF+XMK=1Nf1F zjIvJ8wkXqUQ#qYE-6hG-xf|rXPd=3a6Cps72nh~QoffZnw8q`jMkG5*tNrKgx@NqH zO2cv{pYX_d-{VCJ^j7-)PClX!Y=Rg(tOzt`gFBATDS+F8*Y1x=?^S~vvofj5FbD4+ zZoYkquzofBgAN;&38x?-+}rWvR;zs58AgTQ4TxU{v?8YE+xoVtM{<8jnX6JI&b|)2 zMcpd(WQrAT0nr@Zz2P5bdstF>-y($)@!txxm@-t=260GTS)1JX>@CQ+Xh2E2aXzFy#j6eWW=Y#;0r`qg}aF| zPa?TVIBSM^TazTzyKm>Y?I?o2njFz^F+tTGA3JC zrsw_{zn0QEXVe`_^XAdL=bduY^2GAjHwJ)Fp?dZ30=2jy*|W$-xsrp)UbUZfHBloI z+jIU!pZ9h1hosUOoe7)pFomnb_GP(0HA$BdOPc`kj?8**kFOe2nxgP|B~(-8}J z5)O*Av9B-|aBs$EZJ%9JWrBjAV)d3UH>uU#_+B2yjl!mn&B~AOlRtj2Bo*gi>n8=} zcF38rIeLWhzk6(R*i^a4NL1p26r`Nr{Y~$=%Vw_ZSW08ALOgEv1>rUdqo@ZaVNYLjxkZemD;xxocY&5M)*orH{=(`em+(1 z({ctIhzN6QR3)wE>4zq!Z^XfhyZ4zxjbhP=-f@g8=GCRz$$}#G`q>~S^JjO^06jwd zO!}E!Y#$<9mTltG3s*K0)G@)n-h^&_d`S)#=o%1!S>{Bu)l{tZcPvD}ulxi`wjr8M z`JJ)O(RTJ4a9)k3#Lb^}W(0(I!HX@=S^?Ad+NU(sv#s-Z3S~}xIxT^xacjq!eb1?R z)ldG!`it_duY)c{n@k8huY;u-HqS@pmBH2z`RlcMo8xZXh}_Z4@0)cj2?~R(15^SY9z-v-d7NuzF#8o*GG+|iOer_S096p znH7+kE`#v@K*p<&Ro8I?FJHaCuTSvnoSWcJzuS2ge+K6ntwVaibWaoga@WOvQ2L2+ z2Hk=ZiFverX3T*64f=Y$E@{`~sa46oUr?R*QCpgsTs?&k`OT)s#h$5h?G>BCEa=F3 z%oi*OakQyIe)6)g;+!#KnCq>GLBRf5KGn(xwO`^IS)>(~^#3gM zYMaJ7e9VI~R1`cPjWbAc10dmQ+ht2fLgifFxU@ORLys=tN*KL-+IqE#{tlk3xrIPA zf;cVhB8YwQ0bgqLX5o3lLmG;cp9D-biT#14OQtc8ss~s3V}8BDdoccdFGMs+olQVK zP@yh~zv7er>cg`iw-b1WuCA1jpo_LZ2Qi2g^OOB9kGP0TR?*2x0L7i%NauoWQP&d< zqj)*AiJND*ZgV^8=T%T-D6Jp2;s{$}ewc6O?lwp-7ax>jY6KtpEauFj{*K-)+ijLX z9>gM>G5Kxj)%JZWt)*h@a!vBC^mcB8li_b$iwxnx#YPK`N#<;~j7Q@$qQ}lq3&j?+ zbDaYcL9&4G@b_hh-+PaLZLyb~>AeRjPyoQAA!az;=|hfbuOn}SRugYZSm@Aj4l?kU zAhQKSXJy14Njj26PzPOEwVtIVwX)qmO<1owlDp`P67E-JOM#voIbpQ|tQ#@QrM8UE z8eqBewhdsLC^G3cykVf@z{VwG?$AWI#$6mzfeJZN6JCNAq?*ifagx0MiZX@w(@~o& zxJPSsE|VB}MQqv1pc>QIo$^L?hDXM8Z!(QXL-Ot5US-_SZSB!%P9K1_KIw{Q+Xqw1 zsk%Kr`?w~%m^!!kh2vgWCt%N-C9!kkpBsU1aOKa9OHlhY<@QeAq&vPI^aHc zpox3S0EfZ5JjmOJWSl?n^b9aQtTA&(6YX=89adFy7X1o9S~ScJ8K~t}w$~RkQ$41g z-f;3cT_UODkX4?yZzzDSZ^z9y?gLVrQpZ^=MZI{)=rFax;e29e)Dogf4v)0pTjfZR zkpITKnG}SA&HVE#PoiS&F$v3zs+iV~>(aDoshh?$A z?0|4Maa^NwtN$f?ht4@-J{0N6RyP^I_@xq7{d@8OB4zvTTw&>WwIOkl9!T{1ho@kL zf`$p!^{#pdr(7ULwlO8nI()O&*^`lyltOv+fi9kr&FGRdkbgr%7qPk zP65$_cabJDqJp|%8o41)GG@oDzKVQ!q6^m&P}Uus6uw| zE$>Cu9Z9YSJ$iep6O_>9cL~3~s(KAPSS`WxD~tU)I1zMVnM6^!Ozq5{LUY?A#PZ5e zfu^75jsEOm7wWfQC|j+56Ox}tC42U5tN^>6lm*kq@V&UkelY2oC>Ycj{`L8SP;!>G zmF=h`!(~dX5$`qsp>I>sKjUbjgkMuH#`Jiw6dymtWb(KS%i6KfT>W#gxQWF0r%kZS zF_+$%c04upEIe78>?nkHDAcmWKpx5o<||jK`WKlPZxa1oYIk1A!W+2DPC0@- z3X*g%(*EM76kdP${nO3wS*?+s z&G^YkP-N?SCAP3m<;k3e%#!~1$y>THCYe^y!dk7Fw+b;g+Hd}O-ad6B4JKw_yQ{R{ znlAhqAZhv<=q{^CrawD1<5B0aCE1xU*;Vrn>kpcpjSafK4pvOY zhBn5|hG}tuH6|~G+3H6Ekw2cvM+m-$-;dHp7YB8o_ge0k(Mfbp&xed(*fl7H5}toX z99TFY<=gI;Qt6aP>MM+8Ek=FKuhnf0V$E_4OrvQlXX9^1FQQ96t+9PKqtv+OM#6!J zBI`3ucJ>1_GnLWrW6FoGSTrcoxo-?+b1alWcu86wdk}8896=m%l7X5v#u!(D=$#i07W^Yof&(=cgqo8yds)sX^tx62twGf)P zQdt)KMO$~Kof9|ph2Je}@as9BB!(*Lk?G#@E zr497<&YBM49s`qahw!cb)t}C;FjiZo)h)L0LUXV^MV`4yOjfAqp}K6JOOwaI zpqx*I1)bA3$)x{4!(>|?*>&zrofOlKY4Q);0bsou@00+A!;6#e%iKQ}4JpAII;p=u zXsbx_i~LdHir}Q^&Q0n4rJ8w6P`qcNS6|Y+@9_v%(gipAcQ=09e=aSxIrCs2Qtj}; z-t>oDk>Z(W<>zr#;c%jbqIL(xZMet_&;>_kpo55i&U44l=Qph3(OxpeT^Hi{jS+_f zf4;PMllc^a4!9HP0nAKx+ktqB!q``~mh6ajQ3F2C&yM(~fG^4{Nc{ahqGdnlMGtq!C|`Co%2?|K~G0guBM3{(f%On|J6{g$Ru|KIt3sNIocU%ts1MQ!D%3{e^0rR_M;(xp-b?>qaRt1V-5kp1EU*O`p z70>6h1K)bu?Ccy7VxQo+Z-3<_9rR|vF1;J^9`2{&u{WEtf;ulZcGNP+3MV-8cdgQ{D1v2TEE5-RGE%3DfWn#w{ffKV#igQ{ zAhO_qbNwZu`L27CdS+0Lh4w1m^`WWqB2*4rmTMj3UZX8y!xjVUoEc@#W{usje#c-q zl6a0xZl??g@&d9bv7A@$?2H_05OSr7NB64DUGc*A!yCr+?A*5x< z=0X^#cfQsKn&DPrq$N ztLl0>@{Il8F`!B*H3$@K{m3QUda_ov#IUO^ew3ko)KrAKKfyf-vvY8wLl!KTk0jUz zu}b>&j^2CyV3;PQ=FJD2d!+=~YRtfFKaLI6)L}sx{2z!ZNY){Tst^IiTvt%FnFgK-#bhh@q6Z^Kdol@Kah<^tk_LhkEWYn zn3{Du6-kmI<;Y>LS@pF+u3oj4LG|d@B8ujmf2+M6nCHt4ag_mFC3ho$jorA%iDvR` zg`Lq|glu2w{I|JsGX9Ca&1{jiBS%Ro_O_D^$wM?&=585Gf}9n=Jrc;;FwT;yi|fc& zeoW^&^jJNt2`R|m;*`$96cZCOdzy92}kx{l02+#nMthhCIXcgz@Ue@9JS_Af6%qItU;7=W_#Ei?&sH2CO?Z2bG> zI}KI{8nF3pq{*AC&J{1h%g07bB1=3U=<$!uA#HWSO5;qMFf8a!o+Sj6iEVR8?>PT$ z=^uR$Cd<61X2~zCg{9eqRbK`1V?uMgkp4e`%HG-b+K`EPJ%Z z5b5m%2BFmol*z$RMmZ1WA$Ozgr0AV*Pv(nvgV@6-;3HDsxh`rGOf@8zJ7%s;CRjck*9Oy~h`!vdg zC^Lf$te32(13y33L+LHBav7h|9A5g^K#L@+`?^hnpSU0>iKW6%7 zlPxtT%j@J?lydAH^gL*AwcaN<0Gx|cPP_C)!J})nA2S>uRpA8rR;Z?pEmt7P(zV&o zow+_^dwEEQ@}53M1-YZrBD`E;+3G5r(6Xi(#yM0_xRHNZ2x6<2YM+;}$A!B8!@Y1q zHQG0{`20beB4 zNTNDoYGbuzQ796@>*5-)K0= zBczN?rTWgZBz>A=7Zb?pg59Lag76ZD^-IyLE?3dXMb^2ia>N`^TMnVq>Y%NW->#+% zK5t^=f1~W-OPi3a@%o)2C%#p!mrsyIEQ2mcq?kj#BfOPqJ%?sFRjONifm{{X{v)V$WqC)kI|6)oV0MX;-ny z0wnL@pxl~l|L9$-oO6ucR1Td?=^k?H`6c*0Dvz%y3W560bGXH{gzLs!A+e)MSavo- zQDrY%Mjc7eihUUAzib(bRSh&H)d3qrT@{n+x(oI4(%TAE7s8TMF{B zbo>7YVgUDLktr#CcHx{YO<2;l6wsrX-?R1d9O&>Qeok`6l; zrjHnZ!|7TVaF6Kzp`+L$zcuz`(c!KjP+q&8{lZc+^&j+-8A;&2NJ8V8~v;5 zm*p&mjj>IezB<%zs$KYC-)6T~!z!vO%{gB$niJ`idYooDfdUVcR43Y(Z-2ED26Y?R zbb;wH@Jp|jwwfjkY<*d_yO{--{iJTDyw&*fE2Wp4odW~WjI4t(} z7eOFhC}F*4pQ?5KlKo(Jc{Vim2Gsqcl1%LyIYS$BtpE8F5T7Rm@|ht&paknxk>aZ% zD`KV|eRl+t7wXjV1TPx_UDsdZPuyV4i^s=9XZt>hB19=xdVeB+4&xPk%eb8Y{#6^w zy(W0rg(aO2nq82Irv^$TsRDrA16g5PW0UABt0*!_yKS}ZMde2t$YnfkQZm=oVK|P) zW38(DBzzV1UXaDMop#zOK&gYI~5v_XJg~=+wfV*WPE+w+c?KLfgYQFd=IqJnEr7x@7 zDBml0OW{%39{NLb19)PH?`tAgAKZ<0PyqWkm#;JRH&tI17%-_j%2u_?-e;c6)V5ze z1ef&V7Dt_eE&O?As=Vlv_EsblF{4N@MbKi$pPi#B?xQf2QfJW9j{0cbmd4n^+K@fL z3KvV!6=N;2rpoT}O4Ik_)KOHINu)WeK%ewg_bNWDORK};|8ejxb+EN83~Yk3itS}w zN#?USny@pTT3vX{814pa!Bn#v`F1PI1_$mww9{fV*YEPyS(t#0z+qeYfx|lZk%_Oq zk#|@zqL4NrPxG&M6!e$jD_&_XZ*pqI9q{Z9j%u+R!r1Dt-a&_fZ%8DUVSqX_4b&$D zt+727oG1-eQn1`t+x$J~BUNpK{>&a95~P+Mtg|>MZ4kk$qx>qbF7a9#%NsPGQ`68b z_%(lhcCf(~}02 zWL!HQCiQB~e=n8w;Y_P8GK+L*5zFpEY3FLEz$RD;iFC|QH6$DLa{rwDTDs9GxN2ww z#^Du9+2xl~DaWIdp>O#4Z`OL!itYIzw+Fc_lU-+oIday$QUtFG@KMflcYeZaxXo&( z-p%F-;n(mFl)&~!lFwODuFGD>wvIl6J#2`a5$ORrZ_du5Qt=DHkC?@1%W(&Bn2>Dk zG(EV1_xtNR;(Ck)^0Hzh{;NfgkxL&CV6H4E5nRwQrvE&NY%sQF(&=9uqAF-k4lcJ! z$n9xibwCSVqB<~Ls4BzpHB7o|MtEDH$*_k*RTq7vxG}F<#`@~f`(luZ@zOmVnYFBZ zq9?F7H}LoXQJUDg`k%jF(uyj4AG2|Hijd)(vN3(P`bA$h_$O9qyr$&(bF2NNOdbfd zz)7wdaPTAqFuBRY!ww&8W;=Bo_a-y%T$Kh(DPWstHA7T*&kXKJ8nDXo@j=X(Z#8P1 zX&UI%zkg!RYaIq@DYCxWmnx*3#~-~%Z>V6nQ3mjK?uKT_5sU(=sWbaKLduN)yDAlU zc~!Ku(l7A{@^{NbH^Nt3Zm2dXo~L8E8mLBI;Rs~)C|HjZ{PMR{K(DPPMh9Yj1LkrH zqzwNLepa@?DYi+C}|DGiZUQZ7%@6Ng66&R0RnmIPt+hPGbCWVsVi5 zp9p4$$$@%ew=F9&lF>B9qsa)c~8?c zi`%EF;kEMq8WP_w{VK|b>+%fZpv$hpDTBn|oVEb%4K~cPjzhf-7V|(0Q_SbQilwnp z&V;T_2KtK?jwj3)()8d|a5$I(=Y~EBcGhtraF9uj;B#q%)tm_Mj~%;e^xqk?&RIT* zlQCEUlY-Z(R~z6xMRAiF=);VB4uYX+C$nbVIKQGK%*Ezx|E-%7CrnE&wHDHh*xTvr z04b0M^+8Ai^w80O)@@b5Mr8}^8zmCET<#LxvWn{I{E}a={ z-}o#Pcb1Gy+VXp;LSAddG9a$r{DAvSqI_^PYm$eVDE02e%JBAGD^aPET;OqU$M$UdlzVVT5XkLA1trfP9fg zC8LDCrn=xj*XEJ&CL$N%21!T_;%t*FQeOA?WfuMQY9sYVe+)!cKPMBY0ISJdl_}cUR#VTn9}OYQ3~tTH(hm>(HUhn zc)KmWPV91yV&Hg3E3UjNI=9ooaFC>4xW`5*7g)M$z{*`e$!#k9cw5hm&UMY~QRB`O zxm!$BpKp2C@A<5WC1Ju1=TPEo*)@vCp5>Janm<2Lpu_W!{1B{BFI-NmJlVLKiBoqd zwwEgY9q+5vUNZmB-o;-y8>Q8Jt*+xoUUsnvfsW404f)Sk!5rR~*FzMp!4zr)^g1sQ zZORTdu9HfauX)DPtdm{Y1Y~Y@;sOI5c&gpwVlISet~o39{u${1bAi>?;x9OEBwWT_ zBH%1eL#!m*?P;jAqXMik4*VyMUl1-6Gv41tSoa?&1;)DEv^f^DNg;f8w$e(V8@1p4 znSV+|rPM8r9<)a7Luu4RzK~ktEOwFOseP3aywHxUUPM=kNZAN_YwXObek+PlA5V@x z^~RM4Wnm=mNKLVNmc(2E=c&nUU!$bPn`nH2sh#5ux!Da!1eeoO>OKpC zZ9GMJ6(JbG&Bc0~%A(ffvDde{pXnS?YpS)*3@TFH9gZ}6*_#wnRW5`oVoC4y6}T1P zANsWy^pagpz`DRm3K7#m79^_rdo@7pUsYa9_~Na?)w|aXtJ2oj?BOCGUeNOm2OAd! z1i6Yeys5As{PEqgiA78O{9s?kr_7JX{(W(XLypX&UPYVhhm@D<8%sCLx;AVN3+tOE zdtRm768waleQW1o3$5LAhkxI~DHhe&{EF6mSIL=dOTI|;VUxL< z8E@%=%?NYStH9Vsp3uedpqM_Tf98J_opo4~Zy&``P*l2`fuM+VH&c-oP*57CAT8ZF zLb^dfsezOr-936BCEYnXH;^%4?DszJU;A^{u4ngi-}m{R^EsB?0jw9Sy#K1&KTTD6 z%$J02Q0s^gynH63^3nIL^s-DBSKRg7hjs9LDsl~x_`m^9qsX)`d6?(pFsh}b3(q>5 z;Ob`{<#&xQxBkd@f9dQ*PRfb2;0I#lIPa)D5TKqA?W0tK6`6yEG7$s7vDnM_G)_Xn z{7_3v>22H}{$s$`k|2S^c3aMOYP;O?m+BUx2@pfW`)`CIL3ICaBOzIXO|4VoX^oaG z!6NH%uHEBA|M~*~8v>CVN-=R0I^TM(GrN&+z>8C^AeLS~ZcUcDvlN2Jt17>MFPvhW zZgV6wVT%j~Q+XyUoS!o%iYyRg^DZ@luI>LAiAl_Z#JKaLV=y%>m)SgpWve^vP!fm%pFcB!ZC_0z-0iTfleqYQ7^Nrke8_&TH*LscIA*z zNKXXyjR0!h>@)N>MaTrhWgL&%!M6J9uApuB>OqEw z%RR&!1}9M+J%oE|_MCiyVzRq41X{mmyErgttiEIM;Z=M|N#$vk6O_tuPE2Xnmw{}DCcb&>4xtQ& z7~WuB*Rjt3jzRz$b%AUdhrC1hP00Nj&{p|Dl1)i3XcdQ4Si-vq72KzI&Q6UR-}y$3 z3d>^^+Rt4@oLfRToiI}+nJ(&Jk}X*!?B&_cvF)~ON#Iu{ z1GL63*fg3%td?^h<*SX!R-eWZ_+A@8f2qCuUi(|{J=uDk7w4^r={LmNWq0P2pdvMy zT}IBA<4gp(xoO{EuhtX1D2~pUoES?9<+qZ@A>-&v+M3QE%x&!zEkAq+b_rQwZ=kss zB~CW?-zFhAEt9!Kz9f9_>Kao4lTXKbx|0^oPFdVlqWbG`5QunrJzeo3c1v{%TDx{k z<#_`Rcoo@iVAwucId^oKoPQ6O=ktu9o8x?r?z&;KiU{8et8$-o(2 z=_l(HSI#tN4_IvoHsN;{_lmxIszhg>h*GwvkDGcBPBlDPxh?E`Z^vi~1t9WVl{(ND zcP=DuK!iTMCcML|@8WxUX(HjGU*~#m`v2V|?!ifek{ZtVi%r2lK9*Vv2P_}td_ZZo zLv%F#jE`ycf~iy3|F&rTOB$4|R8$eYz==cWYrwk~x#eaXad;k7G_FI+b(Q?i)i-(z9 zK=QvU;>k`x!hL4p)+%ACQUCibTofayyW^V3XP|k6neyigTC`iE!_$M0r=;Q{I!f4h z|Aj^e@FWfj(%cI;Iv&4~DIX`po_7o5mzX2t3unK;Yj&b%oJrAFGK+cl0*-Hi`W{t> zymCxIfJ0Ak3lp0^1!SN@Oe1EV^9T7HU-~OWh`G!JG0-w8QONm#1 z`@|%#*AFqU6W`o$-mY_KxefAhFo@84x;l&K60 z0?Tmuk6V@v9u|s8hCi$g0|p}KR2S68#yq(T7afk(&x!(R^>ZT|;;s!X*py%*3r+7Lyq-g#pfPD~ zO>reA6pyA|!K_dG&E$$R=QLq3A1E?DAPu=^;gZz%37t7zB)7QVqFh`)lclJJwb@9F z8bvo_3kH}?F?d(66bOG*$a7)Bz%{3aOA`@}vJik?llcLD4c-hX++Lk5eKl z4dEcH^f$=bl!{98iKWw|(T}q`dnK$PXDsL3l)vc%-|P<(LcATA?d?gdEn(IWh70jK zJ3t(doe&yxn)GjALen2W$0lNm^IN+$Rpi)sr2nz#L`ls^3*%yBa-#kDDFODk{+yEz ztmS!nJM3=ey=Vgnioh8xLqm9gxl+YU>uGCc!p?02&GB$}tbm7Mc^M(*c%Kh=wYPqFsq zQ406^PW$Dic5vow82)s>RRWo0& zH5b-hHV5rZ<#63)%KNTeTjXhkCc{oYpHV!zuO&J8H#$~ZlWLjNQUW)UmUxK&V1e1o z3kzllOI_Y9it%~1ofVe*AHmoU09PhB%V_!!b5TO#Q=rS{tB6DE4b4Zg_X)Vu{`v6U z&&@tAd89Csi*em=daOs{V=r;#O9Wl?FUYS%ADQm)fZ*rZY?XXQ>732focFW|Y0LvR zbtom0MV8jv*veXVQDv8_+_Bo#=Q|d}Bfa}ruS(}0uS>-zGX}<;a*v5GEm^ZIT7Ij4 z@n^J`bvIF(^pLK4oFH=|Dt0b>DKXt~W}*@>KQ`jxH=XjjChw8hfZu-vvLoLMq`qz4 zO#90{ewu3atuw)s({u|da}fAk;T860B&Pd60>zmSxxC>#9#AAQGj9==a|S>n{qPbU z^-qPTm$l587hlU42IMZ!9;erH$D8I#-rs4TM1ZecZVR)3ZtXs`m`DD^8-BOwng&4+;0Nb7YDc z{`rTqxz8t9j+z?zjd_ydzfr;6eM`q*vO)#qq{nGot+|3h3KrQG+n|I_X`C=K&{=QT}x zRr8iy$T?LKfdm?S4B&`~W^Rjv?jOGMfpkf(K0u%RaFK6QkkXw7*EaM&DjT4)Hqynv zHtTDRS|YGA-A>$3FW8V%PkccO^a|~p(sq)eg7VQOz&JQpps(-l>)jN! zqcEkGYcEeEIbYGuGaUcm9U!yQYXzL&Xh6F^;Ji^kjS8lNC`@%&WE|x7FFdrQWV+(F zLK$+%-3-M)3QL>KO9R~JJV5Y*CcqlV6Xe;Dnm263z4rooH##1Pk%g=bGEi63tQ>zy zBYhlyey-vU34HZ4r9;XiKu|1~;xbbV@cgcqfa;qfpteHM*Tg-EU!@*`!*B%W>C^No zX%Y(BI?1aHLXl1Nuh0=3(NFl_2M0HWnnQpe(sUcqu3EVenW&E)`d#()iyCR4E%Qq$ zzjk+mY9D>HMk+4{%CST>sn($?e>~rwH-Du(RwM7T(RazM${}B8k|GuYvms+Qc6xJl zUFVh=eSp6^4Ygj22qIOKtbsd#Dfg}|?EM0VyZM$IwwQcy%g++tiLD2IV?BCOOTl&i z=syDdBfgtA0p3#$(C|))nJ<7B+91W~g2j=ZNx-r-Q~z9$D_u2tVO^9a3U3-0$?XcM zgw21A<&gXxo3$JU9TX-qiGDg@fwjJmr;GPsf3_@)<>+izR*VudARIqKEI&1+%q1VH`-rgoh zkEb6pusmUWJNzF3|Ae;Jz?x{~9fE&16d2dr5d1Tr;T|tAtvruHah*fyo)mN3go(=M zK>6qR9nGep#qL@&pR;a)>`dGt$}Bx$4s(6)Xl`e)<-EAbFzzs|=UY6MQ+v|eYiMiT z;NJ(d9@6eM1h|IZ>b$y54|thx0`VEw37ynb697yevNCrATTYJW`yb2Yxw7`WEsEkV zjANUw$RE|tf{R=cqQmeHchL;%O}$z)m=yH0`kBoc%SYEm*-FX`5byxSyLrbw6(T53P8rX55y#P)a#rRQkKt z&Q9Q&dD@xtHe!F5;dD_a;kR`K`@{6GvLVXE^}JbRh@+<9h83Ex-*GSR*#ha;pV8n4m@GoYR384GWz3P2bZ9+B;j*9 z%jjUfIM<3U#e2!?cj}@KuI#u%|FOvMVI(D$&73t`cey9uD(%x z6OmJs!1W%qMud?a&s;_dm?Jdxzb*E2l8JjQ%?~6txn&p*>H$1ZUdgP#@p?5k&No!p zaSRkISBCxF2PbHU2*q-?mK z|Ar7EWGxDGTm{CS&=v>J(=ep!dk@0x2wC$VA3pV$e+1^)$rp6Pw#UB!?A}Y%! zQ*{$YJ>+i&GD|}1btvQcHc!9er2^R6lRtn?{IyUsumbdQ6u1oOG zz+b@${})aM_?Nw~00p3m(bli$Kypqtydg4r=&#U{*4GIC?1<(^)jgz>yy1-me?|u! z&ipav*bZQzOFSoUL=lc>40w(HO7Dg6-17DwEq}=oKTRE5TCpA~p<9|Xd=C3YtpZm1 z|0co|@F`<}+J3Db)O#$nsW1?hzkmH1!~CzdkUyzCgPhusZiG6+^V_#BU%H2EBInIx zWZecugXoV&yog+Z>$I25eCYDHZ1ddAN7# z@A=89+_p&{&uQyyQ=ci_mt^Q$%P;n7(gOOd+}>MSX(|qDSBg{rYk`fw(ZUWJpxCq4 zDdK6C$2UCDPHDbnJxO-)Z1Kg#XG=!4i^jvW5OKYcPB(Qpm1yJXNELzo|9gs}jsMuq z!HC;^QM)GAo(_o*4;wQ(%8mG!O%A0Wi_~ZPD%lYLnDKvRz_Xu3pB}}c{4uuZYyspr z)d8Neab{K1VZ~Cjvti~aswPIVy1J%mEc65W zg^ih7s~O@>XYK69!bzReqWwJ--{!ii?H`hDH-=DCHa*cb9J-Qkk}Kq?c_1Udo7e+4 z1lv(8FklvMe|7TOuhHQY1k=#Qqkrv;U+02m>y0FcCdzknjvRMuh_w@#@)N!+KTvYY zSq^5fPfRYpjfdKSNDncc4`&rYK9Rkbmj<)UwvL*b?f2Cs_|od*3zE5Px8HkH2#2hs z3#*MYUD|7E=?w1o%g7NQjRvA*ZxDX4Zk;Ft26Ku@d2cJlRI4)M1BN6cJNCypX&x22 z2eUHt4=wGW6O~UgB}EDb`pPX-KvIANp^TR5reHn27IZ#yY&0Sc?mG^Cjus;hgr(?*yY6!xA16l2M4J-x04O3T$PlS zuy4_6MoMxYVW~_K1N$(Rb}HZtWFbAyOT^040qVuJltsCbn;p!`I&^!DZ4m;QMnkds zQ-AL?E*^?1H<9e5HRt_J%yk&60y9nc=$RDPQ!z?j@|g)?wY?^o;+HhC2OMP zEdMLNvi>SZ<6+?fwOXBUe3}Xq3lRR4yDb2O`qSt&7De*40K(K)^-~~n`uW2j9K2Oi zxoFBI85HESYm|ggzm^$%!!CQPgn4wE51ch-k^Pw&VIDd)d3w-NAGnsLe$#%(ZsJ%H zZFe`7q{^M$%t^||5zpsxhQK*0^bOXeOA^*7(OI`S3elRJdi~dv<+n@&->+lBHTCT! zC01*dwN!&R!voRheWRj{6L!>8lZ!SgWov$(qYyoHa0&ATo zy|u4@-7O4C^s@mkJ%K7qp~%WgaX#fAKip~cy>!d( zE((_=D?e6iCIWvyIl|5qZWlbx?wDEvj;KGOlwW|8%wpAMWPJMry?0Iczmn;?e0`Sb z4kpijCIy7ZSMwOek`msHhZ$q4qG6QcAgTZe3a~Ps&fjdpgDofjtv$5OWdn3;JxFKj z>uLE4!TTdx&YsS7zL`dkk`Cxz$VW)yCTA~9G_j{o;@Z#5Mu8g5OOV*8_}HX;V#u(3 z!qJFd9sA5N5Y>lU=)}MpDIzbjsv;+h>^eb{>6&u44sUaaT(u-hMS5wUYYuUWA{O4? z2Z;&unU9&o{{EWnN(doRGTqc=AA8Fo&rge$784@T{I z3+Y+BNVUtj4m?V~wBDT5`H_EPn!a=XiP8G;`YE1kjAF@V^|3WmI_TiS<^-1Q;v9PQ zR26b4t>%AScmt`qFu+ltV;WGGN2#0f_Pd+$Q-N8!f2oQ;jO}|qpcQ`ek%p^=OPakT zvudM?4%qmb#-s5v*fpcMQ*oh(&>k5_*G)!#j+h<)EZfTLy=$$iY%kRvGd}TJ*2j5r zz4!kB3`QwUn_qH$V^c#d;~Y7KPM70X{r;y%O*clS_~ELG;a~jcSoeXX#eKhq_BSL5 zwzl?YcUGI*&&l;)X$M!oTJqC^e)OXwL@UimYw=qWO&9a$&F*`by;wo9e%BGZH3oB$ z*uZc8UL6_BiTlp@hqoL1P)qo{29z8N>yZV=fDEQCptKO<*Id(zQ~m*vBlV{jE1VIF z(m&1bzuLVEkA%{!eQSw7c|`(yV%ZvBK*hKtLmlu{a9O=Y1Kq^fwG@MI32?qK59)){ z1n@n$&BnP@J6va1Bkreie*W>JC&lUmiO51Ve(%}8F9Z%}6aTjqh0A6{L;70BQkt$~ z?eBe^yl=?9v#Bo%PW_APYouV>tq5|3NJTIUerSa)vJ!8k+x2}wstQEJdQX62*h$;b zpkRsb?Vn0aPSfXhfjM}<%fvgiU7Uv@W5N#U(}JfL9lFT(ow`m!+`ff9;lqRd^T8tZ zpHak4VvxCrDil|5(BtMwJjif=@guw?l+VG$NJFJAGys0#!$iJ(A2WC#&Hw~mz<^Dm zANCc_DgmOfrLQ(w9H#YlG0qA;WpxkjkxzTnC9Lp()1UoRU~I-mwoE|TE+|8BDiOz$ zt7M)_aY&V8$5-aCxovE|l6*FPw0$EPpnY40v$8|YZ8Q{KQhyH^+BVFoIR2>ez^2t_ zfGbMI@RAibx_lpTaN6UHeF7V(n!m(EqY!bOl8gIut>kGXhqBm~I;iZERQ0J{+f7Gg zq}VWR>{;?xo=U!1_e?tg}zr&3`a_Hga-2e;Szr7AU~bv%{>9oIyZsRmBtGGO^_~oGQi&oaq8g{W zuDY|$$iMQTyJXmi4^h{oa|Rv-7lC6Du8cRX!o z8rWnc6pX@Rn^QiexTfT_bnTC+^MJ#HV)p<{J!lcq12FDcp$*X3)A}`1A2-a5p#I{C zJKgkz##&2M55uWu(mO@e_y(k4t)>J=12#m%js<>UNs#)9uJ^;%O~M@wMyXg>esF} zr_nXld=~VzAhPTIz>ZLcxgp{=bSp7ytTPE)z832uFVL+a;gn{4Ar&vHRF0p20bf|Al%fcBV zUHSu?cam$|#~rvroSwSaHCjg1eX2f@eDR>wXhwcEMlR}=ve=6r89EoluFQ56TZF5T zs}E0K=9`G?vHQ(FT<2WAwCcS!#1`wxuwPvjzzU|4I3>ddjq5iyG}iebI=wWJKEN3(1C?hNl^Z8+Px?4DH9g*GS7L z*DKGuRQKd_rao*HXjrY0f1!Q$ELw!M%o6F(qfG8zzsv1GH@d(kBUr4a2;rxD0gYoP zzcZlNFlXo!?g@%oLnU5D0Td?NLAiFl^!8%wHEXvWO%P zOjXu7h>3T0PhFGzGN-Y2uIr5W{z{zY)CI}yU1A|m=b}H=rXpNhOI)=f5iC*5Qg@n? z)D(Y|AHXOs;8dns8{bFhD^kh6CrR|TCVw*`mrUnk8I)dDBbw3BR~dipnyh_SgDW~k zEG*?gH&>e8oc%?&@Y@4=na=g(ogT(*=i?^FP zajySmWeQ8UD?Mh3KisP@jG#t(Puq1LF`IH?;iyixmCPEt-nc_ZxHI&H=I?Hj`&#yO z&{r%RQ-y-|K(J5wp>;vOoxO{F>Wn*b3hKg{J~vNQ$qzR>7Y-5*C8fZmRz17M?tpX6 z`J0_d_gfPRer=>LuKH>e-0xD$8GE6a?K-Y4gWQ8HDQ@t$2X2^g>4zQb8siiv-u{LY zH8c+rmU0D?%OMHg?ypF>Grf0B0o%dXqh{s67Qd<}sdlhoCejBl7$y@D`Q<=&J$uO} z8%iZC@cn>y z)>YR&PdU=fALI&Ed0{!BNsb*H4T=hyhM;sH@!-0MBG0n!!tpAsm&%$0)QT!iUu=w( zLolxW?jz52nrw$-jXX|Lb_Nn#B z+84f1ZS}2NiZetdm{%yduvLmcRs1+~fl-;TiHD03sIrZ@)d5c6KliH&@e{3W;~XU1 z2?XY5-)aO9?7d;R_wNPiIV4|6=0CXM79~)T@!F5Gxmhh)>##8<`94RYw=%u6s44Bt zoov`%DY{e>>^?LmGNmB0SgSSim_`5@7y9t6+e_kq$S^#e_2x1A8}*y!Wg%%s3uvn_ zbj&@bf<9WHi@MMx`Re>3E2Zp~O`IpD-@U;xq0(wJFGI?tlFkF$6EP&i$d~Jj88vE1 zSJ$j_`{PYO{*slvb2mf}Q5dzbYWKSK8Nm?~7tfT!t*e=G@eg}SKIImJxYGT>^&~%h zZiBWyo9%_92aD~K1fE_;3v%s;`-#0tfiEwrKB6Wj*IZKL7j(amE5?ZpDWFH)Tb0{+ zZL^Nw`2c(gCM|`!DoLWoM$Q>rIN8CSx^KlDe;|3GW?_&bCp3$sNB?ZV&yaJkc zz2tV|f*Oo5Jr6&tFh-Lx%YaqopKP+Rxs)#;2_vvcFExhm>czXcJP6iMj%zPk?^Cvtp_?C$ z=58M7QR};^_A+9N?n;VgK$G->?OxypiURX;PLadMQQoqYIDrXq@>A$$DDdH!i(JA^ zs@dDCiSKwop-mhxC_-^&8K;a@ zQ3SzL%a-KH7_YpY1a&qB@3+q>C-odO@|V%ljkzZ*C*W5O4b>l+*n9bN`OvZ+FLe{9 zxDj9Nv>!suQt4g#qnG_%5&x=Q*ERbZnRPiQ1(UnOUIH^dO2ygQ(1!@l#1&_4A5fz4 zAB*Ck3urf=XWL#oYqEyA@{h)AOIJc5XYX15p}l0f2=qKy9S=3e0d}C!cg?B2IxH^A zy&}Z71+d{ve4KzdcgLjevzy8X>=)UVr3GHnfnbElIB!#<<2+I!a>KN#&#theHerA6 z#HQFiMb<#i4z+2*rhdY~Xz)=CHzsS4w`@yq&sqfqFfX zs`>}R5p!6t;0;Nc?)KRxexdVbv*TLlE1u0}`9SP|fEZ-FR*#a5C1O{R?;jBEsne`p zsyQo4$k}vMG6qUO-7zjIewUy>o!O|W$S=nQG*_11#9WK5Z8{|Tv(N*Ykf|k!w#H{_ zF`Nm@uKE+-tSo#c?o#GaErD`mEMnw~?}qKk;12ExyDfjD=+eE~Ykux;2~3%J2d)cJ zW^ruvwZcbi6xO@B7nT~Rr$7zhU}2RjLSwK05A|C~sK!gber*+U7YcLREoF!a13h;r z$M3&>%ze{NlXE*K?voW)moyvq6}q@*{8uDa#oGQOm@)bz`3#j9WBgi?7Rw!jt5fie2z!);Zn8vh}PUi5KQ+{*CGs{!0ALe=|2)-0yBWg`q`C zcU^ZlnGW2?=|Ut1ADBPoiUXZJ-)^r(Ivu6sKj5auJ)j@8`Ik~QlERiR{vqsl8nm=B zwh5fT{rd)jOfGNYmsr_n1`lXnS=vcosY1^2bWc5+1jw|FDk9F)w;!dKT!$ACCo z*Dt3r&G{EjX-0owzSdYNeivwO@}HYtBo1Gn60mGi0YAfuJ_iwC1u4k)(M!+2E(ZI< z{$EwpS{EZdGadXu-a~xm-8p6~ zW4N0yy;*bIaHCFDvE@SK!-vJ-4l;h!#xAdzRMZ@q(s1l9R_-%^+C0DK6a-Tg^LA;KL2{nMiG z{OXaU&r(i7+~=9}Hp&&{Ts5)*_vG2etrmoghn$Jr-)!i^Lzv$}BRu-Ej5LRff~&bV z+tqTJYhq9iG{?5MgjP2}olR7kz9!ZbQPJ)9Du2M=)ugd0EZlmL!fCU8SPM|!?`*}L z`8_)DxJi{JUy<|Ex3?B6^m{`+*e9+TjxhfFsH|90#&V5rWO22Ol6#LY=+74X5AF>xs6y>?R=@1C@We-GaBzKv z+klyvNkh!Z?2c$k|MN&yh!X4&cX)>QKWb{AS2xp4Z@mva-=eDx3m{FVA5%+scV6s& zpIyFJRvQJrLV}SgvwCt!$#($=HwUjpVl#KR3F1Rm{Tx4GlKg~?uc)1wa4+&c( zL6fZ(i0OC+7D^UuXcmjM$qk+vb>Q4a#zsc^IQZ3(nfS1FE7WN(Uc4ICoBMdG;`GQ# zr1jy%XKig2sk^FN@)mHuPGC;btsq5G;lKXF5Q96j%OKZF(S9vP>c|%CGJgT&>4%yJ z;vsIuk=rdz_dXPzPEB7C_pkEb#w&7|h%*lqp}`wvUv%Ntu^MQVoaRQgx5JgAHS0>LJr$Osj4x67jUAxVg zs_Nd&y@mqSfw|uII`4zpaFRgK2)W_e6y*tvf|1}}RvKx2;%J<0fBZ#W)ppX?gyxdj zb7U?~Se@snE1O+dCFl+|41KAD4ZKm<1J`0&?w8VG5?x)NG$5kOizl|5{F_I-$s8Q~ zl6Ck`n7S;AXlde->#>O71_9>{X!JVzv^NbuIDNdsz$Z~gM6Ge>?Nk(#{KcYs?b}`s zR;!mF)jd#?^Kn7Jml$ZYY(ibhZ+b_*KKjL=2HPu{=Mx8#wWdV7Cr|!-{CM|gW5G~) z-1GO&D@xGM&XJ15*aGAlR{4Urb4g;EW8Z56_wx+NNq^S_`%*4yd^9c)>Z2$hG^9v5 z33UWL_uFx`TU_K_g%ZXs>kh6>D57ei4HGs~0bFl3q47ba z>3{ma;1?wDFr=J2k)cS}WZO`=yk*jTLP~99HuKa1!b3MjW8?~k%)kKGcjgN-;-2$< zi9&BzLneVo56m{4pL`c3s})V)PJ(?eRZtFU!y`HwuwgesI5FTG$V{|MP9GWXYi_a` z9@GU!aH|o7s-9EI7-kAf$uQmV=8#98)6ZdSv5-oOwe?fPc;sUFdH4-`;^ym4lzE;k zDYQsn@{};oFeBUTUJwd^m}aIh$tB*Iz`l z{jwF{VVICDMm7i-3u@YMSMW~mjo5y;%!j%odq zv!{l$vtnDlL{BN%Rz69hx*n6A(+x>;hn(|7ddRJqACR$VpHuH_C({;M>xQbl7o|I) z?A$pX5QF&Rm%vSCy8{%Fxs+IjO%T}%R(n^YDPiD0f_Lc0n#BjqHT74HT$*yt8z~a; z_vhR*0!Yc)=URb<`b?1$OM!_*Cq^lf3`1EJIcC}C7rUEPrVRTNB{q|?YvQw9<5{j^4E4{aQe!;zKQkGcX8%3d#n^cwk1>B8u+z`A4pEukN*oTimtWz{^~ z!QgM>lqLa^XlUPx@!E!wT|G;@#-~rB!CebIBLRc2YN+|1(<@Cx2&;Xxa}&4UISOh7 zembKK+B|>rlz|MafuESHf52Z=6zifSKV>Rbey94yK=1SPo4A+VgM>h2)gFp{cG(Sn zgpJ)S2UBusc6j$2=ZrY!^F!>NSB-l~W9A;nR{_yp>QLH`j$4`kPD25eZ8r*T0iUPY z1YjyZ&HCLEOS&Z0!_Os%Urh9rx23wh=;j7!y`l^p7H~R%c?hnPipP@%d<Pg{-^#=Tu28T(W=KCgei$5Ae*-1ATYWr3 zGZr)A>xKRioFGi-#-;zj#m9Q(Z+7DT5d5=HDEJ}#Gl;wb9wV50-jA0`RQvHclgoE& zv72jLPNjt^LpY=BZB)6i0yJa%4)*?eAD(kk+?VV8lfw-}=KI&XGCVJq=GkAcMBz_# z>~H_vHp3ktbUtz_XoIhc^gb3-J(tXHs~t$1w;j^jrgFca>srM1x4HS~mgZv~7>52TE&cP=9LKZOB9qin zfA|qU*vXj@8>wB3wL*dzl{c=6nqtgE*(@+;tFN;jC58F(-&k=!G#RulR5mSTNr18k zxFTV3VEUjZ5S$Knv;yLj(I*x3#@RoRBSov4EJ;Q3d7u??t12+F06A_p+`g6=mJZwquKLR^PX0dVc-MJ}91zpbT}K zzhXgR^3esR*m!q=rk+F+obHtK1(zK^yHLoE?~|x3&)jichwqaUuj4j-jUZd{!Lqn+ zbe+y^up$%g8q_tHDX|@+GRF*LSy^F}`&8}Kk(3q1HFWhsU!MOtWq!4n|Lug| zPzd<@H9F&HRWa@pVCz%*pwU+AZ=P^AHphG_x1mSEnRaX(N%+)Y#0#K9^-iUbAAPJd~*U6Y#5mZ? z>ZX#}8IiVL1W!qlNI1 zs4wP9+fk_uh#hL0l61w7c^1pCjf=w?~bL*tDgj}gdUZ#tvx~Q?1c=ABC z;vn)1uPE6($K3z}%*Y%F<26?grov8bFa!s<0xn^8CB-^dhG_90Je>*tmaK1*4jw*B zp%YPOIiix@j@n9nzxPL1ds9z?1r)9i`;uba(4HKX!Zm}vV2%42EHVxmfPVz$q2FQk zRlUxkt1M{MZa^T@m=)+`^Qn7ha*5VYw2?TsV=mYK+e5$qN#81}@Yx^a)2GWO+n*9S zA;9>#TfE)+Zz4?q1)BJ)gl0kK9n^R~#5q)gQPI-ypl6X=F8U88GNk!D=5_@IIwso~ zUueS6qsF^ncWke%V3EmH75q3OWGVgX&REa!kD?ZMQ$w6e6O|a_Cl1dIYt@3lDffW=KfJb$Q7@&|!D(sgw% zdQKH8qj^GH(wj?J?dSqq)#1VVcvcmHSCf(>A@d(ey%FpU*U$|JmWSt9tb9qSJb+~` zfEewp6HVj*gnQpCya(yV3fWaDZ!>eUCh%hU&P1!(r_%rYHH<#VI& z120&U!+TkG3CP7x&7C(jV~49K3>U`Qic-hEA2D%=EWj*7y02qyO@UWWQc#!qW8l*p zm_ax7P|yIb3l2D%{JTVK9aWUPaA2vxL@p!Nh*7-KH7*KWPYAh#vqyCx!Y(?vAQL%` zU(3*{MAYTkTrh#O474mq;i(bhkIoy!334xB;L>iLc{y*Q%7X){j zhMHAyXl=Zzo$CRS0Dz@DBZSo?QFAVhqwHpJwVX_rn&RB5D&sm zZCXc{uBa9qH1a;#n&^)zKVD87(pCJhtS-&3z8iBLhB?LZq9X^u^`h8yYE|&Nq%Y1r)4D=#CCr$S|?1^Km1ZK8-O#rf{-qw=u@unNQq;iG$@)YlMsTUjmE6 zYnsi(D9WG_cx`3djk2ka_3n$N$$weujsYUvURL5SI1^^&TxO$0nIXBllQK5ecN&9< zTe_A($~#Vm#)%7hGs6x~ZVmAP*IL-agdWtZM9TH`bAHEtmC*X12RbWLS{CU|jS+Ll z?f(%_pFpj~S(Q;VgIRq;PV{JjYC&d>urW0ZZq+sR#A%n+04>1E&XId~%p3s|<$jS< zMUqE0LdmO2Q%Js zNdzRRkiboPP8-7ynd_M1D^q_jJKufxE4@9()bXC&#~B1@ZoP`QnBN*r=SEMS>zK(f zUm7?e&J1``t*M;2O*EqwKPSAR$_{~jlYEHeM#ho;+kxAIEkIZvAkqrDH^hGV3Sc8GI@(1pG~s zAoi{GbzhQ(q%A}3aDhdv%|K>n+b<=XVta2i{qxXSo-}%e{&#S%itPadCLUWv z5E&GBnOBQLNgIR~tjErH^UT1IOw5VaaE(=jT~wl5Hm*F6lH6y&cmJPx(}qyQ>K)Wh zN4XDJtG+S5{>oeZOH`;nAxSn$ho?$HczsA4RPS?7*%Kf|psFs^%mGW-yceHnh%iB>@yR<@dboel)unx6%aJPMplKd{l|Kp(-~Bw$N)&pc?Iz`#^6KAigKMT$J8J)|Ay_V}dL877MVpsyELAWM z>xTxqJ*@ijHrbVkyt=LCrtR}bui*KuGv7)^uK6b34G=^6*l^EfqaO!-wW_6C@q^`K zrjX&!-b5)-jhjRKBd$9@0(pzS!f`9t4BXu+8V5=Pdo!0>-7H1PC&U4~Zy1ERfhT=f zSIyFpnXCpo3^2$EelpNj-z$h(CGn(PU1(`>KVdqW;~=XNQPtCR5cgpBo94B zG9j{3fv3?wei(CJs_Ev%!6wER5XeXzHSlghT-)^7%6mK8R4mXtDhg3X)=8$w*1s9r z`I#t2`oSogQ`2!h6Cc<>F)xOJH=$mG85?vW6nP_ir;Lh@yhlrFf|o>3jmQ~W^Oc(E zU&5;B&b;!Wo_0={tjMg8U{PttfenP>{E0)xBD~h0wwfxX%@4Luwn0IQlgEY?UFANQ z6F>GEdp&;5w#@M0kE%=g!tQhs-L9h0Z3@%|%m5)%8d#$cCsRS*30TTed>SNk81ffA z#Z-0Pg39tKl3+Y-2RXZwT~vNHn9^0w70wGCnaxwn^OlR;hkOi>1m2wyL5q+_j(Eg6 zEINoYf?B?-&a~o;7r|(PJy9d_xP!TQ)Qrp>C93tN8>P8%La&9JtQ&Njd7WdRe?5-5 z-ZnN`*F}&RZZ=VStfKpyMjprzWZN()9G>p|ThRqF05R+OV-Geg6vGSKK0YbB&Y6r^IqUtW&5hnMlH!LJcw{`Ff12|$D($)Qp!`Lq=>EDi4 z60ezk(4g*&4`CHT58pDVeRX$t3zokQ(9hockD!(@{II8=>AtHw=}<^4je8*ZIS4-F z4W;oaEi|YTNH5U4YEXG{mU(j_U+Iqu&DeW{HE_1L!bAw3iQ0rtyFh{(F8N#S2S;@gx|LF?Lo4dJOh z+aGDx6y9T4n*a?!dO-vBlet(`l*KZWq~KShCX>cp#QI{f`e&9X0|nXF{Lh__UWin4 zybz67D*BJWupHWbF(rI?doE3(@V=AC4#CaD$973dl6t%z4%<$?QV#RO%ahe7ijKF!VA{FhN9xX$T?32frGz zK`Z76Ts>;w#}y=mCSU9t*8)c(v28t1y=5Q-KbXx`iKrpS&9v%9#tz7;R6#3%7;wrH zpmn|}y~TF{}3!D8o3Y9{0qx+_N zHuy_ECaVk;&ggq5Igbo+%)8vkf{lYldoal+1`2~N+0zFhnm_tJ|C0T=bxY;e7dU2kok023XxJd^IeAf8|Ue`FS?9g;mrX6gNjQ8(?c&wK6fCtrMnkRf19?`*!(=L>Y^YP`kD;-t|XIhi@5sM4W0Oi)9C+5Q7GDI zWvPQeL*i`W9w=32{v5SlPpbZ=V}&#nJc7VIAd|=`-(&D0a(Eu8A;XbH+97=o-|gsb zu+2~vz4ziJ{^_=p?Ynwe!6^%G>D{5*l#jzDt@kwiwwqS84dZ7qmRsS3{qL};(WvyN37(5NXNkRU1~)ztRnNxjK!7;U8PvS^88Qr_?emAT zrX@6VPhi>c*I6zwDxnb_v(>3*aA;!x&PSQa85EvFn)6~a)9V6fzhwAZfytRDIezvF zb*P+h-ILg(xv%eSQFjr{sCxTTL&Xl^RW8ercOv&m4mfZuNt)l|dgy=7{+$(g(9KOs z0TlufX}WED%5k{q{)U_$9+9}sFXpuQ+c4egxKr&obCHX3$HJi}*YgN4D~>H=JbFqo z_XnH5TRe1JV0Q@!pHdzowc9`JtROP9J#sXiK6Ylp?GfN4(URd~?QkC1EbldQ{gCT9 zQVipb`+o#T5Z?cWbKv%_8uXziNB@EET99r(w3{jCY^+0u;J>+RuwsKluOv;6*`}G- z^$pGJTzI?`*?05cafdjSsj0hakdj~mq9Tr2_U+n|0=KLc4L>0FQyL#4TP?3|>{|~@ zqml^}7>4L>gx5zz5LI5sr(~f_Aa7ZWjp`@T2cNWq(f<*^teaBhIn_ptHC}ye&CI@t zQ;p(oAqsWM(ktCyx9D$P^7VP;l0K-%{rh@;0Yt9AY=G5Nj+01!A}LCTEZ%`XX+^Bj z_ITtPRpk26NiuTE)||~xwU2~xg>xovIb(~IsJ4!k%X(Oc@mV4%wE`?*QgHFLFcweSG1dBe#o~6d z@$~E)!HrGhomx5V5_aAy&#SI}B?7lTj||N$k1xW;u+=;MX9(5!x4*NdW)8}EQw*$SsOkKVooICa^E!EkMg4`SfOC*xV-)O-5`6^y z_{AbCb15C-nPX`7vR(=QycBa2k1tc~ow7#mO7S$FXQxReB1(?urRj+ly)lj1iZT|f zh01ffS1N<0u6k8DkEPW{p5|93^pM}EHZJxQ$vZ^cQ2pH0Su$^UHyV-4 zojhi4yxYH$!NIf%S)FAmPZ!B$D1+>vT*87LqPIgm){!iB_1AUZhd&m~I6OgOQX-f0 zX~LAHw>uuSivbfdaWLU7bs2;q31y&cFkR)3Oqv=@v$PW zE^zzj7MLbH4DtZo@IL!Y#pdKVnrj8)9#$|T?^66YIFL<|e9fWqbEa2u!pCOIZ=R-A z)V)3enZ{Yu5zE8rIAvAcYJ8gR%gIeDeHG!n(TE4HrS)b>a~@{ApMFNV9mTN5=6$8$ zoVDN6&JOL;#y#_3bH$b_x7U0OvW7Vhdd#QDwp|hEBRi-%TtEw#{RQgvO;mymk^`cC z9}40L9IsK)*FV0LzF$Swl{@#>^!qS@}O;y1#-Ag{4@s8Vo}n(RLw9>Qknw?Te?jsUj= z(7KB3u|1s23FkuERBfc`E~A^S_G^4^IF9|RayMC*P`FCH9$J(NBnOWp;}~= z=_4#+{qwe_(6-X7pqx$NI7LXcZ9&3b1Kk?Rq4)JtXea$92M7L#0yA)iGFrt^;(y7J z7Tb#q!;5xTp8>OkuCyHoOH!l0OwqgJ-o3xhCg@@~`0#1BV!lp>P8L0B*;=tKb#%tX z(gP<6_%<1R*uDZ2nj_q*e*RF%aaLv2CsBp;MJHIG#ZgY6t3v5-3 z$o`H>arl7;9P)JLNlo~v!#>`n3z+P|cYRcMxR^FFWY_+7nF&V6o~UdF@c@)}Z4oT! zsc-4q>2}_~_8bq@IfkiUsBNejoEPuhNDb4`@4c>n;l89(^Kx97C^JsV6xcTyZb`m^ zX_r%}G5Gs_2Yg?cUgEc66D3skbYkOyU0+V{#`Si=l%|Ts5p>T>-a-96*Y5S-`q^Ke zyLJ6}R5dRVA9*)*&x!?DRMB%vdmtPge2uotWwCD)pxuYeZ=g%5*L%!X-_&_C)tC(q z<_T(2uh^W;nOLJU&*mW3z@4In=-~fAZQ&1m=XKIlP8xawM)W3%8Z(y+#k~L2&rd1f zf5F6lVCX_Cn`wW-h7qK<)0|Y|wD*c)ZXZEdPvkNdRjnK5A)?gBp%=FK0+r47EFX>^ zH@$gnwUmh}qK`qd_JXQ34;ck^gXCt~`LU0j3<~VbIx5jY-_Ha{4X7BIXRNHg7^uDN z;7aJLO4A^Jd`wcO@CEC2veW}*=&;RO;|yzn3ni91H0UjQjYf6gX(W;z2RMDjKGjCH z&HR$r037|$;M-^Tbf^`S&i+~`u6W3*6#MmICBxZ=I6wDpsV~}FnN=$xm6^|^4hOav zzbf3pGIp)LoN5ick-nX}CI1PoY%*G5S?ZTyT%~U_imd+0F8sDE=5dV@*E^HJ!><5D zgrWy9L)a~}5hmy)BDnog(70hm3-BUrowH0YL!{jh zfA73Gb|ufB*1(W;8NI!t$5#Sz8erfxA(1n8D)%j6c3kQ$3{= zVE`rr4L_7c%ic1Adf_z75b^2rR0auuno^rUD~xRg8?#mF-ZiCfg-xoCUgCE@+ZU0V zdiWAxLPCRM!)LVytWgFAY;aWNzJ=R*kawt19wmWbf;22x)0koQa=0@%769tZ?q zpdbTY8rU!i*bwi-C$mSI&f(uN)So!Zel7b{F>4x6l-QVo`+`pkA|FDdHdbIgN#77+ zP69%2ls|n&1qJP%c8a_h;6f3VmDp2s!)4n(;klq)j}%_u6ai~C3r?eIT8vcE<Mx6Mg8v8rU{<>WxS;L@Avzc>Pc&nkei*NaO{+Z2 z%#j*u{*ZhbWo^xKF|IOHHszpIGCo=R=^Tc;-_w0djdtm0g;Hbt%x;`!*OOLd%M1|W)ktR{reh&C1Ue}3pnKGf29_vv$Z&u#o>Uh=K65fbgnm;OPXK9nA5<`9>@Uv z1C^xa9#E5acp`wh?D>x%bOPtnfvza_De!e;?UjrvL#~)C_1MYL5|ioKS@urdQ||}b#v-i zr0wq@gV+@z(0uC+q3t}cH(Kn(oeY=y7)VYn6V&d%<7(79a|%)EVgGZ*WqF4Xo^ea< z06NjsT>RPp0?U87_M~`i#njbWGKdN-c5LO$&1}Fjj(ePIbEWt4!O_qGjhqi=1v@W! zNQpLelGThI@FB_bDg-Yl(DNj#XZ?=*LfHP!PjEiD>*KH3WSAB3N-NlBPy>8|VF36gs6E{9qNc(VHyXbD>yH&orAD}0quj6KJHmDW2BpzC-o7fP&4 zkE^|5$|#zU=_xqqdqa|9%TD|xbH3SndiragH42>9)Gb@kUnKppV)6Q+_8RPv(ZN}i ztzXS3P;Z@V1mETOB{6c~xm(EeFMJjr4s{eJ#folRM()h5Aq(v?D)^E(4 z?kkEc{7RKFrkYQN{@EK+Crwo^WrUYIVnb`YQ|Accs)+ITlh(_ zkDK*0KD>X6XKbre|GvuCe)UkQ9%ea~>oO9*sDf{)G%>38R{=oQ!x^!YO>3E+Mz@a5 zW2f;yr!Pi+9vBl$J_E&rgG~jnHaPlP(v51eYpOXfcjqJmX2)S{kk6!j)QWSSdYnrX7 z2l;&lV5X$le*`hb7|u{mHXwuosofASVI&F_O8)+|-AL2vQA&>#@iD0#LPONF>4pQ^ zC2}ih*HM?9e1gCfRBMv_qs>RI$j|-sqwj0mGjh7u%Uct;?}!j+5q&K2uY1SY$78J~ zR)bDMjMs|Sx>@|6w;L=hosmwrM}O?;v+>aFBEd{>vR>7R9JE3IFv4yF$!xE{hGy%q zMN=aej~o?79K_qk`UelcSVn)&n%|0l8capVBqf*()(=8L>%qM)3;TdDH0nm8tDxYb zFilJby4X`aOod6E9zVGAeI@;~FgH7vsY3gfg7Cx#V}#FC5dOzv(@D#^U{4wFWibv_ zKAEt%y0p^m=sKP7P)aF*Pv9o6YngCOPWJ}fg?2D%Lkl0OoalFf?$xP(-Z=go;w%=Z zxITM_GcvATA=-+Zt$WyjvH7a28o((o<&ZdNR-l4>!r_S~W)h&spuXM&~+0TTISs# zMr;^Kj*p#>!yh}51%%&i_}c-BVbkR@;aX=M*mHR-=sx80T#$lq_>$gqkOEfQc(TIz z;;gv-*W6`QVEmLfrJEg#pRlvJu52i?d%jt?G~8Xz>FGLO_;)Y2Pnr|BLU`y*wv7@e z`7X0`?KOT7UjeH9jibdULnIvvYJD==n|!Z-eBHkc=81rglOf1!snD4e=L>+56WFbD z7(kX#Dqld(aN?a_Y^T68=OzF6_1)?|KWEP&sxRBD-w7Lz`U$0&HaZC9G*N=0y~#%> zt8j%j3tM7_OA&gJ@49Rc-`2}vjPH<;v(4}Agoq0-jC6BWrgg`F7g~lz*^yicplo%on!y^t7%G{r))wjGAsNxB&3_50J z^$#>afx?m1;6oQ6kOD~;M239^6w8hD=pFJd>wzWGyS^W@v5(;^J(rU^-dAGbi@$TpYCb(dkc}n^t-{r_7 z3s?YIyq*p??J|AEz=HLLPlGnij~ml+OQCu5DQKbt&>=7A9?dx3*i0r@=Ps$_!diube?rfH`;XuYD7?O%A;uUT z{v+)&+>!&-&w3l1Y+O4da(mp^K-Xrti7y+ZqQFiYYm3MS{%d0hNlra-8H-wSlh} zHfAXE6ulD`jPWY{FXTg{2d1yvPjW(W4~lS)r;W6#rX9;xzF)->tCndV_4`}W5U^34 zz&LLEI!G1x_A`89z4~t$<{pe+8{vQ0e~hKumbs(NV*&9s6OFau?(af>=M#|Hoxu0R zD8w{{lin%)l<_?k4bHtfyaDLqCs0SklFvG(0Ijq}5>sT)qL}tarO>IZoxxph;#bnA zhe5_=gQB(dTUXUD`!%1f|NoGTrQM*mc!iBAtm}w$JZ>N3Q4x{P=nqC&{t2k(5@(@fIj9n<{8GkJ7|hisIRLGT%kk>EU$LfzFQ zuuN1~(efaKsqpkI`_kThdqeq@GKthTA6azcA0t?sy8L*Z4lMo1t-rXd2ZntXi$)_=tCLU~(>%{NE&Q{8 zs&tYS5eKD^9zH@l7@V{xJFLe@(3Ouq)}tUpjK3wCprSjy_JWT;1Jz#K^f$RriAn@y z2GAnt=gRzMz!E!e;l5{v^E_5(%6d!`sn^4W#iRsat6*TMpRC+dJ>a{ z2e>xP{DVwNCxBg_x{JiZb~wMtd~p2rp8tt_^LD6HYQ)_FUyW^_54i*=ZsO2>cPK~u z>>h&xT|?;o>Z=Nk&Q}BSqDUfi`93S5T^qMGX_9w>va!eVEq9&2P#VTIOXIK;KSxAx z(aCcv64b_@Tv;MWVyD0u0i<5O`ka)jMx!E+*dIDJE&7FhW4F-Snfp*!p%Yc)mJy>A zFTJV6CEz5@w3H;@b=3d}iB0^EfRBgOy`15zHxYq(nQnh++;&&Pmqa4cQ=HZer0%{+ z-4Tejq_VVhg{IL@_pR&LcE0YHMs0Ivay0G_n5uit!ML)rCLV+ha!N7{a!-@i2b_=F zuPnPKJPiG+@87PI?H@VIAVHtR$TE$1?{WHv6 z%?}rA=$!8Q4{T!64q1;~o~v-oSzK1PxT{FtDCSNb$Y)R&0^X`L;HTz~6XBChMCQk^F zNXy-z$848;qmR6eJR@v9E|uhE+-7W$iKa(Jy;7r3_){eSp4LxwxqQ*MesNge&{JDVk_;0dyR0({2dzHwg+rq>UIB4Ae(Y!{uV zgErbz_*lo%TTCxdc1gV1NDr%;Nho#F=LIRB5$9L33C?Q5T| z=M?G8X)kmy9x?o^R4k}&gLFy~=8?&3925D{S!YT0qvvklsu1SVoLNB34N1~re}gB| zi=H*t0(@kO`eS6Y_(JU(V_;0exeYfZN!u_$6#c@R0YOGfChRr^c!BgMNpwnIat?9|XV z*=)M%5-+4WiD0*FQi3%8S;Lq9##*t)76QBT=n89$$&-2fLuEHzxfL z^#6LUXPU(~3F)`EU2%N?Ao*B%C3Vp6neU z%<%*8u93S{iyv-(I;|X1$OJw_JthM+Ji_cJ4snu~v{^-5HgNy8dr67}G_Cji1MNNE zE1A$lBA?rA4RN2B3;|LTwD$En;mSKc3xe^yJOVyp97E_P&A`JWPa zyt<+m@u+@i(4v!+bGZ56_dndRK{;Ws16alw$3hyWGt$(L?)!7lZ*YeIG!IyZyaA3Sj2L^ z$jo*ReE+&+&+WLo@*g=|63rM1_1;q6N6H6y!?#Pa5C@U3Hg6yKhEoPU(dLdN&iiyUbj z*&|zF6o0w@h$G(Q)TZz2^*)!U_OY2*<^1~85%uzq7RhoTKmL4-3iOmX+Cp*e^4&s$ z{&c;7sLo7KPwMxtja>S9QlGDs>$ltmN(+o^4E)#VIsPNaaur=3;~8_Ld26A7R4pjp z*B*QPqbA7%s~3pLjj<$aQS-VOJkHooZjpZ~q|L3<;=5`4g9!G0KFy)w$)fdXkkzN_ zj6)Y*X2L6WP3T;sle=yDhp0~Wn~nIlxgSn78RhZ#a2}VHt7vznpo|da8+|tu?HJ?!q~e{B=?VYY&sIsSZCA|C`uOMrGEdW*{l)8cpYu|lkrJJi zj)}Qnd2j?dwYd$7Z)5yhmgEw{k65qf4X8KG`fE7u>=b#7IS~6zEw>47)~pOMJN`L8 zFSYZH7V&dw7QLk(T-_sKt^9H;{2fnwUShqQ9-0^0@C$*RERlKI{qJ1X;gspy7xFcz z;mTAU!+o-m1X{k;R!p}F4_#w2sWc~Is%43qU$e5l);lF?mK-4)d4690T__&AV2d!F z6n~oMns3G-1=p@?j4N0us-Y)}Z@r!$OXSv z{DV5{9xT^$O#hN+_)S(vQJs^4{ma8H+4)mAOXW=8vas8;{+?KvrvGY$p^-Ct+O~Xv zhY{X%k;AfB*51Em|Kn34Ud>ms8|8g}-YJt|QSuJG;_T*@o+&g2zRNTQDj0THouBYG z9MF4xeLl%MJ=*S#;P>HqI_}pSJbo_7al3t$!}{#spJb zZnB`fTC9dlS1zg0hRLfgJpxq&xw|TI{}H&1)k^zit_Koumz#_K-SNE67TBPc()bXc zXG_enhJPRQ4j7NT>#$s+T@+ng=?_`IG3SdGD>ei=s*|+nO=ipwLk2q=)d$^`sp~40 z>2DsCBAlmL?M$>@DN9RnbNp`A?vwa92zDT`lG0;u&p{b(`NdY&p+3o{cm1%c>YYfD zoB?Dp0VV<;r(E)t7$`l)s{GIrXZgFSB~dnKypUMX=MlQ<@vzE^wZ+zH-O+%^Zn5-~bS*@8>aNwxaB`h$~`Z?)MlMxY7!AJ8wbUvujAz z8W%VEM4=o@pGT+C;w_QjF0(`6H5OD1P+rD>Jh@biCm#CvrF}V5!o8oYJXC8bAaL)Q z$!Ei7EgU8gHbGy`7DjOW@d3Wbw$Q|AD0AsuO*eIGId@>ZN=M_J^p^BVPLkIH^u-}y5+|Igxa_; zu8sr-u8&A<3EVa>GqG7(CQQ=9N#~(v!ePz*&T{gl$XzUGZ_BbN7WP3ox8n(7u0tw_ z3+IJR146g7eIwq_?}YvC?j7HLuSXR8DGI?+B#yw*0q80h;xa21D4>fTE6nlta&lMa zSd_~1-CSZ*zI9d;si{f&8KgTXhbiYb`yM#`RI4oIC@>x6@>gIZ+E~r2V4uag7!yvN zs`A{@k$~~&DkhkKfIxbu94MI*UXVq>!^|m5u->QJB;$N_r^gRq$4-lQ?3KU2{>tg? zQuy$}>ylkjYl){VWFlsq8>Ye6Yl+9E1#8Dkur-Yq|7`ZwIg6^<<-;5HC9*A^*rYs= z%uNN5?hwnt@QKYW*(eV!`EjxiN(1^U&X+N1MfgFqEP*ZFt=j8vr`K`(Y_bDGP0>me zPG+9vLsg}@N4}b1egtVKCg#}}SNTAPYdKh72UV+6(Uq2(dC9xp2Q4EhWQSe1-~vA& zFBN3Xxvoq>=TB|mO{tdL#|nX49(PBIid1$Tq%2M%l2)WqsfB66+os>3nsfgxxyhohawm$g?WdTB7(UPd>6 zm80D|WgN|h5mD}x(xqzs`dTiYbV+6&_uy=O`}Z_oc-^7usJBXM%b(`JDNEL>WcKeeHWnX;tMe?IspMt_5UM}eKf}aO8)?H z^BViCRl88_@uC4ld0ME}6DlH~#5=6oEfB_Y#7aShqH>5vcO2xQ4LempQLU_ye`N-S z{a#HC8ZWaVb$`(Gu;~Yb|J}Yk(aUok@!*YWCgebVs?Mmjk5X z?R>uV{d3fz2ZrAh_Pq~8l=W{QTBADWE~}yO-@Hc_iVDUfBHJU*fmI=vMCTlIp!K`b zt_#z=iqc!@ej$Bx^uB4bs)%E0~_vD$&aWhoP_=4cVr zAU3oD3pbv-psh3dX=fSusY2NDUD(&5Y6B~3=LlYM)+UnHm^Z-UhwY8|xWRFzCz8Q9 zqdzNMyqOKDhH}>=x#IaPYF)fzWuvBio_8m14;y(k1V~NME(e_GE6!fbsRkF5_ zNVOPwe_A@j-s;dcvj}~WAHRpT-f(k%CyZ|VsKUsP{!|A`1DPK$pw#fc75JdtlAil6 zY@eP_$qsErQ8Fxlj?GF;a4#LXPp}_~7x6`|+4R%?OZD_{%ryP#z zt*Y{*W_<8IIDV-}I+$e8T3OQcopgvGLg0$~=7|B00-qK1#1P_*k7`%=$Kn&^D7aG- zFB}!b(Nx>ud&KhiAJ#V4kMdoMr7{24CB|(*a0R$F?NIW@8E1^euR)iDl2Uky#8Y#}dpZ~lwtotjjx?`XIm1FdkET-VZ<nEPj_9Vv3i2IB-AD#aanMc% zQQ-uulHVjk-is|pMDEz}1`K|n=KQ-EPjBv6?!iCY^GGudK^%=E%2@|TcUb>Nz+`9o zB#v+Txa{~#c2|Cq$dgl}M;pFBwkS3w-egM1&YwpCV=*}(LgvnGC%BR!Hy7fDmdM(G z$J|OZ)I9TJ+p|v7Z7{!0adJsA5BcOFNkDbPmVtW#{G|ZMV{9P06vf+y=x^EItu<1s zasC769nHHZ-utOP793?X5@|uGBJV4Zk~mesa}KJ6FU(_Fun{*tL7mq^$td~913fiZ zu#V4sdD+76+8N85zk=||d;+6^Cim2>thXe3-drrVV4yD-#IS|`)nO-nBzE>CLo>{A zZQ4npcYSPhFsGyGM+$S`*cN|C@WUh(^M-4{(0KtSfUul^4+d_ieXX~|)Q)30gr>dz zBVbjs_XaY4izF8X#V)UeNtrxC1GS{`{v8 z0qo#V%1DWdUrBl8a}z-@0kd2N?*EgKz@TAdtxp8hR-LnVmF)yq497xySuE7dWv^_; z6KI7NE#D}mi%H5R(x@IQnUQtkJ%Ni#Z&y|s(WD2HD9w;;!jm#oZ;;@e4bWIoVo$(o z3#zf?({2bIw7zfh7UL5mO(k>sa7x$dB=?Qn$SUXuoOIb3XV99nE>z4S9_xLoe5OK? zuF4bro5{*qH{aSgiDqV{f%q$^2DHEp=w-T&7m%1IGq+FvUfs9XFST1&zw1hvZ3l!J z@n6slbl9Sbc{Ym<*-PcINTskYf90lI;;1SdPgFI3a`7X2qnGTSuE%N z{Qs*$Ji4Kbt#|(bkui)C*SfHt(ij11hCS@t`^IC>)u4WUJXQ-nKO;WpeN@qjGYVcd zb`UR*_x}`!7}8uk!z^N9H_vY;7ZIJHh~qp^sMr$gGgEeLWtdhyAR#{EY1QiB$&vos zr1ywcs_SuS&=4c&Zih3q>h+BdmU_)ZQ0qbvX;@PufwWiR<+H9QczVY3j)(*jV>x`5}yiLTtC6*LM`QK z*H^}2Cjwn8xs%RiwLkG*sD>{lPnuztT1xk`60Tl@Z3);ayHMh|iX}icD@Th8q>vY0 z>*(*eiyg<74tUr>Wp`_a*EZBgp8ebwG75O{{Bu@scE=R-(54*XjFnx7a^5avI7&1x zhbqQ9O{uQxw&m*`yyk&58mb@c1pko|$5~*7JFh`;dA>NE}t{s%|*KRf295NnM-GG9o!BjvP>$kKV7Ei(Z+sLkrkQt{s zN|oPD0p$u)tG>T$l6>z(nMbSW&X2wtsUh`2!gYY#lpVARW!*;KrdgZ}44!O0-mPQ( zS!(oJzBr8gRBO(UH!fG`R5H_5_q)*Q6=w;uW~Ylb0(lo|UM|_YXiTSB=3Dz08_<(_ zq7<$ckf1Q{6}BO6EW@?`O$y$RfC0iK#K7@F9!jt6At;-Cc=?ngJSNE!}1V;#iMzkU6Ec9cWJ>Ep3I$CJ@*3s=!wbn$uxs<+AX7X zn*l@=v=TZXOm6_8m@7Xj&udH5Xm4oNto^)qXIwFo`7tSLh%uw7>kA(OfjvYN_(TsB z!^zkVWX7!b9Y?fEulqq>Q@I8(d@vRGM60=0 z-LkP88Qb}6u9LGt^pZ*uSI)s0Ggt2?_oG;8&S%_zqjBj#WEk?H3X!iv9|vb+-K-#P zDd20@x9YDHGK0*q>0OIP6Pp%ye&@TeX1p%Vhs_}WwqQ)K3nzRS?b&wWJ^fVI9+YM^ zQpMI$aB<7=H;L5i*7OgP$E1GB-N6U$DnklOs6daNMR-V=Q|6C3EhBEPV31)hI=&uW>Na~uu^+WYX8yH?l%YVn&%8HTj5Zi(ore} zQw`n0-7{TeBu@6XJ^WW;IYEXrg?!o~u}h}ScKn+%8mX&rw*jDqfd=LHUdeRK7Ity- z&n3~Ucr&q-@mR8a;a@gi9a{c4>_L|VBhkcY&jHl1B;Lm?s^I_DaA?~9oT5Lr5tFQEV!Eq7TlSe??}wxz9}Ws~W0i#AQArYxAMor}zjdJAqz_Dc;lzo`>1H)J7W*f6 zCHF~MP4-(vP$%2#A2!~*Df~*ST-zOmrx5;l4nd&^EcFJ55a;4Wo_auu#vJG;XwhLE zKi5$HZw~Xi;8c*Ej0)^>OwRQmfiEx=xe(u8)bEiEWEmK5UfMRVN%Ap+){HNs$4Nx5 zfNcT28YDHVC&q>E%6aju%NoH7lO7L*Y6z$% zIB0Jb%hP6w`_$DS{-PF#^SCxQi-)cs9QON_J@rybRSf^AlZ=x~Zjt5<1ZjWTo2PQ- z9E5~C`bdEIaIq7+v%6SgyC~EY$Y0PPG&W?W%#3(F8^!+Yt%a@XB75MsBq!w!DuSyQ z{t43mXndKuXXaK4P7#+W(ar?u#_YC0Dbo1WI)$7yhk6~s{?E?ITw7I%@#Os=Q&E$Y ziU{hTJo?{U(`9SEdQ22cAH%?=0yg>T(n%Am6Gz+4i(rq)NL{|*h4ohmcj>`n)3!Y2 zFYi<`owwXk(roSl4TbW7alU=yO+~w`LSI(KV5ic^iH2DznIGsw{XsN;xYa* z1Uui|z)9!TU!Bm8%O!p>IAr?kIvK0a=Y|$A>J?q@h_gRHfb>Fi@mu3|eGm;N>m+Eu$H$K!6-4@!77G`|1J@8ErqFAmh8_V1oL z8HE&=r6(VJ9XzEUgA>ljE_Gkt-k;~bZ)kr{?7nafm1RJD-Yyt%TYPf%8Eb|Y2U^&HS5!%DZ3N)7d;G?_-kX|veCBnYXo-i-%98P?sM+k z6pdB{B7r+pgs!Ze`1!WoY3e;c;IDSRz{~gwYo`W^NHaIbD*-)5<>1jB+ym|PzLk!} zI&upIBMl0-_#d0JhPR1w+}3j}{&&dC8adK0%D)`N+Eo2(t}A0HNM2MHZM~;7UEo`e z_?FQ<{`ob6I25^WS~jJ+dA69Bw5sy3=9FyrqEtj)YFyQVVB?Q z5;67|l-|_pbD~&_&x@rkFvd>_ExRpezi`X=;#iTO$+hT5B+WTjyey|T)V|(@An+_b zHSMiTC+{NK4HoG0D)-#;j|_jZSh5`Wly1*E?W1bwmrXC?>p7eju9fB`HsdUge?wN6 z?9_(xG!$XDFL*qeqWVJWSX~jNG4O_M^Pb;r$_q$bCpvRys`^nQ@~l|g%=j*!hov`Z zn=$8WmZ~ZP$zYnJ>{;89RDtZf9wPx%j+76w6=hj$Fh3Hkg=k(*i@%)RyE~*M?nrd4 z6JYTl!Q(&a!YacI15Rxq3iZqX2+pTZ%cbve{x`8%H}>(Z>+S?q7$^>MiDn!q?9oj6 zjHHs{IE+{Khs9o`*44=>AqI)#-S)w(d+y7=`~4C@Y;moFlMSk*ZwUW6T$PlxN8ZkL zYia5Q^4`3J$mZzJXvTQGHy7K=WFR`C`GJtTfKLaqs^=)z%El|0dMxXI!wF0rcskt| z<8~R&4KgO|3mEmE(dyw*-P?;c%5GoNHwB8qH91B50t_>&7Fb`bisKW_G=Jng>t6Jti z0)Fx*QI5+}{4Yf3<)MUXfAZwJ`y78J+*v;BbG`O1dk#+#%-MR^ujxnwHQYO>yRkFN zR)Q$&Z}I&qE_!eD*8f5_)3iZmNm)-~ElG1CU_No*@P7bnL6p9#TiQHG*$hh(IT*!u zy4~z49KUGGZ8^yIub%v0to@$Zg_sD)2|tH4xh#&F66QGzDce)lm1M@oxFF-c(Z}mw zKt?2uO5Ei7FZDI^@51|cnkY3{hGUO$T#w=>B-he$7!?WYo^#hf(zB;aTa}5eYa=f5 z-XOq#7Bka;E1$WzRJq)Ts_+W6h}DVs*Dc2nwts3u_e^9 zvVQNA8v@7iso;0B7MYVc##nQKiuzn8NaU{1KCWv7)KTNs zI`4=k4IPSkARn72KTf{YvuS7IYlt>Ua7vTg{jRmM6_8iWxW`}f_}4|Js8wC#k=nfp zWa`#uRXj`{wlXceJE}`+mf}`Gjl31eIsX8Aty{V9mZv+Li6$k_Z~*>7yW2Tq-Hdhb zT_vt0T=gTj^{+mzMFws4{$GV2QDdd+x^#;qGLjTy9>=Jzmd{`DZH=?rMB@xFc;|}r zi0z_bmH<`w^qX10B>?v|c`e_>J!en(r?YldAAJbx--_wH0pndK zR=SqqrV3$G`-eD?=aY<)k~>#bcj0SEW81V~*PLqq01d64UpW;<4+M4nE9YzBt5KHM z2}X@b*=R%JtwnX85!_!#1d5(!=$H;2M<0pxu18$C)8$xWwMUL+3?wcwpTqns(DZK( zMZ4@*a?24>^0K$5PPMH!fb|OqWtzbtzm>uH?sJ?sC5}3uO6HCpa(6f<7(+&WW`5Y; z1vI~mKLs@(0$oIna}=WcO}Q#rqPv6=g>i$mfhhj~?3(^je`xI~{1c=90Kz|Tjcqi} zRikVc4216tI`Q290Q#%@Me#H#b*RY2W6 zU9oG1AL!Pz?F70Y-l z;6H;r1>&{wH-v<-&l)^rO}a?2CIe+y@J^wkS(|t!x`~k(??qC3 zvBPnnOxNucaI&*({4%W5*!-M}#E)s={{Rt0vu!swHsv}NA~_w~1oP7XfyI8%_#;Z! zv=0htT3w~m%(2=)Lfk|NQ?L{BDPLT2IIqd=fA&iF(V|N>%Q!Fi&-yIE$;c-lNU@xL zN7FU?6{p?V+v)LJ88%7fqPnr#cLWQ8xPpG2KdzWcPVY+-iLyxixc#7QTg1N?*TQ<1 z$eQ-~7D-}eaTH8d7@%x!D!ab+0ph-*{f2xgqUmYkjbhce!5ooUMzS}}z8NGX^MD7K zn@%&2;T<{n&*O)WH2Y7BI{Vm{Ynw~3Y?>vBm&`-^!0g#@y|9=h`wIJO_8Uu?z8C6x zgz5`i>Wl}jQX~f>lhmJTygYAK#LfQd$EE((dX*E0=!e;M~mND_=oWO!nSt>e#52+CJ~dy#e0l0 z@&Vp3Tc`y3nyg3hk|v6^Hh#N2aYXkL7xRz@Wo9|~ags25laft-DO>zV+51P$;*Str zWo>OQ#4g2i8#TO<#)+JB^I&w&?APm8h&)NFj}KnT-ci|YE8wmG`3cW%o%`3~Zkwd| zZ^f5-&cCTRjOhm0+bXaNER)L03*=`Cil@cn?`|a@m!|-er%=TyRj3d*p3l z)4gea&e7=p9QY^U%{Nn<6E(ZtG=y;G=0hQDbRg#-cIjUde%w!~c&En^_-jFwOy6b- zBLnX<1A)eH#BhVuj4WO za!(^>&<_LGBe=#utZ8AQ;mpkO7#er7KUusB`+t7TzCM~$qZg&OeCyqK--G2ptZr_Q1BGYvPs!bHP);g8M4{Fft+i0!+jVPG6Eh>;oJiq;)Qcel2Cm1vr2VjsL%!wj)bbF^_;%L^rPmM*GV zqwwcn_)D+p61}#iHO8KR{ma`)U<>p(*_!e(@S9$-xu00@{4tAys#@bqm_aEi$YUf8 z9EFEt+qHjI_TLcx8u+>tfZSSLM8^a^#ys(iFyx$iS0~~R+2{6i@#LOvwc)D*Qzd1M zJf{Tl@|gCKn$FUW=8G|1kLSa|{{XdD?YHoT71R7B@gK!jR?xWLYke@(pl!XFY7yKq zRvckmaqe?owJ-b>8^t~-(_*st{qW1cpAw{kVKg$|>A%_6aWap-w>HZmNde9s6-dt< z*XkCn{{RI3_*bdI*B%+w^*tQ{7|fz{Tyv1Jsn4fh&c1o^m;4it#&QLpN!2vHU0)~t zGThrtNBi-XACls_6-c{X8bchfq51u&{89e^f_HpL*QN0n#J`1pHSl(+brQ!WrQyAI z`(_jX5TsjbF3jqgIA0)uc?+IvzW71#clILEz9T{6f7$!?je|hHn0ZTS<82yk8sVln z@)<6WK>^t3k|Av5j{N9&ZCLuEQaag6+AvB}ZF#@SDZo@Q_>h z)57*}N2tWbqrTB*`z_35la}+X-YLN$8>=H~ReQ7dgZ4)Kp?(Kwf3nxa{{Y)N z;D)-IuD@-4adDz(aoi>C<(2-YA(4#AnPzKf*<)4%3WLlqh5&vOe00~-O8)?Yd3ZPB zmyd6J?-;L)yhY-xw=TI|eLE1Lc5DHj)Xh9`D58@Js&yiAgH>kHJ3_ejG`+ zd+It)uLp|kpo|goc^aEda#fgxIEZBQJq>d>q^xS|H?i}l>>==1!ap56b}haj%u?Fd zQd=TGE|5bVu)BH8W94UM0yv2qMoAl(fPbdn+Rx!H!!Lsp`~&|0f_nISOS7@@7sY=O z>Ha3xpK2S8Gf&glygGWnRg(E4m(7uZ4zbOGHmE;~-voXT{?6YGz9!iGW&N1{0BO$* zM|o>?6UU`|K+tczGS?C!lN!x&A^R)7bAp!O0h|IxYwVxe8{r4-xbYvxKL=}m6};1@hUO?W z9U}e(r#{62`umRHguNuUAvk`{{Vume0K5t8dr}0 z0B8LlShhX^@ZPtj{5{lC#FE;UuG&e}ucMXzZPxI?7>t3m7s?!yivE54FQ{4gJI1!Y zDbm@N;atI<3N&&7y$*QTNa@EQ9-}q&{{V>Yw0{hKz`hyyGvY}tr12r~rmf<=PVC5K zxVn;CYnvNsCOB1TjCTRu{_pPgjPOU3{>0w{bkEuo;{K&&e{!pJrQIY@!#EBhfo;}j zyIA@(j9A8{iBt+tQgd@kC~{JhvOjJ=W)Ju%*0tixzX@D;@56CvUJ>|JVH?i2q`A19 zE8APLf;ndMB$1Q0IL})A;r{@Fn|{!~0r32^+k!7aS4Oj8br1 zszy~@qwX{G)BXwd`%Y+o0K845d{AhlxV5o{ONNRexUJH{B85tJ8?xd006lB=e@5|t zjy@xP&Kj5Pn`L@T-w^cco2Y#M0Fc27MBimu707MQpt}Mxtag!+U(XNhulq0f_v03| zX>ax!H0v8bE=!b+oHp@;9k3(syAq+J1mF{#ai7}X_$!spo$$BeosaD0;LE1d;P_kN zYYjR?jI>7YSkzbK4gp=_D9Lh0e)dlyrX0^mis?nlN9INKo~7as6MQQ8N}71N*Y186 zct$IWnL%_bcO1;>Q~-YZw2W5;#t>tg{kzvcVUGlU%HOfA$HdKM-}@Eu{*{D>&W@Dv+tszH0p}_)X(a9{$o#srZZbrnnmN%?-TPnsuChMWv;92<(_E*byQOFm0V;Eg98{HwH+-};va@BylZTClWXF=BTKyVV{QnLquV~=&}Wg{SM>AYkJw+~_w4uZ$4~Ij z!Ve8vYPU#;y0)Ww|RxLq?`vVrA&DrOQ#bGznpqal&m&ft1v-~cgG zgyH-*KRl_V&to_7uRQvk@KkYg%Kk%2rPagQEz}mLE;pPpe9x6xzF>D?@H+9& z<6gz$tzS#gbfrSunnooaL9{4S!S)A$Gm?Kg@^T}#29;1w&l{+q%XDN!x5DE+ppaGNL+@9yKtl4Is z{I8lpM8H-&~Igy|^6Y9B1E;dgleN!aV9XutOp^^2CgC6cK~i zayaXsLtORz_kM9*g+l|-bI%`MN#N%-w{&dcvXbKSLdt~%Jpy#G|ILBUj?Li}3 zm(J|Ej^_=*0eyYWdT>WIYAlw{Lr}SYu@<*KI3-!J_izq-A8)7YShrIwx5;>c$IBX-@r{Z7()o~Nh( z0A9Bvip}mJ3P9dDV}%(bBRJp_kL6tsH#3z>XpW0ZUEXQ=l;b05`ANYef(|fv=YyPA zsAw};ua=i_0)Yb#a#Z7xdC$LpOjnm$pY)B3A;N%32ZDNqKD_nq>0Q>4^35tdrwHoA z=c0geKpjW7eB;)%aj~3ZW9{GB2Gikue-|x$L-AKrx6|}}DZbUZ;NfMNapkYC2a}!# zF<;P6h5rC)4}pF$)$P1J;cpXI-dWS7;ZS?y4wr8WYra;aq|&{2Oy8)2Q~5zn{_3v&iIaZV1TDNIqC;)1$yU$d}$l% zG27pNt=taN++=k3_OIf3!L3pLbJDD>W`9cGv44fM8(#_8&ubV$>$va_%zE=*sCG7x z3su@M0LaaLS^mU&lH7Pg%NznfO!LKlrP;W9Z{8gDt!Zp?)Rv{ME+qhwkMrKCU22wg zpDc~Aeib`QlskBH-}+aIc&^h~msVD{Ew>y2!1~p#jE_yc@dcDX9oQbds;s^xw(`8$ z7yy5*d49EPsIHk5lJl_gdg8pZQ`a?_VKz#q$xuLHlh@j&F|#z2(#O)bJ}tAgMU#JC zGshyh%}?SpCDeA--#74q*A?a-4Ys+viLLcU5+NNM>-txFW#BzN8NS(RxkhpqJ%6oP znYpX#nw8#y#@{>GVB@xHneeuWbnm|OU~`l7I5p~;eVbarj{0330V>FZtYr{LkKTnm}-Tlh)z z_N~o7!j@5@$1}yj|)LcrksR$8RanSVqtIuzyYqQ%sxF=eCy)(eX3m*OEso#A z+O5u|s@z9A@oE&lJMJ~yPpw-mqriwyagR*&ua^8h;tfHyyRWgiNJvDGj!snPt$OO* zOwpD_IUpR9gZ>q?6H4Y4)$EN8M)EddfRYPj1K4A^ubloTUYD5JTaX&z@W6U^$NA#D zYh27wJXt4(Jo zGDm85upDz)5Zl|zeCt7lU@|?&6>3Pt(cu>$k_jC;^s3~tIcinrW;N8yHsYr|bM*DB zV(5?)06hNy`l|k>vRkW4IuHK|+ zjz-`y8NlYTYqa0xI*V3G0W2zF+xp}RaGqJD$#~lx?eJAiQ z!H;`!7PWsL?$0>6~&p*Xh^8jSej%Oj8n%Hc_{? z%A@>i>@p0kH|-{P`NlWd$B`bJq*$zQ^dJ__53x9|m25Xg%0^BJKT4-zZuHsWd0RU2_cg#KRzqXsSR}@Q@+P-71$|)Iq&IK%#g@7xEMV> zIIcDe^S1-;=hn2602HdxmfPMvoD_`qG!|4 zRw`UJ3a}aNSXWm!FkHtpM+FpAVz3yk8Ysg%MnmvW~(` zb-krsYknSwL)I^JNU`PFPVgyVh9M3z z*&JkJj`hiEk+R#bl6lF%=Pi-OM{EwY{Y`|Zs?kzEl=1L%YB+XgZkHgr-72m@ImyWY z=Od0jxvst#7U3E=kyw*}r??~X{JK{gWem3Jxl-tZ7|+T!jsWjl>dzttWf3Ocov^%h z_UWIkbVduQ!sOdIEpx!$1@UaZXV-LFE4d^aSjz$y<2+{>Cl%EAYr$R`@E(aKh2aY* ztZdANe)5UIqZ;+Og!jCgGkb0YSq@G|Jakp}JMJ?m)0Z(&#J*b?9~U)wtv(m)lIXCxxcd~oSdAH*?&Gi| z>`-xP=|D(>Wu9kJh6VhjM9`g{c)6bFkC&sPw%8 z&cp>pw6(W^RD8HqjYdAa=cRsMd~MZlm-dLc@v}a3-3so(Zdf`Zs8;y~)@-{wj2)ou zQI^^;YxPzJl1C0)zE5$~a5?XccdvzhDgMTqXT%Q_Uig~F#B!zG?5{CN;8`F{o>58^ zV56YtC%r6eTY`cX9jLWR!%q^G zMh-xX0N*xtkHGge^S|xIr+BXa0K?iwpQ6}aTv`d8?qs)yNft5`h{F}mH!(QloE~~+ zlzC{BwVCqY!p{l#cm5I&2x-RHUTPZhB==#77~eY>RXZY>QMdPEM{50|yVbPWQf>R; zKy!kJ?xDs29S8aCUyuI)vG#$gYX1NjG}v`}M_IIsN$!b|JY+`_2%=rA20mtN9^?=@ zSL#2D=UoTFx{kCY3@oi(*|Kn?CQm1+$>ygog`(Rl7QN&0=fnx)EpOvSq2oUR8(Hr3 z+lek+t_U#N!6KM<%vgm07Qn$Q2p9xrzVrQ;G^wvX9JarCxvr;wCU<5nyX^T*+3pXo zAocXG&F_c0rIg+u)$J~|SYy7{76`?=X9-pEt{{RH;?EFWqcniZG7nHMTmPSd6jlpj3rax!^FgRpZA@DE*W9id= z*1jo=Soou$coG~tMr}*WaO>tWTuZg$ShyVHJBK|-7_R>S_IuI1INmnC@dt)9=7;mXPP@65H(@B2bzvR2C4k!=?C=ie+md+|?*9M~JZ#!mf^{8P zen+%{%yQrZxbUPNnH_oQUzi>i_OGMWq9=RQ=Bh>T!30JCQ&hU<>Qj%(=& zzi+)e!CEZ7BlwA7HNBORJd;ls?*vO9-X&CSJ+J^I=Yd}U{5jLpMDP}gro$4(4Z2M_ zDczYR`QHV)j(}Iff41L?EUvXEyd86J_WE9@}JWugTHO>f<7*m-rh}BV7t4wisC3P2bTU+z?j^I90vo9+}FBTc*o(-jx_lM z(%Nc5Pm=^Bsz(?FSQFnrU(@+-{hGW${v-IE;x8C@c$oCvO3Cdc+y)-TAgL5j8-s$| zRhNKMkUE_GRpOiIJT0Q?9x9URcwW*6kO-tJhe5{CoP5WxYjQyVR zC+xHPHTctXlXz~@JD0|0v(2-{agMPN20agd#=Kuy{{Vt~_$~8m;I9#Cwkkn#ml7@f zc_%m?cq9S*v&Jj%&*2a4llw%CGgrU2@k(j&&8pey+I*U%;(ao~LK&`_R|>Mop%`G6 z!m$8gV!u~c_PX)^0Eg30Iz7x9;@n%T%`}Q&+{A!FDwFc#p(NyU#bxYjJ&2VWvDIp3 zc(48m?eQ?m{{Y$d8V0^TY#E}K!dw&m=={Ye&~fX>LGwR|KVu(?S_`_|ctcjPw`4I& z`c=~1!6^IRJV1wa&p0YVummnZBkb)@{t7?g4~NzXaq&A(yVD_-Xzimm>TW#Si7*y8 z(Ls^i{q3Pn0I#LI5Bp{O8}a?+?v0@8dAri2Xm22B-5wbgLpsQDgdh>SCxgdY#Z#Jg zXcc;~_@aIj>OTxM9T68w8m-=vGSVA;LJ2K-$WqJz11*8h3CDaI;jF$2_?t!4+r-`# zwu&3*&hNKqw<5~y?m5Ap-Qc*xe;3Wk#&f~1>HgElzYY9;C|=hwSa*)M+n#J!1r{x!-P|XP6#7Y{plfq!Hh+rR^oNMvET1ABsK({joo9zl4^* z*}5mh?-ptHkSUN_>axeJTQaNUMt`*;yORyb%E|y8F^)Yv{@wSUH!ZIGdiYK7-^cou zta$rZ_GF$Mze6BZlr80pT(a)_&4|=v0ljPVA6fl{JOc4G*M&8`OHF1QV~>1usSVUH zbjpxgQRglWa3C7ic5V*hq*Jbdt!v6rWzk|Lc z+Wb`gmw#!^147rd?dWX&BzS)3NtR&WFot;}YkO%UE`Yw+fFNWMiab&K8hk;~Ehajr zh3?Wg{$-a-oo+Ld22~i7lD@0QY@RFT`_F-cL6Tc#dyPGZ$jf_cDlupIjwB&QdBNc1 z)lRfpwT-D)UlM2Z3Hw2OMg6n>IsVWZU+shNPr^Dci?uBqMYGX#^WiTL*lQ5m!Lk0^ za}brSC0Cwz-a;b~sF=%)55OE6!4Dkksc@4tf$l8{Zc$TMY?qc(Z z+7Fmywk63d$Ai<(ZaxOvXxA3^z7EoC;JvevoBKmdlgYkjkcR&NTM>>_!R1OgVP8#n z1NN`|wZ0wc(CPjS_>JPtHV6=JwYa$&oKk>(?2+n`Ui_qXQm5ZM*08G{UQ}GFxij{^ z{t5p8`%He#{ss66u71&aYufmm#9khibsIkjMKlR=_xB2Xm2$)Z3eAUU20%p^%W+?q z9~HhO_}k+D0D@-mSM7bR-)kNu)}X$)xR%}GGPb18AJ`yLvBsj_)-xn*;d6yhOL9vl z{kQes6-)Ndjz12(0r3{)L1dcyOKlqYGPrPWtap&bzlmWO7#Jj1FXAn0{t5T-B54Q2 zUxuDM@HOr9QX}4YN5t)^TRrWl{ zb6R`UzrSA*+UfD>vYo|kcjmo{V_>d(i$4e#QPM)E8CwRq>Iu zsUcMoTX@$&y3@jZ+yi@V5)}o874SxRQcf$R_<{Q`e%PKZ)h)g!{5I44FXNqNJVzF{ z;f-5P)i2GgWO)P4yf%(Psb(>los{khSe%row(lWRtrWC9)8gO79SVPke;hs=_;Tu5 zwEqAKcsIhgR|?x%C)IAX36^VuHt*ic5Jx#AsNiR>$G`AQd%Y`8{k6OiZLZF%HS6D6 z!bcy!n$|~EUq;%DpaYN(8SUTrAK{?M8}yJN5TfqW?plj_!{DW{S> zR^f>fsPbPqA0$TzrE)%DUj%5LBiFny<4r%unjO+uYZ@iYSJrndgzUJtCE;SKNAAG| zCCA=EMnxFt`?qH%9;d#4Wqvu+zi163;eU?w__b?YSM6xcq!9|+y|i!gly@1<)gWgX zBxfArybIyC!HbzZJ)`M*<=}X%(M`h!bz?C(cfiR!^e3lEu5^Q&526mXgMzoq%ugDE0Al}JYnI#6L>l}uRJ?o*RW0tui4l> zdE{q5!aC%AE1Lx3mC~+(G5qS`!W=4q8xz?w6d50l9(c z(;2VEPuUye&%d}rWIMqMHG7(+y|+scb1GODX#<9OR)2P@_yGWH|i zd|~0eE8^dQ^-lwMs>dJ8-HF+!6^q)uykbI-sQNmdA&G!CL!tTd0w5UG*U)@vLGB}0C#)- z81K*Xp1Peh>D^fFZUjN{zyK3rU_m`WQaI_;@$ZVR?(pFP?<5jOJB|Pt1JfVUv!ZkJ zIN%Y2!<>RMpYS8!98``Yl2t-C7XYbzu1GyIk5k*<(yNtS6&YDrtt$tGWs!`9n`$#Q zPh9YNaC!mSs%k=2ypkLe89^I}`HyV+bv1EqKFw-8N%|Iwzayx zWyx5iQhsi5a55Kwc>FQx-nyJ`u=$m>ISJv7?Y2oFIb)7Gl6k-tLz{c`V!;@Iqa^el zF~_L%t&KuSBDD?yD9%R!9i(TI>@(@jV%+)g+^pMAo40NTalppxo-lgzSqDF3Bg^yV znl%BANDgtFbBumGeiWBB@Y~u!8@ACa5zw4t01!JKy(zE;w)1x@Zd~v&jN_&cZ2I*a zjcgHUd*kJXZM-1HGTzM=I7|g@~ zR{#QVP6@{xap_jimb%n(#z6CUD&KTq9N~VvbH)W{D-$%kRfC=%92F<0=bDx7fg;>n zTUamJ0Z3hm$0u>^$EWykYoKQ#<3=U6ADp=71ZN}aZAL(#N{kL?az;Xq@S?0RQu_dNjjue!ftS-kJsN5Sy0;U<@9AoUjVeq4W^ z)$oRv;}0XK`A6P83aA*##zE*$>(ajI{e`A>{iVDhl5JvVxX2m8{{W*)g1xXn#})Pd z97g;{m;V6Q>RagX0W_+#3? zJRRj_S5N|>#&(g{IODLzeu)17!A2$fKgDehbIAV5+l+ue*U8u0@atK@ zBR+$#rAawWiu?A>5l~rjdB7taa(z!sbg4Y_k%y84VB?d4*PL>A{CGTdH3p^Rn?UT# zzmhQ7KmC6~KT7;#uBY>(RzH5f;F=#BbpHSm_&szh=@E4c7uhQAB>dcl8OH=;)124t z&XcS`CY+BGa6mZkU&l}E7vjBBLHOBer`bQ372E|GbMlg>BmDc<^^NfMTZ`QuBPY#} zImfTow}Mx&k6kzDhvmuaDzw)zPC#|Z91QjRDmJwFhJPF!)Z*C_Aa=*F_Y^QGU7?=W z?9(sEMltPNUqeAK0eN`i2C9X~2SVB2U`R=_lI4&R+^ z{g=vJp4k9YjT*&=P;u1LPV&J|JazP-3vj`12bQ@x=bE+U#1G29HamZfRaaw!p0x2G z3-jO(ooE8U1Af*6AaH2{{J*_9Jn_{1Y6fgE8@TnSMA%Q=oCE7xM@<+ObCt+A0eVxz z5Wg=V@&5qVs-@6m0r=*f$qI%&3mj($r)+Uwep=g$8+g{)HvFd~dJe+AbNChE+fs{p=IYKep(0bPsE#gF6 zA9waJ#zo737{O z)h}#q-hVKFM+$nLIIibWjbLZ$OLO`5uP@eu>blLQixCZ<-adLAzu{G@)aXebiQqjZ zQKhZJp$y6k1N=;RCcBl^mflv2Yn}p*KbO5$(3*JR{oumqYLV(IPUSL+8-m#{(>U#l z(JLd4buP{;#@-|Q9i)pJ4l)A{K_{RdhPjUgXe|x3walQ0Vq{=3l33@T&YvTV-RxO@dso|V~Z_fd;=cWjamuLJAT6;I)R zho#lLM<%U&GOO}OjzWy{`PZp{!77sF9ZLMD`k&z6fT6e3+Eh%kuJ#>w4l)7j#eK7& zXsH&J1^ez(Cq*4d72|#qu!l|3BZd))ByPDq0Lc6edp?bMbpBjq=Kulej{H~X_<9kg z1r&Tm>J0DMlosp9Ttg)~N zb6stW)5JjAyVkP2fdqwS&+gApr&`#8@-g!5#dFRFbE$KrwY!1iF=U2peup&Ii>WQV zpU$eo61WaHBc?yCUctrz&#@K3QU)p7S{Y&zPVJ`yBi@mgXwWDpj=8I%OmX*4aqCTY zi#ZwmD~eRCZyML!&spW&mOOoG3#s=;Qv(>zYTSz(4CHn6=ku(qsFa~|oZ`I9MjNRT zNuA$?H8*QDVJ9kagX%h0%3mBb81zpY$kC?QH4rXQM?W)g;C?x;ZSZB&eX{1z@&kq$ z?^!>z4w!Cy6=mX4{PVdtnTJf9fWhuT^`6I~~$!?wfv;J{j^ZP~Xx)qPc%~M26s9NnIwvpfr zzGQ165;COc4UVjcAel>o3MV2Eau4H8c83g2e=i01WM{NWsv9ZdZ;XlvVRk?1Xw;o!S zD}Y(CjQu)i@vnL^JR^aySj_(bIr9$e@W5jyo=;lqW{VM?L;s-kfCP+vPaTxaC+o+1Dp(dRl98^K_QQm7#!^+oSxht=T&Qs z#$37)>Q|DOgj41 zVLBIej|y{!KX~JUeGlnPN1)Pa9Wz{QP!G+Xc_jXR->q^HUzu*&OOuVHB?igoES(75P}a3I)U%~E1Z}ZbvOC*#sd@S(*x_) zvA060-LtN>Xd;oX41c{~2IL=jbiwr<#bS8#!unT?{5f}^>rCruc@sr4qj`IyKY4No z9Alc+xBc(W7S$|I$~g*g(0Agi%_Q#X z2GV&QFgVEi`&UVG`@PRO0U{i*>CYqI{A(H%lnwc$_dYK8mGMX7c8l<*#(xVuDc~7D zwLD9&9a8VaFS1sTNU^et6}GjBcNOy_h|Mg!mO`!N#+$Okto@j*^!NB=b<1Rt?=I#m za_)^0^I{m0L~V_uaXIzpzANZ^HN5klUoQbjCwDjDLe@UlKT{jD{fGfVhfbX(cviXB2!5;O`KnNaR1Lonfw1moM*zG3~H zwF@5?U3h21_R$s^d1jN$UBHKCX*eex3Be-+f(C2v{{V}B1$+(hNg=iIeXB_%ClI5JABA{IOnd@T>M*(0&&9xOlfk)Gnkk!0@fC&Kf`76(P4^9DoiN_0DSwv|Of) z=}VR;(2Z{z$LB8S(l5KP?ZV@r?X&^G$4&))V_N(~@Xh}K#IGB8m&MveuCr&OLo-@K zb-1LL&dn9G$~adDNpCH_T!7t1YxJYWiLS@tO-%S!)uy^II>Lc~+~rR>Y=D2xd)MP! z{{RAhHF$aM_1$wwxfcFnd9lHnjEx~JksN!Og8u*$5s{JCCl!m*&>aQ4KT*B`TX=TE z!cq9z&rCKCtwRWv7=30CTV!|x zaUACj>ydyyW0A#sM~8GNG!F}DdQ>26w6={7?r`|aG4v;pN$cLfHva%^Pl)!z;#QmC zSRZ|^k>yP~>{j0<@Zb`80YE!|#&gv6ZE{l-J?Wm4@KfL~i~L)wpNChvu)5RyJsWD5 z1tSY*Z6)ai6v?$*J;Q*BxRxX_MF@;5^gi{p%V$U}SVd_F2%rE0tZRdV>PRO&4?eZ= zckGol?}>a-;!lY&-Am-(!4xt^uHIRfC(A4k-q@wK1ImW$UqpOW)%2eM{6ExuQ8|%P z&fLBuecQ4KR6tG(6VpBa07D5&-Ez5gTeEJ#@=kRld5h>7G1`lI$Ww((?s3-M=+HLJG`;)!F5_8g6pPO{5#+ri~Z%QTFj z5uM!h82IZ%@uh~jXFrSeZ89mf4;5-++6IA1Yh+I@CJ?a%jug2?!#B`ozhm{Od^c%u z_C6TX;?p$$05Cjo+po$LC^(hFho~$Bll&S=FdT#9CKbD;9uIW_L=y2o)^(|4-nkJd*V$-Szm+dK0Xu5PW`*3>Q)gO+EOX?Y7AD6JsR zEKuNft_SvH_-Qu1@e@t)mZ7YFZ7!B3Ep*`Q+ZbS&XU-E0#ys#tWK+aO4r(aEofXL2 zN9~$^)&Bq&d?zYJB(}Gy5&-^j3hgIlQl}#$*z=QJErD{?K`LD^Cekp1C z$Hgxg`1Z;Rlc`N(BI!$jO|YA6FEik0d{B~NK&LFled`QO2t{1vr-6*!nf+*dIQ_dm z2>eIWzHK5Pv?*9PbFYNu|kKQ(i zW+#&%TtcQ6IUMDa9eKzj73BK=0PH{D8~0}LuBU&e%P7a*Nn=nBakP)?Uy7drKWPt* z+E0jV{vA)NO{m_cp0~GeG~*FmGbZ~s2Y1eqI_(MoW0DSdufM!e`)l~`PVtVXYv9W( zcr@5{{hrS5cX=Z?0Qr{zS9a#yG7#(p4|>PyQg7Tu`#RM6o%e}RsqcPAmbboqK7+}E=BU;YYJ zrYDP2z9&*4Gv?^E$Uvv;IVH=fovcefMU8G+u7<;?H2p~+E@2VtC7kWD5G*Q%d) zF{g*3n}p5#I}RO{{XaRgLmOst|B(?sc8G} zETk@^d7%RN_W8ze%2iJrm{;S+#4p(g_>}b!jx6{a)5)Ak~$IV zUJtDJJH(zExmyip#_q|GaMv+Q7|1w3GXS~gpd+5O%JA!S&q9tNTGtevWn7bQAH_kC z(IG7(6cj0ulpdgx($Xm*(%lUrqA(f+NfGJp9NjQ_bPX6aV3Y$k{?DG*d$Z4W-`Dkv zbG`>urWMWJ1UdHji}sb3(uy~+sHkoKxnj^pZT=L*M_XRjP7m~a{rCbD$9|>_S(NT+ z_Qmak8-6WfT((W$rjv0Nn08e3u}g`KtUP-8N*LL*>18=C+V*F5WY5KzZbv5bVI2hN zHJc_;u~ojxr2Z$@VA7U2-&OJ;w=>WWQzlpKGFcoqGkiOAor*2#;<=w^dxaDA6c0YJ zX^sk9auC1Ek~X44d_FmiV+@ttm#qGAMfRoT=ipdc#zXoD>s9+*E;z@%(FxBp*lyF^ zu7Re4zO-=$)3QfgvNR>2*<|-r@I*|yv3WLtQeUUV+Li!cN#drR{E=44gsY_+15?GmebrAS&!UIR=)kP z?;EtXXStarm=}?g%v`OXa~+;}wJ|52NHeyj z^KpgtHjW0h8#nuSqz0f=7wIIkd~H3a3TP#wkDfIFpc7rfhoFIKI`9}o{Ji~&(6A*~oE``(GI_RndJJa78H*xGaB zA(BovatqhH8qpyY7?v5=mm1i5b(vq;>V3|u#k-Ox%3Rm<`yXpka)(%*-y6gXnt*yY zn4AKGSYN--dOu8qZ=ih~h(AcxiafPQdVSo9O8L;LQhDhx^3D)}7hYH@LvB;WcXf(; zaUb8a^c5NP6n#$Cy!G7>m{wvUhjW%5&0STi&ELy9{<}~w+YeKI<(d(1*(RV7Ut9M;`D-uV@A-To9juf-Az0Ti8@`C4m zoL-&)j@-hHlKTL}wc$2ZJVvYXrb)>20kxD9DRyJ&1jk9LK5-Jcs7hkTV4-yi1 zXQWtVoQfqLbWcM?vlt;`R?O{rP6tmJ6v+*MADDb-v)JEiE&MaW^>PQe+vN;|XZ!Al z45?x9u~9OaAO|-RZ066h5qHm_DuEqfARHEvWSOmP=4kMeGg(~z4>f@N&lT$}mDYhJ z&g<19eO2Ibr-Qbh)cC8l5kHnqbL}UKBSZXOX4$pUd#Guqp0RNsI{P2q%=B$_qz;7H zj_>|Aj&gA@oaY?Yqw-z@WvZrnPJ72eDI1KCZN)&|8zRO9-GpNlpBgZYk&|DJoX&Y1 z<)-}$!_Z~usJq2wnSJc7nMuhPfk z^dDZrrSf73?_StL&`e)b?PcK<*X=$r4f)y z^#{a%wCg|GG9y6ZT6mYpxX0hGc3YbgMnR&^uU(HRy)Jx?W*|?sl`pQYYA@}N<2_wM zL7z=2XIoPdT}lcVS-#s_wDGHqcg?O67C21R5a@U$uomNdhMZiBv&SC+dc(6}*ALIq z!$5DpT|P8qD+aez7PhiNy#jE?@gnY@EUg2E_Ex`AQ=pnxKVe*wcAPM_M)IiQ=)RJr z+^`~zXaF-;UMOE)KZuT@Rd*}n*fctELW|6%_m&fL{z)jr`!(7UIvlt|+K7+eBfKe{X&iNSpDpi5G(foVN`1^RFH00YXe z$|+EGHhM5=8Zk-L$q0K{dt*bYARRIo2>uTbae=fTMjromSz2ya7Ot8<4F|x zi%Zs{zN@i~I+1`D?N%dcYl zJZxZv)c%SbbL0Gh-=YsetkT4n4 zL41ARm{Yb^$1Yo&)71j6t!lcTD*HJ_ogbGNAckn}IVnnCgY7ckbOPKa>jIevUkf{X zmxsJ(wcbpesa3%$O=o8vU1Dnn&-<4=UwI65TAQXBd|ynKKV-~DV#*dh@KTljl#}y$ z_s~~ZfgS6Eo(6pLaTD2fYb%7wT@`wXI=@j;8qn8OX69@H1okH}=g!dGfIR`s-8*}Y z+ScPM%tL^NPqSBenPbWbt6>&)^Pu|;b7vt3ip z)beWw<~hiy7XLaD3E7}fAg!4IHhm{E_C|ZtCNfNF@|Ej59;59OQKY)=XYbuUzT_oB znmE|f22n84Q==7Idpz2f;6j32DOfm${Y-YUI#f)(WLR4(y>*{tWFR!{^Ez9!C|^*y z-flELS6tj9EtY1(jU7o(9fW=C&+Qu?oRiAMEmvX>k5?F(aiPRP zv&Ek)Z7yEZ?+Y!oj=VHp9f|L|tXOe+QmQ zkM_Z3`)lKcKc;XGMK*_cmg{bCi(xT7*lPCkBY0Ftkwj z{6Z+(`v`osIQg3zAGqCGUeJ;Y;@!@s{O&_PuCcSL`m}si<0+pXQ@P$ybGW->d|wpJ zs&L^#$L-OZf_56T5MwTtwh^hMsQG3E^VjI(?CmaKpe zX_EVz3iOOa@j9YmUy)oh#BfHBQPUGl`r&yiw8p|Ig@W>P<0?9PgMRGW-fT^r=mSFWRt@Y{DB*#7mY{d@j7*65_e`$k7k*KG;_l$i7JJM1LaklN|LgJ zVU+W?gAW=GbfYCY6LvKDCRv^BR28n|5^Ax3?s*&pADd0M`72@%w(x&#c-u+hSWgYr z%iFddZ0)}bOSM@ye`Y}Mo^-QU1_!FNW*}+ez}ZxeMfIZ@Y}%E^)qZECD17}H4RlmWyflV2=`d(EzV z$0RGUA3br2K(kvSbW2*)6U1MZ$dgkN4>^NFj^+xo8d165p*tBJ2@7xvWdDKJV+8kC zcA@TnSCt{PE5~2*G8MKwvVFLxF6JI%+NL`Ewvn_SYr0ya^?$giniA#~r{Kn0A$B+= z&*6;i2G?u#$b5B1=fJP*IX->jfB%UW^?P62uir*@7L7mQE; z*d!Ws_ZUKKREwSe&A8JHc>Av0!Ep*s{xKyN)DB^v>;$Qx|DE0Gr|Iuy%_#Og_zad{ z-@uEQ@K$C8)XS0@R}x(&9k=!4Ot+s#bFC}|xvUVpK{lO+)0Y=`2DoSgNu34;PB1PB zkA8gFzfb|T;hIyjGLg=#eaLi2O)QDCJvn(W)u`Ys6_VXO$HYC8e1*%;8>F{%Q@a?P zSME=U>;@m44RItmd#$$=IvQ+Y_RMcaSc##U(kRnrlek1iRT3ZR(EZKa#jC##fue@> zEbZwMT*-K=OSd-pbZ}a=_lvVQj#;foLYoA6Xfb4_wbSC$_f6#%fKH;y&I5nEumrWs z&kaZB-}k3mEZf2EUQ?7gw=mieYsm77NJrC5KU>r+CaYy|@Vf!$3@-G}to%`-gd~Dp zD{y|k;<~$ijF*8R*XszE7ulyVT`XLko(~L}hT)Qy3p4!20FcK87n>;Esq^NQ?bXF!s$EI^972Y$s%e+r= zdcs%J0#-p5N!~?3mI%OJ9AJ zU&@c{(9W{Q1ok#1{h2(W&CU%3hw!N?3K+*KsekZ*klZsJK!`6{Dp~rxWTw}(5PSPo z7$hmZ8s00w`#7xAB*Z}rKUf8|5y7Z%X4mkxVR}L+;F{sX$UDnaaIwH4-+}hNIleBv zVl>nuC)#e+Leu`Ut@|h=9%ZOS4(ev1_IIn94ryhPZ>V)J30fMJ(#uZW5CRySk}-KY zA}|*4zM9T$(90S`f>H6z_WBmFD81^f;N|-_{Du$1ZgAU-6Nu zV!OJJ$(#uu(V<@kMUWj)Jp-YCLMKc_eL=)XpP-nF6Q5R-b3@MO8sjQ_VDYH%!s3~n zZOf&M&9AL82Yv<5^Z1wKe6r)oJiU^d3HD^*OtJ$(R51-qxEyt)bnmU^LgQ>cc$s4- zj!V5!;Y#8##3@2Cso?9?bTCyIN`DoYr=k(^42KZ=MJn6bq4-Qyay8$^WB)Z<>ku0T zhJXy-1#SEYJieznyD!m&YyG^@KEYQo#P=iIvM@Fx{)wGeas|*|3l40sJA_fl&;)JY z)gy}9czKEV_J+r4^kkA!22aAhEYsOZWy1d87#&(H;abO<}KkI8PxvI7ZCmbXp1hB-@3p%Uwylu72h1x$yFZ?aa}ysfAh}~-Yi<-pU|hpwCKdG zeLvi+UTJSRSJ33ZMY*>=zH2MPqm^^+k(lp&69Kr)v1vS0{&E~l`;nrq?1ckfTyY-PIrfQVec$8F zHefusZ|9*`)Fed^;&>iqxcv@Ww{DL9di&0!3ncu>4HAyS+iC$fJ)O=o;OucvP)dc5 zKcB07>}XwkEUx#D22%=_z<%8?=ZQ5oYEgE{v=k22mv=@9_%kAnl$6g%_`|BUJtp(0n+*mi2KP02RyB5LI zlsiZE+-?TJ;?aKEjWZ34>E7$JR!EuLSHdFuUgpTjV)DNm?;3;CH!se!&lL{LKb%da zQc-poiv12eW~Z&rk5tEcy-$82{}90;p&f8H>W@{1R91>?zwU!Db)O_Cs2pp%?@y z{9(E;I-j=jc(?oSKhq7eIrX}#u8_e|J|CvxILoG=UBrmJ%~cDut3_+nX-7`h&GPMG zq;hGyP5+dG-D!U`LRST(?@59-6Ocj_L*E5E!j~w3;)j7d=ZD=X;FcZKOh?~!`9hc- zWKpD-$7^dCW{kS4&iMN-Kx%|b;DXQmXA-%`w=^(|6@R~Sq6$5F7fyxdJ4I$}OB?fh zcdBch9jX<)F*0#YBv`ZXO(DFP1Qmt4qf>_Do}xb0`)!BOSwc%44bKCbX`!6zT$Op- zHgPsN`R)Kb(ixJbUs4}q+*H{TD$$u@A!<%YN5ka9L*-;8PgOs!bcD=DJqR5#;t<*ZTEZ{wsN4Qmox6SG%a+9a8gjgEV%{S?T)DrUYGOVyKwzCn3YkJgWp z;5RiFJ`g4ul0@e2kQ+Aod%-n|zlzimTGhFY9DcZjvSsIub}7$zmmlpJA?I>7)|gK% zErJEH3HPrs%IAX##qXDVb(s=UDc|6=4qqY2PR&0E2{;GLm%Q5#T+g}tj4o8l4DBgi z;c`~M9<^ecBJ#`-5=cuAf7*>ziOjR?Ci6ayHO0cw7(z3nKdf&23SbMesvdo%q*aJb$^P>5lvX=s0gm6 z(9D*qpTfLGC!pAk>$Ch?r;TxRHr^A`KlV)Aaktm^mQT^p!R3iD^`{4WuOhy6_vo&% zuwK9%HWNuM*;hlL7+SvW$K#6UhrJA+o^{y)2>&r3SvYM|p}8`8*NiUyn7%stsvX7= za)S^JXgGmCT_I3@_>+4x(xym1tQ`KS1CJBrS1kaye;{=$5yQthG->J`rvcxS+W^mR7hi{B3*}f>fBY0<-dUQP{A;1CmxL3%0xv9eLdPxX z?|Bb5m_$!W{o$(THbTRY&${kv1&4n;pq-&-yx2GM_Yfq7-{Vhi^mJjpVck^VCx zMwpB(77&WAoM0RZWIeXDg6JztTK=T|?!N*B>Ajy9(CEvnPkh7YH3V-4Qb7*}LU|;X z7BPyvcdUZl%o!T!k$lZf4%2-35l)KB!=-kR=JsJQnrJm4k?lTe9g>juMI35_ z;(L>G4p@fwz$1`Yr`v1vGg9>e`8AQpNywxX*`q8Szn0Uf+ehk4wc#Mp5!mUmR)hMB zNhR5E;H{zZwa>eixZB&g=Mvq^eYZ2juDT6PEt@nKen`{A#TE&^l&OeQb!U1bE3X5z zL3RLOcS!bP;(>Fdv;vI;H^F)7=)f*KeW;o)`B99kN>2%iw{GP|=L12-5(#-g3G3lZ z)BMBXOK7K^5+bqlE->t>Y{!c&cpT0&^*K;!Ny%)M}#@W6zN z12fkgxGd#AOI&{YZuCT1Y_FJqjG^LFW}l^S+gV5*TU#ql=6`elq{}5P z5;u6D7X3g&&Y(YBuYMIJinxscT83E5r%zq-zl%FXjIoJKg{7D=v^^RXHVcmPE!B%k zy^)d}|a<@9QPS7+EQr^OD8( znRvY*`+g!m+XF>?YbPcu$0y{V zEC%xQqmi=iApzxnkAsZ&cH+w@i2;(bx2Ophux1rwxc%>y}tA4me=X>|S(N zb#=|q6i8i@q1}(G-aB@#;c-@m%%z_h{cf{;scG(JXaN#~0U(nrmLH#HU3ObYXRJK2 z_{_&rdV!~@Ob6$QA4z;Yvbpsi+!;r{@&PwpNCmz&Y}+ z)I4rJ2rXF*Ky~h6=T#<&vTfR`^q(F@H0c}az+fOXfh~hQalYd~gYf9DGu=D4o+74+ zro91n%yRRw3t8`iG)4>Di`mj@Qid4US+oMnuSJKwZ>V6Epka?RMJlb%Q?rZA39ipv z{r@QWOy**lT(tp#Jw_}nzCL0h=9RO%5(8d8$INL8{W;eXm09DxUb~k^8eWv^PR@j) zCYAFmT8+hbJ&7CxXtZ6Q3-k--{2{-E30Aazctz_-LGpnQg;luc4i9%}LLm z^PdOX7oTcImS$dF|8;#|Ukk?Rh28<-R)LLG*q$JU0RTS=X2516WdsVpZ5W__tU9Fc z#uBYFfBfj-p1;GW^5)yc;5Fe6Db^+TNMpu3z=v;J0O`E#P~_=OPi>nGJHuTT4{5Pw zIBlJ?<+8!WfD|9&)Mbr#JSo$vlqfNLyu~b{{{$ct`K^MIMQq=85x~PE7qb&=liT*8 z=tZZ+H*_xo3or?LSpWpHML|d zzj%$!c~hf+WfO&)54LD2ie#K{nV)QMK{y%&cZ6lc{OWoysQdYPP%VQ5$o-%5l(K%lAJ# zhgZsrw_!th4_C{I2F8{ni4bYTW)ZV85zzOyhHm+2c(2~Xo~a|X8H4k~3nF-~7c{?m z{BETbpM*_8R<3J(F5TDf5iS1`*Jj)$&fX{Ejdd!M?C6?#j_c#U>VPb0`xA&Uu5Mw!7lUn3 zovGhTg(q9qVzfgNIP-cNi*poC62hnki~{&njj%Mc#j{(A=Pw-I*ze+S&k&Q+ZKS3u zzwRhcaG?#WXOZH(Q)IC}HJ*z^K|xs8w0Ub|7kn;&^CKckz}8HM z%^TF-SABzp1G>~f<`}&V)_|&Tbd`Gq(tY4em=ccw!ajqeWs9{gmMfX6#JUu;E>tmC z`DH)}IP8IbRSCzuS|>1m3DQ-9q>%xueZO`wh6@!zAs{>@_iBMvZH-ySh=DXf76J^D za$F;g*ASJ2K9U{*(x|^6+@c34()mp2)Haz0x$Lt%@?~Pe&9XJ;UlxbpLSy0Y>3&3a z!}E#}Cce`#ODw>btK_%=bxbAA*P=UR`cj=DfBX&!ZB2JA?pdajFw#98d(&7-5(AKk z#MM5)!pW@+n^F+1tdx|<&GK0s3&tOPk&}NW_0Y@&4 zyMQ>OB)0^)r=u59C*HU1P;FMS;WkgEc<-lb3dx zvAJRnK)5g7$Pg>&F1w1@pit}JRiS0-poI+LSi?O~l@vcc*maxISS=W>XaM0M*` zY{5^ask#hS<&UdDSSQA@6h{_C`t0D9mRsN>A!sH2S()14_rj=GT@U@ApLT;t^JjfN z#hI^b@z4IzI4|{+GbxoAAz(?+Y}xLBz@Z5&y(ZG1?NZGhZSkplu*+B1xIT|qHY5;M z&0oK~+CYh9p(K%&l^?#R*${&sf|j!49zn~OhqydS-PZ9`IZw9Qun%8M@BE$4D)kL@ zt?Wd63w_q(R$QG;#_y5R^Fb%vV_y|I2RpUwj+f>4c4DFSO-pzfdhNA}6G)g~+R=tv zeCnsH6IGf?uJ)@$?qy7vp9Ekcp?i(c+F<^A@Um?iH{O=Vzi+Iy2U%wy{G5g8`71&q z9Et;Yv%r4D8Kj`nE3w&wz|_Y?2_D;6HQA)z=(;{hiOq!3)(LR|E$u8a>395b3SO72 z9t&MGxF$d1emZ8W`AgUqU~2cd;vc*}al`)0At74%tZgvGYDasD$FBqPQbEm7 zg)@66Ie;r_%7DWrT`2yK2RPd>o~O0`pk^-BT4gs@!WsilnhK&)Q>Bv%?n5iEYH{6X zmPOnQjX~c>3}{wO+xvz(?oD*9vC3kR<69Zu%A@#7nJVFN( zyO#QTuxPxJytZ&iAeE)s{kt%GL0ViZPGH}(&?vg@&N8pe(t_AymL-N3g+}2F-aQ6l z6VI0ff`xvwp#uLlu|?hH$f@=1zUN!14FWF z`rB{hiK>GN5|g0e>Y-N1W`QMru+P@tIg>R3%i`PK#a@K0(CwMiMZz`&S%Atg%gk@= zxO>H~q&kK_D5sMYHSxi2ZpR^SZn7LsMZ%6}sqk!6?n6Y>O3P4ZU^9j`#d4;yL$XAZ zTZetcj67M2EiWewxc&%RAop_phaq@~eV?&&7&F`^JQ=zP(xU->AJfZT&Ae6tg z^;^P~AqyAYT{vB7_kQ3lEQhJ5)YpSdG9BHm= zlhQCV+E0|M2}dl~KYpku)1?cB$;I8n;H>W+hL}yj))c3Qsx~7s6%V8!MzLa}X z7@Qr5c86|j(0uHS5Vly>KqX5~vM@p6=E^vmF`7^Gsi=$F+m`deP;Z`Dn5)-Jr|eaakh7IQKUAUo`TLnG+0zmxD3F@31+9Rq zo=I?t^pwK_P1UTO!%R*=ziU-frtpTc!AiW<-@0C+O$Tl(Zk6JtR8HD!{;<&{oP*Lr zTes{;1;3q9f-cV4vp^PS%#f=Mo&+qY=s&z7&I|7AL2RZeob698XM?`T8&^*D7i;Ih zvqh+8BqZBhY1%?cMBi6Q@_tKcs4E)L;z{&g{99O~NDhRz?t?P+1^diRSl_(;_IKt1`GbIeIA+6T_2>><$DBR3 zy=U>7irk;_g;>1EhemB3ZY7`<`>%^z*d^qQr}r~Md)u*PhyQ_P1c=D`7cNS>>D$;I z0dLYVKH%)u@RIK=L+yTI`eQ^JZ^?m~SfLAPRO?A}mzLrZLh?w1FzTyxKo3zlvpkzI zzOttOc3I=9)n<)!EA#cg3L=+x9K`KjDU(`af9j5JlqnJ^Jk^8PHj9%YHoACw50l+k z>)eT65R}>9xGM}@m4UZqD1RbQ6+AByKW(^x_hD+`H!dmJXDc#EUK>#}p~npyazbZlPY;xvOo zw}!K~6itnOzXu$)g_AW8Vr%5ytgxrydKA}K`wBCsh1#$p&3ws`eW8{71M~O}t}f^n zf{-%pHsiY-w=UF9QNocr@{7Y^e&Nf{gA>p5y7PM5xDr+{?x?C5+A#_s14GU;O}Y$G zhZ3zU>Rk_w*LMx~52v3kqMu%L-}s<+mhI?jMsTwK!~7)6j{*?VUx6;TNIp%IchmJLi`!k0!FyS-Ps|w4 zOn;E3nh?UgETsHqKg50}WuPrsHEQI=)L@XCeN0S)dAXRw#=Fzc5XH5eI^}ag5R87R zJBbaT?U6Me%lK6WDOUU->C2>aXfSN+)#AOhb890gE<6N;{owNBuJ7tE^`Bj+TyKhV z=zn-=#=!mm=5OD8ILCZ_GYPN|vXnu?ELzgFj&pbjH2d*Wrg9Ny)eShC$ES@ShVIdk z6HLkYI>L{Hjy1f>?{J*vvpHyqxdW{hSBuL?Y}h3*3s)X8n=II$Hi+;_x3WJ&zuB7m zYuGhE)!rn$dIf|pcY1gmAzenI>G34)R?lTA0>x`Ls~HZy{nn5>ky{CFCP=X0dmu=P zF4VV+oS6(Dxj%lX!a4ihqt`@SUAOF$j+Y8CGm)0)ZmP@hCjJm2&hT{rA%id1 z@U}tfX2B+Yu8^hLyF1BX!}-ck808N+7^`_QC$#?6)8^mUG&z2Ag;@S4U&4v(awOQz z#B|5X#A;;rQoZ+-2WA!S>JkgyO&(Vl441C2qwOgKQ&q|c{fZ8PAo?EVNR>4b7V(@V*_wCuSH{ZT4nW8B@tbRQ z64~48JSJvYEueiVRIFm1t~u_;aU~6e$V#MwTU_~Um2Td+768c~Z0>lV4TSwotjGr9 zD5b(%uIbzVCc!kC{C%Kb>9YsF40iV5;YLFq7EjSWf1Q?frcZq{emrBh=k;o_x?^)X zP(F)8vSe5b?1 zkD5GZ+$eyz?%@K;HXc{lezdR3s7qvfgYCO?Q@fIeJm}UjdgxLd-jO%7+=A8G3W**k z9RFr?`JOFLZNDJP`o%$;w0%_Xf_dgi*2`MEl76nHRJG#lQYib^K$vbUbB~2QYdO57 zgP`316IwlgL;aJMgx+~5uRoS=PE-qso>h4pW74cXX9-W(@w$QnE~`x``nB`gWhsHm zl#^^%0y?K2rb(lFjV{|sL~HFaM`mB6P*lCQnKbG=O{uu8P?;eBd)gL8V39_sWAFhGA}aW=#5?Cqkh&wj+f?fRr*V_(T7ONhMiC1uIq~5Ssc@ypyBw{-RWbl7$-2pLznYeqdvQ4$xeBkA@ zjS~;Az+9m#8ZiSt>(k!7lL4Tegu|L{nto8tJN0+z+eUo3T#0<2yE^63v>y({tm zVKm>N?>nQxm8{C2qB42j-n^b{=xL$KCDQ>`uieSI?Yk$LzGGevg+XY7A~(T7bfnxSJkaO+R+m1an?dk%-tSh9h5v#O!GELk&!6y|7 zARtVN2I4Q*Vn9_rHf245XV?PkB=f{etB#8y&LfM;JDYo`A$vV&sMBkUD`VPGpqL4o z!+iLRFkJZ)UU1*O|Ac)oHTnr0`n_(=7%igtOSdJ0FfQo{x5MNNN%uW%b`aauL7B&H z>zJv4J}cA)n-BSXN{0D7eJMzVek~vJP&8G}GgH5>YoZ{P2j0qcvD~5FE%iS1CCWVE z>%z6PTjO{wiLF)HYma1ACgi<;H7iOkt<3*TKP-!(knD|z+Y=>aU1m)JtEj2XDAO#1 zUu9;?6Xm^eV~;bqY*8tTSGRic3{5f>O7DvV8srXf`G%u?n+XGag5-x%1C`j$aV7m^ zhV^`&9XXOA?gTUM>Sri{ove+xS*5dq(ky#|&#|ifMk!NXv&9Qt(i)0z=*2(wS2#UC z5S(qZXjmD{jc(lD_>wEoggX5)ZhZ^o?+RA@aFmxxVs=lc7fqBOaE11LT_^W#zT;_| zYmw8|nwkj3Dl|rkMa@1cF%Y;=f;N_96m)yVN381^lnpQPj~U2Y<{J!Sk$b9&;_Uyu zJacZ8Ox^U^TE0XTs;mCU)AX#`68r03Fj%-2MVD^*Sg^Qpwm9Kl?n!)+4YxegOBFy| z@~eC=gQ}!$Yl+Yz=%v|1LW)7Fer$42q<4{uNm+ znvrp;Hr^N9`e85VAT<6XuOkE-_PFy-0d3m5PO^|ceaQ`Sig@qUugp8r7f1OMR2kqJ z^VjildXyNlN>%eg#H5zI9Aq-P%;>_&$~LDW9v@J-ZW z7^ov?CDatw}-tJ0(bR9Tdm!sXYZB{?@> zVmrA{(66_!)~ap|d|zT^P6g=Q*)tN*`PIhMmv`T^MO<)EkJ^>7stTt9M9 zAt||^c8aazUM}sL`-jgDs$=!WHZ}t^>QS@2$0E)y9SG~muy@TTM3b+@Fyr#EkLD(U zxYK@Mc81&1qkOrWASrxkmmn%KME0n7wsFGb89=Kw>-m=ZA9%F{RKY^S`$8*-npj@1 z0ePBmaB4o^;q}94=F!`BEdm@Ph80)tVapTrB=*D#8#0g5Av7K8c0fVVT#q{lNLF@; z!_X_BKhH=znTE1tKWMbgkU}1@^Dg2 zH*K~(M7G@drJPggbj0@fJNls2TR# zTTuo@9cUl;9tuP~qJy8rcjSe_&#KG9HuKo)c4LsGn|#$w{>6qFeg9rf>I#wb3D*)N z_jGgTMs}5>@-UBH!*g?SIhDO#sF(58?=U3p)pmlc_!3E~*La5Sz0@=oZ~gULyg1KM zE>nd>?)bnwuiU;ycf<6IM~As)@u{3F3WUkhRPV2dx}d0`<0p4^=$8vh^B58zzenUZ z>5r6s!>K;61hAh`JMC23E26X_uT=Si^@`0MQu19;YYJR4Y>*J;u)x!=FMpZP9`3Eg;C+3Z)tMhe`t@&m?ghRQXjl)2CdrPVDi;y&J|D!AAGu&O&ZeFIEInH^>%o@$S3 z&W&73up?0Aw^gavh7=UDoV-{1&X~TsTU4H-fc270a-ui}!o$o2)s?ny{EW>}K27}c zQr!lOkBG>=KgFnAaWJi6ix#G9Sb{Z4I_2SpT`vACaz) zi(@|&G52^Hlzekx>@P7)n6zr$0*PIY#+VSi6|c)?Q|3#F#2=#H{q%Fv$g^_kA^=Ch zcqzJlWuJlJoOKm!tfwOzL``i9a!SIP2R$(5S1DUnVD8U`W4yInj2_JJVgej%2G$c+ zAM^F)CpKF&7JfQ%*d8#HKN-evc*xk-`N(STR<~w(xk|;RhcgRR$n5DDB$@+fa>a7|k#-7KOOp+i_eR#4^^2DX3B(X#KU=KA2N4(|0HcbM4?Pk= zP&EUR<3PDs8~cDlK#MlURydCOm8Zy|P(r1rK@;vra{Q*kAAT&safyJ~bj!`J_l^w^+P#za-qT$=8GvV>wc~<}%PI?qawL%)BE$>W5Bw*3U^X%K=Gfeo$*@mHDaQTW z54aU;O*8{=^#{y!XuaWW4r`w@gYOO%n_O2vG8>nXNPdFv`#|;m1H7XstfnkqkBqc8 zQkoa>aikZlz*-X$gs(4ZcarzXU((L)p_aeGYC#W<{DV&lc>g;8Xk(#E0W~T#pHBC2 zg)3)?;|i(}cMV@Pgt4)7w1z!Uv(c60^p(?X;m$wwT4@Y+fzviy*eC3{#znVUW|RV2 zaX6za)s43=4zHx#V!lyA09kj8<8QTJsakFD;Gw`jF9$-xQ17;*R7nrHMqL&qq}yn7 zb4U(W;q)k2pF=K%=YqB3@0L%xctadMtV%>eGhH?4(vq9>K{Dlw=S+5Xh-Y6F2ncTO z)6AkhpZkW9;pU04GFB-pfi;8cRF*nJH^WsMZ>VgxO}}C4limC6ImC%a5V;+s@GizJ zQ3;F7G@Hli%cQ#*RRKHrFmNY@kCbZxxyfbS@Q%26e4pQ_$`M%hRcPi_MWN1yq8%Aq zNVVl8&IA7>ot%cH^y3^gnJaI=$ia6~K09|l)1qOy@d??EZwBONr6e?C~XjyUyP z0zU-*w%RhZ@zK|2-dp3WNZ9f1&jglXNkZ0&7TI>NN5rhywc)XGsl{sObd!z-e|+1h zr-D}l9%DQNK8vdUVjEC}(RgZd^2{H~6^C8jx!U*ifI8m&x@L<|MzWKoufB`JxD3wV zC;%^W({8JyJj0GOE!l4asK&7g`=?~61zpI&6=;IpJJ=T6+^7|v$M78O7gSVLVCAyi z5f8p?qjKrbCqHg<$-_rlUJY^V1cs@hIzmPYVz-Y&lxO}xL>6xq z_bBt&KB3g_EwwJ>Ibws8tqru&abf*0N^Oq@ z-1?jf{UIKuH)!!p$kZQ&lg!bDjG>_vbxc)~*C3&NyvpN9=+mOC*rNj_3)waPgN%_jP%ae9orT z*H^LLe0JUN&u%#f!*bge$y$GZOZt4E`>=$dZe+h=M9||=r~>;3{EgF*d|W&{8)Na4 zR^VHPEm*W_pwZJb9>w+9YT@_1UMe1HVW&r5PR?I?$~(<0P`_jp9qYl)o!spGG95cW zn+7l9U;Ug(&s-H3eM1PjeXE4^lCi31Q>5oVr)>*Qz&Wl}V{&3e2TiX^)^xIUBX32F zQBGfqJW|clo{Ma03_IP@T;O_o-ZLT@$Y;X0doK5Fsph| zv^3f5qtUK@Il7_b&~v%*nw@pad7d7tIz_Wv2jE4%!}~;ri!lgEt`CWKIv&my0f*%Y ziq&OO_3f(?$R1<-jG(rfGa|-0L%mFMiB9o|RLXNRL$6t;G*o&5zA9FlS1co9P5+?H z4L&}>SnkhPyN0BGU7Y`+B@Fp*lJ?<2J@?QcN6jer91rF#ytC@Tv>rWE%?iL1Ha0|E zE#`WEnzgTc=S9OjxS`lp^4q*hpyyGkj)-aR2;>G@0#mp4DtZz zkPnG8Y!INc3X?Aq^*rLAxFZbzq=*Te%DBVhJ-j>An}QK88Vr2tvo%@sLOmJQV>_>j zI+wcoB6HZQIy1K-%1HN=K1vrM#A*4y_<_1-&b!a}>kh?zr6pT;98vvBDqhOR=+$i6 z1>XPd)#m(P!(u46N~|605`@0!+xV*Ge`8J+T+p7k=MlO=OA8fqN+@vHmjmDXf$+r0 zQxpNsMiVS*2|FOgw8o3caO4OI>0pNuGlx8sVecRoh4;xH->skjk+l>G$kLH%p>tvE zpB)AH$$871Rq#d`vAXexM2tf1K~oTAeWA60fTD1_lcq;*Ufy~|_BVg|T4Ao*>eqC; zQtITg)GsZ=s{-1V>?SMMQK*p06J$z#T0Mt14U%MQWj1F%OU>hP|LrG;Qo}0tmlds6 zBQ-{s`JeE4y6-`L=re|Obk@168ZUBzdCi{l(cQ|{oDjUD!D#QI;PKt3AJT%=x15?< zxDNcv)zIz*AL8{%PA<0a6rPz<2%#>re}Jlpd6cyAF6K%deW% zG>m=Wgf0}y?!x4cv|>Z=(}uw+W8B>|K5{fJ_t}6Zy_@iaYi-&TbI=`T!3mmgzCn|r zr8e%`Pbd4*-_=RoA*WHD;brqdp{Yg|4fvcBu*Y-8E`B7>cFhXAY_r6V{1|^X>6f2jbOi%cV+@(+g||Q{TD9>Keu(k?tXTfa!csF_cnbcx_nYnzUUA1T6xGe$Kbd>x_w4AfT=S7xRA=8E+4KN6&v!Zs`#zqh)7qi_l&1WA1L{YYvQPLajWE6w@F3uo_a}dr&g`Q z9Xqtc?B`I|=+1hzj+IcZ;$kaV78|6-SIQm26opHMq(p`nK1>(?xI&=RB~+w+5i>{* zC-iBdd8p2tGSUCh2_6QO-kYO{k<*<$FWg0#FI;QzfaV?Wen83)DAPY{Z^{IK)RKuH z=0`eaH7oEjJ2O7M@2aPf5>1Z&$DEb7fnkh)8oVIX6_$EN!nH_+;q>FS{~TTh%nkq( zcc?C<<>a0IXsaP{b&7H=bnSZGI86kWtj+ID(s6Z-QS-KUW&j@5W;(8D(}@~v^bqY+ zfVE(7YGU=4&GDnH&PvBmxmp%kck`@YWWFdbrrqZP6``*a{devVL~zswhnldRt)8>m z(?=miGmUQsyKl?=&E_IEE&WHw1pB?KxI??G`*Sl>8&*G#LhQfPf3;?*nuP3aS?=o0 zG`D;SJ;bt^|E`6FRFrW4crae-|~)39#^DRkcw6Dy*p4x-ULa>ILX`<*fHO*W9@c6p=`x z`{hTUE&o3K7p#WYXVoICFR4w|`0_r_p2?4wTRe_MwEo=!dj7>AJFbK(k}mn}vYJ1} zxRP4AE&HK6`)_TcD}Id5o+3F2w16==S*sEdNlU|uELOQ?rgeWiJ-*?`58}!AZYV>r zr_J|=S)z9dc`_g8R{MCDt^$E=5}ObIQVOPXCedDN*2)SArg)I^i-SGL9c96~lU=Mw zb0=;CD-U}CuFRr1qYH7#4(^`urT@CW{F@;k)>5{ah`hg++c+I&PPMl zv$Zx)$WkV>Tq`{E9_7viSdn7!zHV$u>r8?=A<2Edf91^*GH=_Na6zl0>BeZ^M!Du( ztD6=-LQe_2IN1jEMUro4CI{1>-9m5gEGd4gMC?y(A6S0RB|eo{HjL+B*bzO4iS&+2 zG&af?{rt{ZPiJ6#MZbGX;L6_e`o}gLPx`IVwi@^A!+5J=0_(hHI|rQ*dnjzJb%#t3 z$Q2~=;Mucav5Dp|!u}tov_g?A>qi52Dfjh$EAj`e^Rt_@w_X`tG#$^c3TK($dBW(| zZh!%rilz>!%gEV59B3POWEt1sxY$lBT?kHM{MY&Fmttmk#M5cJv>b_^+#&r!<{@=? zW4${U{(3>u?;JMGSs7Xh8=WktFAI@uZ}B1I4%kgXe3x?lAe_SiuC5{&_n4ISTP6@d zJbStK9G5G6U``aM$;fToU*5#o#C;sB>YLMe7nmXL4YEwzf{xeia1$1nQ2+l!szVrh zm5mDaJ|0hyeZ5zxI=OPeZ&ok%%LRE*C*cX>vuQsKT1?!>C=ik9s5 zcLM{{dO`;&fCdr?HKp95M!|Q~mWSwl&9h$joTC1b9a`5%^cqwz|&JrXB!7=^-!bP?@GhQRC zU5HM(`W8bMD;dryS{iJI8)hC#vTJw~|6|FwAFw1GP1R7IQ@?~hpeU1rn0t`i|E6xd z&-Cki8}Jzy^@*GL+o?Tb=EtZ#d*v6aT&-mA1DOQF1r?*Sdvz{3Z$n)u^$cTCP&=5U z9s&BX%`SV9dy{s%GI@VKORxv2z-#EiwjwKf(7sMY_v=c`FZ7N*TNhewZEe^vnmpJx zIrsQV)xFt7^_@NJ>TLG+I;|8iKdKb_$4aHwnjJ7(@iBodJ#IQa2h4#RSjIEX(x4!U z)R;UZc9HPK+8oQ3J4Ca*if3tGVpn*4bcF6VC|x{ZVD{6p-1naQdU|7!R7q}8=={=p zaZ|ZHO+E4@QDgOI%A=fOR{Gx~L0rGX68McI%s1i4qR!&s>X6>HbIoA+GiL{B_~)C_ zxCXl770SYwf1Ef==_Uf+a>NZhgDaZ5qAmP*47SPoFHHF)L6cfQ(RVI0gZ`bD>!N@8 z5B%;GCrVnN~2vWHl$}0!4sZFxcS+N%G^6UQ(p#r6n&5NsXvd{d?0W!`9D`>Gu&9=NUFu>p@zyi{fo7y-rNl$uYG%=(<6W6}7Lh1>LBP`;% zV^xEeWl>N@?yrfhPlO+x+x>K&SNt2TW^J)LtmC5lQfxO*^^UnVa_3K0dP>wi1_96C z>LOcT2Y&1|sd8sdn|-gtJKCG^(1iddFEW66VN`U zI?Fw3$v87QyY)dv#iKsXKP_sW{TL18_rFyTd25J_GISnn*A?0HEu%JN6M;g!O|uz< zPx&sTRw+sNB+bwwzt06NP&G9dfB5&2;xlUD#iDvQ3Gf%Ss+`kABM3W8OwHS}aV$UO ziR8hRz=-5<&T#;ss@ld{GrURi{uQNUb#l^p)N{*^I@VW|*{@RI-7obEJpTM{)HvD( zx#zcW8shwO%x9)DrJgSDFQTD+BVz8bR415gS>XQWr8ftcazJ+z(~>{fN0>mWj#$ud ztM4f@OnDt*1VT<<`Of>xlGx5}T%Q!~XHVKMH>gepcpu2p0AzCY+|Sy@8PpfH^qa6= zm1Nnbt=ZOssy{BMs-dD5zl?cK!PtGO)@Un?oLzkJftI~vqVkUCh>Qqxa=0%h%zVid zHJo=8tR}PYqZU#KXq>{x=o?d{fY_Hl^kvebpYUxc(HxrZS@!vC5xNTE)@++x+fo{s zTbGYyO~AWIjLxz0C5O5Ntha>L+^RKY_nbF*I_D4Z`BtjSzd3_kTEeH~gmOg{kzYNX zl5<_Ys60!%!!&8}CH1Ao&H>xu-Zu4@B8u;+DqhrIZL2I-2lL(q#|OFyoBMxYk|;&f zQEZBG*@k_TJ)l;l)Y5*WR~?Ik3Xt(MmL|egBS#rkhGi+J#%IoyTeeLfgF*@JTmPI% z$<6^nn=LR4=r+EZ6^izNE(rDZYx zkMx%$53=#G+oinD>(KkrP;lZrdqVKd-kkjuh(vS5_>Ag}!qlLz_aQ!Nsl`3oc$m`*q45;H%$iQt?xg{xu*P|9jbbE1R-RX-FIS&IF z4$B%Xbv6EBhY5lbZzQbm|2Y+uFND3>f)1OSA z%P*8myu3Ii*laRpzP)jNpO^2wDNbFWzMWwlfa;cfo!l;^Se0oMs4~%c$-&RiR_xhgD=1LaoEi zT$=`jSb(~S5S>1M;`1J)iFY6{5r`;+A#j zzoP5MZb;eVZE$XD&D7uCVP4E2!Y`2y2$=QC&A%^y!TiaD!QXP{?ar_R%6r4%M~$p% zBws{3;|gdzKIW%!=vO5qP84u(b^fq_w&Z|iEsyu688j!QPqA)H4v zBMAk6<*Tv__xbUn#{!C6bi8WLPx_SpVi@>5u>cJ0Wa9ocbk-*=59PBzeJ?(JyrDV$ zjnj=OO!*vjwB7d2LHvt)H#%{$=jp`H%WIjo>P#Yv8)W>q)A4bucx@-UAADbAcuDvi zPh+?5pT4Ighv&8^djfRcPd)DbHFLZ8Bi@aFS}%-#wAIF}JZSTVr$qo-q3qP?cUeEN zDHUD5p_)Gvyq~WowSK4r-9G}))3|ggcZwZv$@`r()k*JuutA-W%HFSA&)t@#uaT>^ z_1#I^*_tAjI-^0G3K@4CS8vZgELY=6j-3)RCK^BS@&PA~xQi1P;%=o6ZeRX3&%z+& z*_lk`#91qp+$NB|yQV}Wc(jZ2WvhbJ)%2b458&5ehynaig_kNe)9KI!$O)&HNEgAd zzJX^|2eyZYilhh6ZNN`LR$Z5MB^Gg?{fL%Viuhvsjb`<9)=^#>0$Puu4;^moCU`D? zj(P>7)Tp-cF~5Px0DNcIo7Qo|TXhE(gOBJK2@p=bqo;=I?Q(D6`s-iUBOTi8y|>WU z7hvvMNp24|V%CH*UT`phQ37GTbrd<`^CuJUEcj4nR`>D~?GegAGnq9ep4j#Q!d6Jm zD&`Ans$jglKJn#Hl>_z<@b8nJqPL+q?au7%-h~E`T=0)|h#1TIlze`P{d+-d5k3&x z!>7yra^FR|?T-b!@;)n2oGHTGur(E7orL?3F40_mcvC*A*V-~i@LRY#?-DzL)2Zbb zZJ_mPomR|W%2+RNwkZ3$iud?BzweR>FdSg7v*V9&5tE`w3^qmmX~Y9X-=wvwHH|*x zE3m$xBM|0Ilj<4nz4U1vq4feN0#f4~n{AD#Bxk?%&DUpFVB6!jT`l*HXlEWjJ7P46 zunZkAF?8K8^Y80g9b^w~Mbu-g^9xnRC)+CP;#~~ds-#W*=oA?k&bn&cLmu4v2RA49 zch7}98r21xr3fVgdFgEb0p>@XLQx%RaPw^+&TEdR@+pl8&fkP$ZT1h^vDOrmfjVRr zcXtW@f~nr>R6hNI0{`Jsn1~@L7Q$csSLs1br1Qs)y9FNK%KO$4vj4QyydNbv4Ct-T zelakTFSqv`*QarG&s2jwD1%n zvao3Dj7%Z}TZ2jvkroo_JOUPh`R{1{ z=KERrF6#Yn%@9^R;^bGeZRvk>yv8>F(LwD`QVs$9Q0ksS*dYx?`~3TKz&OnyS>*Sc zglw<+E@xXHH3xWecH10#>=;xCC<(Wbeq-adJ{!=41%Yw!RB%Oya54X-8LW8D4gLpDkwUUEp2AiR>;v=-E>ezD=P&cr3WNn=r<4ROAh0Zy1 z zhZ9%k-7VjeVe+(JYPH&=WNx)B<DbO_| z0Owy_WaHI;JbUzNXso-U5jiqVTwVMl|}b{OG^b! zDG*QnuwxxZlv}zU_Z@Z_-7JxOY^)WWIA2w$L}{Xj&VsMJQw)nBI^RLVNi|#bz0W{h zQ5*h?sI?SYB8(x60FOS2$5D)(j}omV3=;8r3%#FfO)`U8EvQ6eu$+DZ_@ zsmRu=s3;%#Dfy3W%Wnf2!loWhPk!0Q#$06M*xMIEgJFpJmQ9vkxz z>k8E>tnEi*dl2@t(l@uh(?p;jASU}(*p$=2kek#WNJhJ>f6S(w+n$9v>SEeWbx`oqTw!lw#vVafCsJ5ChZ4> zAv?n%|4q>nw?Ewtf*YKU53z2Hm1?a8ctqqNTGX77xnd)ntEQ%Z9mmUe(&{I8We=|N z8=39;5hSwpMesqM+Lp7^wR7J4h(IHS{(*Ji`7@%8(rR?dKK}j_q3$h}aQ_l#U4fn6 z^rs@awbY>6KAvH_=f2d_X9CXzwbz9_jdU0VLr#8*HoXDsv8ZuAe!VAykDt{N=Xr(2 zJu@r^T@RfRga}?Bdlx(XItwoG@A$36Fjo_H>4HNWPpjzSX5Fat)?7bNB&ny!*VJ=bSCRC>7Cb_nECA8Bx zGfCv%l$dI`x?7a$Aw!y_(LKW#|41Jx`PZxR4q}Hi<~;&AnvaY0{CE~rRoEkyI!=#H zXIDW3od@$QspQB6aQ z5=oI&n2jy66o~Lc{oGCHKPG3)%hz)ctZGq2n zS=w2oGzsYJQN492)h?%7G?)0OLF#_A!OKt zpEbpt6sTM`*1ww?w3MnsLbszLAD$c>*ziEmErFboh8DWkDycnw<-E*mYOG4TDpMC< z6ec}&cJeeD{HJT~*+7NEOi0TWG1__LB-~NP=u5h$aOU2idjd%z;%|wWBqL(AMsnW8 z?0QwX4OrVvK55AqG^~nQqfcG< z#sN`2NgV9j^aaUjCD;2iqlN48&Wg%{#mMK0Vt1};68Y~c+ctiZ+rmPh5rzSn>_!o< zUOrCk(S<$_s1u?4U?dU-G?>Wt6T_BL%2Ou~vENlGaux%BY>*_=#Py2xlPM^!Ey;Wm zuIe2uMXn2Q*g1aN^jRMy0L%o@=9u$chMi%oAmlojOY5?NvAh+~lExJ}K)W5KXX@L= zS<_wnC%{?siJOp52S31FP}&NsijJNBQ8hli8ncQSip~VZAFit+ChXgxbqYICO9f|l zGaDfZcxYCfyYwTK%Uv?^hoD$MktocBT@JP(yZW+S>eZ2Y^t&1Kq`yNz5&Z*|PCBh|4wsLw6cs4v-WT_|l4LMuLi#D!IrRd~L=>o%DM{d@>?>^3a0Zd6s^??lbT}Itd+@k`a)qdt z_-E_u#cDLeL$5EtVGtQl%2qZJ71?YT;!i_}xeyp^(Ry0eZ7U{++~V7N-~Y+}y4>N7 z65}v@iqj9xKVdsrUq)@WK|cEZHFfe-`0RC+PX{0Fy@-;p^gy6SR%y51IF%kjxSLts zf5MZF1WDf&yK=`(^Y!{6Ch#b1c94`pE;>_xUT8+%Jk{CuaZjDSh#53~8ztUk z6CQL9y5IUjNvc5^fzVWz&GBw#@F=QCO^=4RyH^-%0OiJ!ih zd{5sp&_ut&0ttQmv3xY%$pZN>bRf2C7TVLo+zpnB8Xh}ribmMFTxz%Hs~Wclwlt_$ zSjVfdrEj`tFE#Qg!sL)^jbSkljIRte)h5J^xF&MZZhbt!@>PU;TJr$iQyC37qUh<1 zfyYJj-_8pO<`)D5u?o(}#-831l1gRh_>WJ;{_Oa&K;){~>#ow7e}6EK%%38F{#V9R zDzX}z1hj-)j|L7I*M5Kcmys&fvxeVqym|5pG1MhK9W=EuMY+CCY9Sz6obzaXQ1*hz zO^lYQTg{#CT`sVXXR34&iKzvPInf5xC1>J6CpTD)Z1q<4lyBI^Q%ILjce(& zw5+Cx9OLS5>X)_VEn2B0+JxBFmpa;1EDL+H=Upi;Tn%od#zO3wUlL`ufRbokvn+`+bK&ej|~V9v-zAA)X~{8^EQd+dc4|g`03**d*nExN^cu) ztN14La;xw{4Xw23g>A;8d--R@328N#VNcmT`&Uw5V6w)?Y<#|d_XE)Z0slpA+DO)oSa{ew=tpIf$Yu-wi`$JgCG$^+ z{OnH#__;QfJmCh=VhG^{Gyzmqw_QOPvn2l^N^D*uGR6m&wsW(DZ$HK79N`-}*4l)_ z9I>;I-o=_ajGD>vUi|y}S#y0A5plu`6P$hVzhE}U+0^`Gb*Abh9q$Lf&CIn=_Ou8Y zC1GJqa8&!0f{AX0NYZn;tJCyT3)QO6^I=u(f%#XXLc4mc3HSEJrFu0l71Akvnsopnfh0@bIeQB8eofTsN|Jt_ zq@vZAxdSz~_R4xTNu=j;Vls=w^n zAHAmL_(5L&NB0gb5G+aLPCSxQSdRHQiEIGbB}P>~0w1fcmeXCB_MU7lA_CdYIp+qO z5!<hXt1*&Y+b0oo3r=%{GCs% z?czV7%kpd1iW3iVm1lO)I99LZrELLTJ=u2VI;aLTcd<%g=Q$n{MVc+lz24x@t_)wS zwR~WEP`{%ztM7GBsC|FPb z+N0-lv-RM&9c=zrlNIqm(PUqFhAvVgldvkmUs;Pf#-B05ykyvESn!QX7^TjFM}xV{ zkL|2;x);Mxbhz9G0&dgZoIB2)BB6Hm1+lOS)!{`-kvQ@CY3LV`lD0TD*`~QeQwWyM z)>R&Lnq2-H*h-<9Zkc!XgY0;=Q+DIO;U0%LnqSTRgNxlS)9+dk8*P4mZqcDKHYt`L zD9d5neB*cFz<+PHPBRDn*7oD?Xw!Y=*YAdnIJ1t6N$*}?q3k|o+G+8 zJz32`W&Y>P=y#bF!8rg3WCI9l$Tx*uA|rQhnK*r-R||zsF||U8*HMlu*No`ULpn-* z{}i`5fim1nkFnX%o{s4Z-Fh|_u(l#MoA z@E;wf_uCT~_MIZX&#-6P1;|oDqe4%q5JijJRAO2ByD091N9*|0H}_ci?HvSUv1Pge z+}j5~VI_D-kFyH&Qs1bf^4lxI{5$W(o$iRx{oMLWiwK4gxjVoh!r>`*e9eQ3s;ZAa zo?*+cvL_S)t3DD?q)9;+s=4>fR3|h=?$kIa`b!^ zaGk2ddZ#H|1f;QFL$cM5a1-4}MSF48h-s58><;(YwSRR;*6P24vhKy^{cf7y>_dJH z*E!r-Ov#ySrtem4_Op4;5ZC=EHJ!Q%&tMxkZBl{S6_Ow?2ZNQnY={P(W2I~+XRm_G zjjhb}{$}LD4-$cOOq%k7d>#kC2t#8!r_Eu-^M7X&0)o3L4EWahZGKX=3aN3ytY>P$ zugO?v0-p4-zO}k)NY&U2A@Bld* z_I&(SWw}o2gM!KfmPE~K_iMYTBeIAIO7&mZI|ztk3+5v8IeOn4_Z8ttx~`wY0ND-L zWCKVDFKiFdyMoF~&D`wvpY0;kRiCI~|3VRZ!~~~jgF4W^b3aGvvS~NOZKe9?8;cn=aV6OTJcgkbXUX4OiW3oeO3TAhC_EX*g z-=1Ko0o)o=0*x^@Nmi95#6Bi)CLQ%jH^2F+9k)9GM=UE&n7hjeHRh-P9Rtsxmq8>1 zLA(bP8zw-}0badh%qUMXQ(JnvR;b_l{O=YAl|-`PYeMVr$Be7|N@)^VeoUj?zjt-T zw?oFMIYA0z1EdZ2h1SnBJ_0bi@z^i^@ zvz*QB8D3P^d@OUG`$95+{ul_pGna@@{2I`yu;l6cYfUJ783dk~I=&Tr={ zpYyMO{gp4yb^i)K3kITL!s~mv;(Wd6O@6$hAQf1h{#GPk!Nn(X6mxi}>1in)|7ro> z%IdtN|8#B&>A@^=Vv;{c=IqgRl8H{-;ybi6)RgOI4B4Df`BH6r7Y2S8x+}zTQ(NHF zuMZe-NWcwJtYxI=1@yd;g)n}gp5VE_55hd3y(W8pn|hF~ebgbvv5k02ChO$?qnklvW^bYARCE6^+0L@Eu`byL`S7faTYQ&!ZA`wkTy&VLGdYpy@=@>g zCy&50j}VxezWgzFWU!5Q(I)%P?oSJ5bh*t(137qsKt#(K1+)Y@?|kZ39XiD)Qi)Ik z@I;2Piv=N)gk~L%N}DELtvBBeJ`McEau=`$F2JP^s^D3wuzi`|!`jH0890aA|MM$mJb_n)qLBA|9CV2BlZ?3UnaL z6;hG&_xl!3CNuo0nc;NW^X-0b6&xg5i9KPMD;@LOx$ zDkkZw+K?X!6TnC(@c81)x}vy}(pp3ARlU}U8tv-&d#M4}Z+AetDPsES3SP`S=#d=; z(nWHM7?P>tte%-e{UpI=KJbXaV=wn#^5YMD*Y=74zC(0_x}Tg}J=V_$H-~&i zp9WoBhmh}JI|jq}LnltlY8V%+Ff(_@rd{jcymavt?073j@DoA}X0{sOd)6CSGX0+C zM@)loQ%r5fZA;%Z?}Ry(dV2jEbhjHwi%PJ?3#cULHu*s~;2&@N&JMa*I(WU-h{5HH zYdybLNTAK(uVCv!tM>H z#=_Uoq4=s7MkzV8Cs|ReU1;2}$uTpF@2-WeQ}>XcQ^pbcqCsAgoku*??pJ15jxNai z+TQI^H{_r{(UePB{7T@wOcALF%J;>sFDiO%U8R(n`lvMsPGif?huRsVgvTj`m)EpN zU1zGHvk;C@xpvp!J0X0}J{D?c$Gp^n4jrNEUEHtJgbWg-l`vv$So{(i6DCLzBdWfT zF05|UWaY0&)$U@?PgXgznF6kSS=)3Fskodxu|yt9`_&j-{LA0+&7SpzH^eAC>CH9E z#?8>o3k<@m^rF7Q4qAoq+lcUe&eDg!|IL??@U!Tf5-gSnC-2hQ9yMH=-nkrV(@Uqs zRm2~}v<#73C}#D${T`AYa2y|c*C7C%hk66TyGXWge2^5B#)>m}7WeRC2vU2Ege|Qpjk$UTj{8>A&Zs z{;8xcswuejXyrbX@`Q}?T1?a-WGyBzl-~eJ{}Z zJ9ai|?Ec3rfLp4x7WXjhvr<)i++)$qo>K{cwz2vE?cYD3iA18xz?uX6N=&I%$!!r2LCz zw9Z(Od<#kpd<}JmEK(&J#`wx1x#A?7AeyhqqZO_HMrcU|8g;A~F5T37_u5adzRDDJ zg*=P<#1Y8WGq5)Qu|(7$F@4Ld=W;7aQO)`3K(xqWjeXOHyWfb0the&apQztg68@=k zBPw~V?0JkR5EwcC>Yd5~V057r)pBr4Jn)Rbgw|v|xQtN8m`{57>X;_U6-dr!h& zVPvGGpY(iZk8+m^rxzastuIt&8@5zs4jcR4W*SuzqRNegggAe18~c$gl0_$(A>`9{ zw1p&Y#V@Z%6lQvMsCnI&O*;)duo@^sNuq{)Nnu+BJaQ1= z0V~DLL}7f_U6)ezWDmiJnuCz8`?WnvNC<)vW~?2|qn+{c+6sLgQeR`C zO?6if^|S9_;l=LOpf?84P0Y8e)vhlrc6AL{+is-ZqdVT!^{O+uW3OV)?g|<@V%|D6 z5eU|o{iBzgJ|rVDbgPhY{Ve~d>fx5LUKV39`bLEdK8K)&v02EAF_1g)yqey7FGx@k ztF+ws{B}WjB-4F4GRMiv0qv=`sO?M%Zb$cUMlmZrtdV6aQINC7oG4mno|~4SbiaNH z!Gdv%f*;H_eB8CqDwiAg;ZIrIF#1Z(ix@)Q4f1$>b&M#F7QT$>tE=^ne5C?(i~uK( z(QNm|)0e%V&uRN;9``ck_qEc#pT7#9i%#?xNt;_Jta!-DnTi_BR1NdLIF-yiHkv6c z^J(Zzz9D74j1AF6hffR&^{pthkji&UO1^qaTM2?xJT(MPD~vTb1RoJcErd5xoIZots~UneZT=zt2jN_lq_x@b1S{3;eWMP^SPb2NW<1nj~xaz zE$m`&aF2tfPlW#s2@UoS%I@r&`P1x*m*MDzl>72!zh~sSy)Gb2F6Nn#Px;UMnDI%Pj&7Ts&T0Z4=xUU6CirV=~P2vHP;<&U20npDf$OSOk`HP z&=td0RLjiyS$*degt^TbB*k61U+gAy#_s`9K5Ap50YY1qNt_$rWNf#Z52eyPXbd|M zVO-^49&MACcYUDQ>R@@3L7YeYP!%veapa9@#bpFla$QRF`xmg5hZFkyOTRLj1n~)$ zBc53idb+QNU1*h9n0ZDg%vWcYDbQ*tcN%|M(t)gt-O0t>xr%N6(`@FVd64?nOE&R8 zy6YkO&uG@oCO<7U!6HpS&g0{8I-fqH3Eov`-?7(*5gL^n&=e z<6pPZALp&V+qaZA+IuQ@x;_F~`nh0-nE^kbJgkrAW3#V)TAx&@^tSFUH~5=LJ=q`s zA06fD@$#NRT37ypAiF=C>ztZrO~nXOKai&3gPdK*YsLofUs|LVF5KO{lGMGDxPmMU zyFm)lpL4o^x=fzyA}mT$l0;!rV^Mt!Ao#Lm`f4Tg0@$A$w`&D3#Z30c_93MgIKvmK z789951!0v^>niH$7EyD&D?ug-%b@8+jG!s4ud!-;8KWbMh%Kb=P&+d@ki#KowMe0k z#+wV0iyVIkJX;5Jgn0$D**x@HIf8DSso=0X-pdIr-{H8-9wpPno#ex~@VVp*wt~!t zuxsfOgGC3hJ@&U!4!W2>$ZxHp)YN7(yS0n%T``8CR+C*o2Gbkf+3Eq@H#^9AOi692 zFV|#N;D_r6>E)htUr7*F;B5HhKRU;~3ycY`szxbB4t|jvx8n^_MQj5aeLM9g^=Jwg zGmbi)JhklKHMj-6_fG3lTzW_V+>aTEjEd2!jMNP9;7h}VQR;9I@_#he?Ol0A>9=F= z>l&}DYWQ|gl7dS?+Y!rr&Itfbz@AiZ>z+19A5M3goW*rESQt76A?RU0E}1Vbbp5bW z_-*rr$22J26}6ROHHjoxkb=l@tDDe^s?f`#AgL=)Y}X?uYiNHG{*-XtT~z9Nc2wkj zYnt|6HSA2;;VU>nb#i20I9;Z^gyEBCjEg<004A1orlPYPqU3v#+qJoGQCVAQU%1pCOZ${xu$9YTr;~|!_>3P*Ay=2 z-1EgNt@Ha}PL|v9+5|%f5WGaLimL1#KRcb9c8~nX`_rdG%%G*>jUjm7;>WgX@!lPG+z9#kL$tDk#-nW0FF#W>nAzzE z84@p#B=RQ4k2H&@$ z^@}syk+7j-NJHS|Q}YL^)qdLCdHx!^h@3Scjg#-3U8D_N4+CV2_kNLEmgBC?(Gm|vopx6;nn1>6O2|aCdHEMdEEwOADQmr*t=)SGSsj?rJ zF?U;EB0f1T_4eiKUrp6U3xjrP;2gVi4n z=hmLqR796a7rrUF@}>&m5zlGtCW}C|I8e07nae-`djW#%p~>ZzmHoJx_#xFx#io3n zE=2Mld}gehc8(la7b;6sb(PLr{ag#&Qe#d-W)W|nza0i+ML%`EEBTC^VS14SJ;17W z5n^KomWH9aAL4rs)Njr3|MJ- zH31$CBzFxq4lLe0?i;XT@vdv24yX#x^Nyaj;1Q@)5^McL&7leWd!-7!798M_L23+= z>S>lr?CX2{BN0{phJ`t2>9DN$C305SGNUG0e;Kr$N8DOMb`HwKgYS0ZVSazjE(_9Ee1SXrMn;;mU){qJp)1{GymBcN(PP1UuIXS|YCi1&Su90mjg|!B*59u>2+sL^$q*iTI8(i1goZH6>*G{S*pO<5VL<_(KPv zRqm7rsNN(=oL^ewLg&K+ceiU^DP{T#ct)V}B}6i-m%jjWp)?IV4eYc_Xk-m4{Hs!R z7pmW$iMuZ|a2ErDxviYOp*nBv#Xt#A_;py*>#;*ePmAw4$Cc&`{R+)~d|q%< zl6XMEQ8RaFOu;r_X2QfqL*?z?{@^t$lvMxWKRR))NMXfT^pea?% z|0yq9zG@l*C0K*3N~&Xh^wOT>N?4~|usOSJjTMYrzUW|D-pSpVwEP%rHAJUG+Jn9$ z2hrH>5cGQkDas0wM;Dy?YHtP@z81Rvd*oh-B;}AMxnZqHKqg45GN5PpoCjT)<2A5= zV9I}qrEh&pkE|2)3ub7MFnnd-N_rKRwF4cvhzOv2<0XqUM?KTIj1{4(A3{G`Um=R+ zh>!WQt*;JKGQtwy+L$h$A$n z&R{keOmy8Y_;M#Eq$-a&D$+x1+=H_LJqi5~Rx8t!jf^(jKqywmSd?l|uqr&a=9(hq z5FsVQJ@1r4CWEn8dy_2XqU~*ii^6`CC0APLGKs2r=?_*PL?j=oE=*d)(zO`B%s zoB%fuGfOAC0Q5oGp&hI%h=^R+}_G5 zEoP0kg^pF1Tg&UHRe*-{mbd`V-!K^Z`XW<8fOM&e$va{U$Z@6+nYYDp%tVbwLbkb8 zKq~KLRGMFV;L_FbFt)QOZL$)e;735%?TP*$efi!u#9t}b5pUs}SSTEO0}_Iy=Kb>3mcXlP0ta?y>}gh1|*F=pC&yIa)tWcsx{; zVm@+I>fVk0@_K zo(ao0HpYx=$X9v&Y0~o8+ef_IIbyDbh(I0aAc~-s*DshJMZqzrQwx(sXO+?qJxdkx z*Ki**AAC*?J%$0@-MUSpfiSp0J^XS6#;$&#xK!1$VXfdAb#EN2!L#Mphbl}L64hL}I8|3}ez$5Z`(ahwzlBc#Z<3fUu) z?NVPmZYhMgWh8rV?lp?6dyORG-pWqgYzo)DM%?T@uRX7IUEF*7eSUv?Jgz(5pU>x< z*Lj`it4{OI`vS;Ce#Vhg$d5jL)ZFn`;c2$BBj{Zi;N7kA?7&PQ7n#BAnw&1uj(%^2 zN!uT58WPmoysvAeuz4gFrb{&6q_x8B=B9cVz}ra+Nm&XkLLC857>Dl}Wb<%xGd|}< zsse4^RXPm)h>yalQUs0H3&UY{TIL#;EqNHV9G|+MX0rRMBD}1I8oKs-;l_FI0HF<) zmHYYXkconNdmhYAcd^ZJ(zi1kQP1w(7!XmL#T+8BOHe{C#&RD>`&mB~r5^ZtJq3|j zUB|)Bc(SPM)~hpNS~pCAobH%sBmi@(-MQh|9kC)>YOrH71(}w=QkQ9xK zW$yP5br*Ynzx}{RUHvnX)-Yv=uSOn1l};tS3e1uh7uxC_MC1LIihm(<4(cXlj(8K@ zwhn7%*cL+<98S$L65N(YNk484qr9tD)v0WcEH+~kXd+>}O=N%fydc;tk4K7JZ?p1h zz(qot0wSiG0tbF8b@JZApeWgCF-NkUT^G{rzcOypRx{E*uoT)Oxg^UC1MD=_bFD9- z9kxs(w#qch=*8OPc|VbDtH(@d|TYu@Yj zq~?A!OSCW(2*R9&@C{HPcYYE7+_;%GH~rtUKjFSHc-WVaC?>_%e*PVK-i-R6cds%s zsRMP;VQG%CZJUF;jGbHqq&z)_+kV)eR|9-{c;cjW42_a$3D#sLyq}pYg?+48s*fa3VZ0WLrsbOXs9y&&qldDw& z{ydYXMlTU$V+x~$%GUiO%DdO=Fy2AG8Tj^S#9fJotMc?bbcb{yHxI~R5MjMA9PICd zrB#-cYyv}c_RDZrA6(~E?S#<0JNKu3$`o*-%X~+;zvj6Ke@_K^pVww7Z;gLn@@k8< zQ|XlR#T%w=n}6lMt)^?DB~VWbKec#29u(hcnb4eAB0kUXZvJIN$j){Px5~<|-{Bq; z%jZP*MWv&ddW_gR2U5L)aDNXBo@z@Yb%Ii)hh;2a=MeIDI~jw8Mt`(llN9|VADeyD z!mk$Y0}(iCncR#CW-#oCky8>da#~p(7MM9O7aYrtKN@hH{T;z?LZ{KqxA@cb%a>Du zh53uG1*C^A+9}zzDh%^uI_Xz6$UubU##u9H;#k~aG-DhkW~x`?_G(zRu&_*$d`dh{ ztmc-rA11s|SC+6oAM>!KQZPS&$anj5Nqf~2Lu^#}PQ z*I`{@&SdX-Y+Tl1%~R`paynf)sU5>NWdmJ7bu7Y{`7we3V1@lt$Pa)AB zcEMk3S@&?+3;LTwWARkiX7q{V{t@*MMmU5fQM7t2s2b2Tur%BqIic3^kB%KC=Ax-e z9R9O!tHaoJpFg)ZQS>peSsJj21>DW?nkp`*jjfs~w?&!+%-zEO_^Yg@p-|b2*b)${ z%cRIC=1zjMa=5m%*GqrXT;c5wzupDv1;wXjF6Qf8e?Hcs#zpQBaM)=u_LuTBuR&e?NAYMzo{%#lO;EQjsEy*5WYx}yu9Z`;@iVU z9c9W^JzqtQU!N99d?~kC9RZ379b3+fZTouCe;wBYX4T|)GsoGW=es~Pyn68dfVr7& z0z9ih!~Piq=KEV0=CSNycgdgq7rJXNUS>!`HYlsivwp&)!kwhS7DQa9=N8rF9QrnO zYhMpudJQ`lOL_9G52WNQUcC3&Vsu4RH6~Q7noF$j$DCc{u6U;#Gk#t zEsn#Erg=4qW^>cX0SK$%(0aK(;miE7;^#$>z?$Zbhz|8uOKgnr(pmJnEs!6I;czv) z2Vu_D<2ivr8eoOh?r*@%R}5tu^lA2}u%AH`Yl`G4gnqujB6$D-?0ia~&2(=LXOz~Q zz~}X8O+8IX^`ci^5i-e{NzbYpyoM*!ErZpU5OjVA{nGTHJ&Ba5dSd?;1hv}P;+T6BVeR}k&)c2*^4+w5bfcwjQpoPv$v4gE2H zEGNVeeH_9JZ_Kz)0ZnVn`lD%kag;%aPe4tjT1qF|p2e#I=l@8`hkbDHfni?#$_{=h z(b#!7Ek`e)?|10POU*}wMo;S*lLzUxNBl9Lm$SvYHDZs-qGm_0hHD>|O?p=-J4&WM z?z;t;scB}fB@HG*h=qb7cGZNW8@IujO~boYqAF!YZjPb@T(>Hj>tHUFfW80dxK#+m zf+zzu2xPGIy6}QGWh3s1eM7bG1n803&x!NEN3lpA z-aC#rwYfGAIO$fiipKQb0Z$C8S}99DCynowU&Jo*u^QkWS{nKIPk%XvL_Oog=W87h zcA1Y4OH%)P%h)NY@uf@9pO40M=cn;j6d|3MZG^#QDyTUz4y=9CZ6UBwcea1jS<(NQODK>JJ>nT56$8TyEub{7~^S@ej zzoYMHCRofQXt58B=r4#-Ka_>Zmf;Efj8hk_y(Nd)proc)E^6|NsjBi%GY}O}e-k~m z1jewAy{ax7T-ZyOnPadN8n|nAgw)|358&e{wpV9UEU#USGL$1r}t<&N! zQZ@8OOL!f0#G@d}o#8$JgL$KDYN0XPzJquvt}B_YkpJ%bn#$@d=HnTUi6L%gmXC_2 z=q&P|8}TEL*>`fwu(IxGuMZYMVVyKFwBO&J_j*07m-x`Xaci!JZ3~IXfV|J*v=s6C z8$*O|a|`~Y!*4W0n4!)=31T?%@>ivpohk@fLF;N#8nh|+)uz|E@}!H@Yk#m<2jU46 z+f$11c>cn=oL6^O%xS$7qFD!YjR`*F@~TvIDQtuCdE{q?0tIBqNhOWTqC=7@el%4a z_A{cUlj$QrtFefVOs;ADNxe*F;G0sZJ$cU79VV5{E)pPx7P&mp@pW8&Cq|yU$Rx^5 z!LmbNXx4j;AqzH0DP31l0Y|{r{Uaw#eu&arO%}4~Vwk4@nr&i<;k;gJMiEKYPgD|= zsdVZ-QkA15Gs{hnt5?)DFl=>zeE9ifY-JO-=z0jkK`W5&{cx$qYJS9Td$lV6_e2jA zQ4|{oGYKQNBrDaLZ1Q}O1qSQu7F(#!hE?QxlN|bCj)#M}S6*6OTK76MFieSBbI(Xk z%uVsVjZF}r-x^cjF0u!!q5jIzy}-o%n>2bSEvgQ``hwZcd|BZL)c<}_Mb8!8G|Nvd zY~l@iE1A%d^qIT6pHU(DbgXoWoYo?6r}p;j8^`nZyRu0_m!9SaCN2Oqj&NGLw2{~T)v|9>zY^J*#AZ0K=)m{{4o=`xXCd1T93?wbBurC z%tz`LgI2QJ*7MuOW-?lFIkf;=ZjDuMwDGeM88`3x+tm2an+~mBJ`Po)>hKTMHAq$Y zi904tZm&B17cTToZwrA(s9ZSI3?BpJ<|uAM44XzA5luRa7fs31!@h(D-2b0{SL6+1e!xs-0u$K)zczapRU~W#7uD zeHc4&YceP8`>!ai^;AYJfwq&em7S6W$aR;jnK7itkEJ@J;y?KjcyKG*7t)qmU~&7x zu>IGhn`NhH)$o)Z>FeUR-Yh*yWFJ229KtnP4^?$mLR3}agCkxhMyBJvkuy>$-63qXSLzjexnzcVgIC!;di-qb@dqkA-CT?Eu2?&*vCMWnn*xP7w27-0g3-fSoJODL%r{ z_Xj*$aw$WptiJ2$gDm_+;TKS#_L=*H%iU4{r=#c@R6$pv`u*ycW2WM6j6Sgtm>y5` zK1uLEc{Zqsxt)AO3SWT0kAlv#J%na)sO{)GJ}M?eM})KSO|oxRBWHjE0}Mad?|m+^UKs0$Tb($#DBGi&u5k_h;Slrl{{<{`JK?KtG2Ahi zoHb*;`|#Gg3HXfrG=Pkz6wKiyx@4tozTpIKDT9y%tD8uFuW7W9pM9I+qhZKG7p_eSxpDT^f$Y9i{(`Czzcf*(YS)!OJyEnMd{=TJjUwH)CupMRfTe9Ubla z4^2i29~oJA1sT&M9rH}^?Gr(-wmGydZ8m*%R)iW)u_wK@zU5kcOGP6S%j`!fIawk? z{{N*{T*<2=mSMsdjM9#q`V^+bcYenN)TsF%V`>`M&h#i|H5EqKn7M0{+t-+$%SIW^ z<#ZS(!|!gJ=9=@Wp>M?#b5jmpeXpbGjlv|T$h@lTSr-&f3ZFyfE4*hRp9LOuo0^j~ zd5Kw}&rO)yEJcX}LX4bkbZP^TYoN)w)_pkeJsS)H5SW?L{E0hvvy=9M+59~Ir-za~)|5rfb%Di}s_P!H_Sz!oU3R_u2gTOB#2{*15 zd@gA#oK~ab`qZusegPB0l!iQn;nB?M54}m~3qe_z&L`~SR)j*+HnT=m;zNx2tH`;^ ztq(@l=Kj*GwrF&<@BKclj?7=L5Eb&0@Xi)*KJPT8a->nxuWm^!IBq4XG|;nS0}8qA z4Ac+R*{o=V{<{;P4zH3=x2lJe%Wr)UlL}sX=}#$HM#jyRAC={O;}2~cdT_(D?|Kk_ zWmL%Nvl6BsRxf?nX%xx<^i(0H&Ld00vf8EQ9Iy*s#7 zkOmMxK^j3!2;9$YXiXrzq6y8BB+=tk!@lH(Qb@kyq)sR%VHn8iXTs!i*@X;hT+F$p{jKYRjnE%_Nv=s^jXDkXC9{4zr>vl`vCAb4cIoh6@ZTht5)QP{k zrpW*x{%*eVymHGR;N0gu?V-0Vc(#DF8kgVC?V zes?FUjEBFgQ@O_kc`RN^>1m@OE+ef}NM76OxIuoe&}x$83)*0Pv~iZH`a$Y;T14pb zFZ97AR*QC%Hmu6F)wqy9)Wp|nZ8b0b2-V?zEG@4suwdoldFddf!v^*`|M!Phiz1>xIEi^)Sz zP`&w*g^a2@o@pn*w`WXlBAEc1r^{BD^~ z-fuI&KhW+}b7TA#wmTEoDD!*+&pIp}_J8R((Pv}!dIG-UEL8n+u7v&h$a39~?875Q zY;ai<19@X^-WI*5W?oL~zr&{JKJ~qXc{vt4hFsk%q;O6xK%0#@Kx8W@S6Obuu)F>n z>FnbD{vh|llK_k}74U(08oMsCWRh)&-BA-?_h-h^FDt8`W7Xou+>m#cG(g>VO&w~- z&1ve4_=g+W+H-w#oD+L+knNA#$H2%+#8l<0uE0b7k4LT-6CE(;PY0c@KC4 z`}kT4*%jxxokPksXVdqOUWK!t?l6i=HnNWeL0dyCqWqSI!;B>wTX?RnMjm05$vJxg zg4{TUtncavxwV7-QB|>j?m>~e-V`4yo3`n;3F)tSUfAISJhRP5M(q20MF8ql&iS9Ct4xe9@$OA&ppg z5B54u1sG0fgWq^2-o<~N4f=S>FJLx4THf;@|z8~&a|I}6H5r|cX8#X994`me_Pn4GCH?sUB z$A56qEfwt*+sGOysHt@YjWTV~11+f*v38s5LSgG%;=c9TtP-6La~u2QhJzP#__yri zgj@l8+9Czm7r5XJaO+t_Nfkrtcjx)-c8${7RMib`Rn(=9bWq2M3FuC77zW?eo+&``3f(vOo&$SZxokg@_!4BKBRS1e~69 z_z16A4IPk5W7Hay=9a7j9~(4@!{y`u<>fIb&`Yb_s+57l23^^&Ka7czLKh zwgy0HVxH4v0IGv20hfuAOTfOySQ{J9LqYYtn>oL6$VYuwz+cucVzR<4fRO-|`kiuK z3B+1f>A}=@CsXy2QpgV{Hyn)$mpHL#M%N&>wTYvPVia+L`!lUi?Keylx}LFml~2cA z6V=|2gnk3Df#*v>Jcnd+FyC5;M_m!U{l!of+rUWm0ig2HRa++=tJ>whLLq(7Yew(Edgu;wqhE{-P z%lhSv0P3lK3PhwN#s98!aN_2d5A{a2TkOsOt=N1Ks1lv@0~kqaimYW!+Uft!v;2xU zo$^rII_YPk%9mx(0F)4g)1E-wKfLqz%dZSx(;nY^JpPe&G%GAd!3-EJT@n9-UCQZy zGvfIMKbGcNZnuqkzIjF+rtJp*qg#4U3p$>ujAVtrzWfCw&QQ0? z#2>7pSx|}#_GhSG(g{cu>oic-(5A6R|MkO6Lv8{$G!YtTrQvCCK}HMvY#aZy z(_ar{mtcqh{N@QmC!F|5cJgU!lOsNs5xvL-&D6=GJ&Wb(68Byf6OD{$x9D`5(=(Cn zJwmbcYb-d^*pIOc2eT5VLP3!qX3gYJp2cq(d`G{9D$xv)Zx=^VJuG`+TZw@O$-YAj z8aT39-O*<6?N=Er%Qb;c7=efb1bS6*FbF@7?u5n!il_%JE4kd)^qVUqf{

GAXICEqH4&#&hiblLYS zZyiM1{+E5#du$rPss~G#?7jUq?Q$FV{xcH49u~A3-FWYhJ)1;1kdRS7? zB|5gnmL(cc2E$?j>d%T1K0YhGOYQy8xMQ7XQ)2|51;MO(IBFWt?I^fcjRaXWS9=c)$1k%r6D5~38}{l9Sd-tN`^mV;@fTK zvub|zOM7Az{r|sIQ;LpDAQ1xewR_P)^jtj5YT-J=Uy!Qt7(* z54LTBGZ4?Ea#{ChFSbcsofvjG5}`qn=}F}1b)AT=pM%|$do5DZ8ad9wn-IM9KJEV6 zH@G&9A9}^oy0idYacg=Hzf4nHyPs@jn6RYm=?(3%%{hBY8$>Z<`(g?O^3P$rDjd#f zT;kt6!jsggB{G^KL0$#~=iBAj_msUKnFMt{ff33a^3UetreV_^57W>ZK!j(;-|w(5 z>E%Kct(scbtJNMjZCI@Xvf(2ENn74GG!lIm;jabyIR!{TT(yI?TO*X%Hf=^fmpErd zF;-_n179Uth_5s%s;Y6znaBb7K%Id5UO((p;#(^tvIFtUHvh5T|JwsL`A4^4b6A|4 z<=Yg~S7#2*_@WW+vgH{S)M@OfCxq#3=Jz#ke;3I-PAK&+;kh9+gRn>pEV%bI#Gb!? z*I3@;fhyAKht1=}?37)z{tM)tYZwhU-m0P^F{k0>mlB581xrY1L&T zv(O26Qgf&&-kYc97U2>925GU-M7U}qQLdnb`h|G$G@*#6tS7S}-%2YB~HOgQNBzkhqaORwR z#qAV?K7RR`gVc8o$jM5a%oA+j>4-&rLI6(;69(Fvr!sJ@B(YMgd)IPM?$K(b`Rucl zcrT_WhewK;;snWNJ|~`n6vqc9Tbzk2^=OVY;>Jg|D}vqJ1g-)7ajB=nh-|7$Ze3D5 z_7C92B}~Tr5Xr44-#80_b=BA^Gg%_$e9Is`^131Oh;%Y!5kLO@#MD5_C|A6Tnbm~N zw+pkQ*Dk;@=-+i-DZVs2icKhsm=sEKBFg;WZp?E;K8?(Vo%`)IQg2=;9byrvM;uuM zPpEaCY8klS6=TZwQqgS6-N%TGz^(-C8px7*uhUzoT;@%g+XwaqNHdG*@xqp@$YA&F ziAzG<>yfk&i{2&~YLp4j4-0zjv$jNs!#+RNlr`To9+}uZLg+%D)t_LCkA1wHZCt`^ zJ{ma8K}i!QLXE|Pr}k>#QW{EOsvNWa5C{ILTha8=^+JvXHA3S=2o#~X&lLZU?p3kh z6t=qQ4HS=|A~Q_LXFvaIUdP=?O@0Eq|zezCT7ncq>yGZ(GOx19~Y) zez!$c@TY^{Gul3C`ia~>I(-#x>23T1fY8j&`(eK|gEu3VmFHVV_+L!b3S~#*xa=1} zh#wfgJYrLnq51C==7LQN+hQ2bI>On`pAr9+2 zf|=-ukkNvyO2rRP^>m5jwtEti9_o>}pCrr`ataZxJ+jU7RmZ|D@*Q{gJWZ&~bwc{n zhu&nmRTS3hE5^2&P z;k_JvxY$%hE%kstCVv$c+`Sr+x6cUw7~B!o=jkL2zqc7duj~og*9EL)vxWZ!$PZ3F z6#X>6M1#`44kl|oiVzbWw=ebI%Zq%l(YzCD?w_8)Q6E@-^Xb<* zZKw!xB3B2i7Rzrb@iC;N^=rTlw}pv=+fr;7d=V!ajPQO5_HWa%ENtiZuLTJ1i^<8| z1}f7vlTXbmU7~2)rjdNs{NiPuszHguT)ubs7inFk;%-;Cr+81mPdc8;iQBK-pCx#c z2n>Uzb~oc*WayQKNsYyPUNo|K`n-<%2T~WKeqk+Gg@8TjfOQ1vk?P16;jXMmiD2Dp zSM~{C_)tNZmT?XTPnrAPo!Tv{0_i2Lq44Clbx-iUV^d9V3749;lej}GG^Zx}=6#r- zMfrdB=PPPd**jn%6eBWWUUHYOJAbOb$*j`-f^`7oA6?1G*lJc#v~^9=H^f4X(SAB! zptb%^d41;O!l&hW72#D4rlOKU%Z{B#Bluw>5C_?}^ZMR;Z_rnR?gu^(Nd54fP{%*E z0!Xc@zdz1H__R0^!#60IIjSL3loW*U%$HeJ!`fCnA0zCy7 zlC1|J?7>d%$dOw_U|?12Ejw8{FqIOG#1A(7qkBO`g)tS2O?lh`Z~1rcut7asm% zW7g^1%6!vV)^vT*hJ~?luJ#8m#|wdo!!7_**>x`Qupjnm^^~osOlRvzE%>~AbJt_K z_I*Y@4PacRU)^`^j90zlhm!Y+e~}E(B2sm%3`!SY26fWmi~A*I9b#aQe_Z`3XLL+Y z$o56$NW9xl1UrpqGqXnzF*U-nHvZ9_Yq(Kb1$Bz<@n^c=J4VDvjKG~(R7bL`gEOPV z35ak5obsXK-B`Qel)Zw_3!klxnCkYN!n?*#y-*s#4uZXwES=$EOBmO;rLPF?K^-2nIXJZIHEI-zK2Hj8(DmG$Kd z5?%&d8XAzIAN5lADrT)#o3_WhTKL1^ZJRIl+jLKJKNg(J9?3(_A!D&s$GAquJv)lWbe2x?yLK8}I9L!P z_5)nTnn_{Zx0i<@z&<58J2Z;T#M`DRWzT*Q5&dECC=@A6_f5eoTp@d(Dc^UvcR?B{ z%GLJVC4Mme1U=fB0<`+FwNa!i{Aa#iSv6ylfP!bq+YW7cSE5) zcnra!`JvPsc{UZd;`9E1yJF-;Meiipa_=NI=D8|ff9fx-W{%`V?5t%3uph2O6T11k z=D4r@-nJTmd4GJfeVZ>eM`H3&?reY{#CMP~d^$ES+qOFiSy(jTZKeU?mTH3iS8ZxD zrk0<5sG!pE9IiA?6J@vK&K{6q7xRdP2x&#vS5f7*x15B8iq8u`cr>fkt8>c_hKQ4; zOfO>Cs>Akg~c1qkeiyHCDuO<^lx}s2B1_Eoyx-1Zth8XPR#QB zuxx<5y6bgmu9D}lMobIy8gW85)*JnZ(_DD8>oTwGJ=qXrpv{-05nZ{9?xNEAdnGoQ<#}m;kXf2 zcLOJE+s%s$(5Ii&6BKATJ31Yk1|H#>*ViZ2)eb*dioAt$?+!1~cZR!q zF4Vr;3WMgCp;fP;mOrYg@t}+SVIGI~-bGvt88Xp{0+6$&eijg2X3JNz>}t>93g>=BCdqzK}n6 z+z7lZEtNaT#M81l#a|9h1&(#Azx18(@XJ5jjHaG_j6oHbIoopng;yR{8NIpvxQ-i? z$-nuhLGe83nj&Ki&KU_C%TS?cBn2NQ{W#*e=h~-x(xv~QTr^qv@bn*Dw#7;zKz}rq zomeF$crpb2BJ>eyrAm0U1)U%5WjOV0-3cM#qsh>*Ek5?tfsPT=BI?j*(4y{jj3Tqp zZ@oht5xHr-d#8@s@cZ{xkGU=(=mGs7L+D~r}eD(<5a)Bm6X6qlOaoO^la!3AA z$~Pn9C2z|@wVnYnK_V1G>ZhiAVba5SL+aiOo11rDz=-XA+=4#L5ifnGk1$7|`V5m{ z`zgN?Re`>kE}`t#4HlhqOfYuxw}FiIUtugf-I{iitf3LEtD6p7pytqLm1Q;)G;55V zdsw?$RO2&N0tS1sQYj~Iv^OMxrG2Mu!d-w!0a5&x(&BI4&naJ>*F)gT4a#wU5kB70 zkpL$w2cIxUG})zJzcGZS-;{4Hx}@W~@@2Er1j2pF-USerhaYth`R5u}ISQ!u5}rKH z`7aNq)z18;XW4s5V*^^%$v7*oH?L;D4t+?@AUW;L#s&*Nxu@hEnL5AC&Hvsb{J`>; zZ1YSIj6`FT*C5}ro~pwMOkgtF=OqVV6f4a%HblM!*+)I}QT2$T(c5U_xP*^!^-e|wLbBG&syGoyGB-X}yH!&M=f&p!EtW@Z^#BYQx_-VGs_Acz}J_mN**xUkf zW7SX292{X5bcBl#K|&d05MFR(qCsOZJUGi$OXB$bsJE9d?kl<`So4UnT#5iJW@fT33hWXhIJ6ILV`vVEtTR9A%> zeUhh7Kx!;)bQhEb5y9Q7bcct9dg?nrtW)WP1uh8yP1$M4sAJvq+7JIrw;T02g`-De z&pQ>7K(z0qGjY*Shg$)=m!ay#J1R72QrKQWL|UtlQ3f}(;ccosYv})-R#~SkW;^Z& zo;M{UF7mxIy=5r46$Yd|3u+xCU)6ow~Kchs_miw(y`V4epqS1I4QGtSccy}Tc z2XOjW^FYL?pxCEF5BAF+`b#`aJWk|z`!XCzDxC!$b5UPmgD~#@XtQ-gM`XPobJDbM zgf}H%1q9RAJUXd6W=$LuX~4>z%N-Jx^6ej(KT#yxRLgON+!jhvwQc+6$yzYTP>{w7Y(L7<}i-{jY9*C!Ha$ zSKaLQKVq}f-szxjfCZ>u5BL&IJ3^G1kO`3x|jxjQ>`E45 zBzDaPR(;~X0KXAb(i*t$VtaGA%x?;LvhFICoG$s-QBIGKD!GZKhs}YjMWbI`0kB94 z8$Z9CWxe&D_R!pUW)MB@$u$9(kQv(kjKEt9o=9-eT;zdwLw^ihYN?e2wvs_cIqNw~ z9IbuSAL@rt(rW!R?DhoTSR&YgZPH>Pf9!K9*_LMgY*Qo~>hg%Q-)g#tj^Afo^N0kY zaI6}m+6Zj#Uo|9sLusg(jeIDP#W%myTE*-y);6#K)tA%Q*Q-+$9b$gK|j%6 zAjMD^|MP&Umh12da9pxzeM4^o1%xZB8$I5QfoW2sWMB#u_?V_J`QY)HK%B2U_m^m@U&77EUO#Pg=Wi@0#gm%x zkIugF8ri5h;OC2tPq>NF%T+ggyT?6GMm2KagO`lsT?fmi z;CLN%CqyFy9vaR}CwXdpji&T&aiOAjvjT^rbi z>aFSRMmh0?iz?g4dXIl^0?mIYS9BCN;(TH=YqC4hvGv=w_w2`+5+P$dZO@mW9@FEB z-6~b{b*rovF^eMX*6s;-_k*>e(%L18-!o?tUD|kc7gBwv1I{O!vt@F$$}s)WW@0*< z8#}+`9oZl9EYUIJuHm`z7aRs|d=YoY560tZmU!h{xjt`Mu1_QWcTTZG75i48c6FOh zm4eWOk6>ktL^a3~+~Q}{ZOK1_jIX}pl=xsaK<`#XE~c-a$z&#!&%)hlkMnUXRlxsB z^iZH$EVLlJr0dHS5?bc5$>6h!`3r*7=|eu>?M?G#4!4aW+=^(ipw~sAA?#?wn_%?4 zaQ;_&s{MzVqV3Mv_G6pth#A*f;&HpQ>L~Grb1jRz7dUA*MQ-t~SZpJQ#1~ z_#UuV9pj^|I0WGm*{OOZVe^FAZtX&R^!1Abp;qJjk(lklLzO&2>i_yVyxmT6yXf&50@UO?3C4URQTZ3w@y0U; z#zvMG4}?!gyB?^f)RyUypCPO6^YR@Ymn3>HIs{mr&8WuLa+NmiXx}d2F>5&qri!=Z zk{0tWEz~B_xz}rAdlg~#(z53ft8-78k z>TvaWXD?vr;$rrHL$r5RboBUz*+`emOZHhPlc|uu)`|9aDh*F_7(=ZhfVk)HEDm|| zMXM-R|ITOU>W;quxq;o(liy%c)TljQ)GH7@TX`okWvYUQg7U}kV0+W@Dd6&c8G7?Uwv;dAd_!XRPPOHz zBhS;SqYc-uj&AImly~Nt+QR94D9xzq)xRGQmPzgIbNnX^M?c2uGr7fA|H4(*mlNfr zn(dGJ9D6-^Iqs%C2$cT)1_4_<`Q?;?Y%LCN%={UoLXkAJ){oZoPP3GC=}j)gSUq)k z9`Bmx$geO5B1{%FB=;t_n1qMI?9dvYW&dDXl|W&8>(6NYXC^ARkoUjYGE*SA>lSn+ zorynKO_&sWT)?bhqD3WAq^|Z=vNolztelWReQCeG1~x2SnHE&0^Br0T#5xa;RA zB@C<&b#BzG)-v~cF9#zyJ%}kDYlmdoIN$BWp12oLm%{9C8k=VEAKQPup}8F)-@?EHan>c`a`ilPgv}wwy4|hPr^eH@ANzT^ z)j>qe`s=f18u##UocjRcqB;Za?^vcQn6BZ%_u>P0yIa5bb2U`WOSngu&Mr*TLhb9k zW%#&STDmoJTr>7w7r6V?xCXjK!PdH;BCv&IiybE*@53H>!9~ikHnw-OmFEqDNbeF;rIM|-AivM z)*1grI7}41U=3asLKPPAhdedy);s-L7u~D9JW|>_l3}={-Ar?(KfvLm}FQE>WR>bfxCscE4tyAk*h-UMII-UDl^Nn(D@t zlZrf~*`dx45q;x?CMK}e5s>ZVnXn~te(D@|`3|EV#tUK_#Ak6&U8%&{gVS37M?+eo zlSbuVbiTM=(eMs}(MFX~f|Z*!d*2%;aAZZ$eYYP$-$3Bkg*?O$aZT&IvHYlVt&{i5 z#E>9Cc*v>B;R!E8Eq9kt8e;C9lgGPG1EEM-*M&)ur|FD<8X5GxwqI-<+ z31MdM3>KXl{r$$xrqJB}SfBZsziqp3B8@B8yCBa*=q*crp!iJ7YMF+&f$k)e%1WTB z^?zT>n+c+*T#C0TH7EDUs^Ii|y7UmnvCre2Id+R90q)(AsXnJb_>7 z|1Oj1MJL4U3-B(u;wSInLP%mid_HRt!{l7gVIb}Lwb zVcTZ*!8&TLr%}?7e6*OOtXno!!`9GNzNN9*TUNS|9b81W-)ZDW=LdL(HsMyeB;L#$ z#}7Td$CU9}8er87vq+LG;Bs>gmR@2!1p*v2?j|#tA_-Be_v z_>#N2H=4N8R8PcHuF-WeTWx6-;r=TCBvuPhAAZ||UFW?>MsrWP7hNQ6jJh!LiwRsH@&Dk7~ z7sL?Oqs|~WsctxR+f#Pn(Wgmn&fl1@B_L02vx2kAZ31s4tx!YGIg?xyxIW}|ICJ^+ zOy@pMB!YnSbUCTCrlQr&=-C)8O?*?T?A7gyrMD-W5@JcwgJBN?hFp9i#U%poN?l_Z zx5qxUF~)a*u0XXCRxy05UtS@1&=9MYY#CR^W3cLO7~3MtIrESEb3!qq7b3S5lJ9Od zbM?Nk?$4CS%T8qPls8eqR8!m+(QJJlMuu@ z`8VX52`Z)>aO&BZ-H&5cqvVRNqc`Kgs8) zPssNjT2sw68MOY@w3YnKzOas;d+`^e z!Ws8ZNsX1qdUczq3xOeKJDAtPsjVBKVaNraOd%}O(7vFBH$jq{kp4PRK3PeD=$jpI zI+oM%=2b7Fh`sXDv|+@D`d{qANb`Xvg)j@^M3Pi>9Ed@DCAFPU&gTd#RNR8`Q!APT zoqfVTx8J`CZD-_@?ePhrZY839q2iZhZ{Je7{!B%9-XR4ww=|fUm$o|28nPFOC}h|) z78&k&_U#y~1vvDl7GNckz>wtWm&QB_OIMu=lRB_rqTx%n7!;tV7B?s|r_@GKJi}k& z(w}(QTw5)eVD&}k!|wIFTP@xfO6Tb`pkt2QjUFG;O?M8===^)JW$D`K|A#QA-$i3$ z?LU?=ejdm@O(1)o*~12Ik2fV?CN~WWmpQ(gXmm*_Y<9YC!Q$Ru|sK5(g-!9!2>%%Q~9a-tohaG1}Bd| zjuwC|wH?Y2k|g=SPm zgM_atthsg^Vh~KNK6v-MZjn5dlZc)oVSjo9ZoYqXNnuU!7TZBqv^X$rEE=~EF-IZu zk?W~!=PeBr?`@9fKm5DHeD?)glAkM-*~%ca*x+iCYVrfB>&Z+5wO(C&K`}Ik=|ysK zwvZZ^bTm$5?=)O;Q8o!ne2Sgq?R*R{!*#;>*duF07y~3X0=+I#T=z#7^h9h!`Bl)Y zD~e)gH_h0_;giv%aw00aaGDI&sfQ}I(Q(DB%U`5p?`3TufNaw#hZNlr8AWP{`)h*q zYW;1c?&d?$f`w_{F@$8xcGE4_U$t@Yn(EDB8IhEj6Ja}CSqMr?VA`%R%KgEZS(T;J z{Hm|aR+MTYA3YS~MbhCD(O@5I4ZB>iv~2!j&}j=z;Z&kswuBR3yMo?=ZpwE59e;oC z?Bsd0%glM-yXqa|DrXJiqPMZ77=|#Dp)iYr4qs2N3X$duHoOweiBVucKfj+)_m3{% z`GqOjFh?zZJ#_)_Whxsr20UL3;siU!ZL41(SbTm#Ouc$LX}r24ixUUzF}CN@EYs@P z>b&2A@*Pfk5|)e0H(sl#PX~X2huno$H}J&OvOOHFr@FSE@>kcvZ>qiKzCQ_a4r=PxLSiPMw@M18~E1})**L2j^cUVQuZ zA^w5hLqzo{NhdAbWiaUn{*Q0N-YZXjk6)l)SPranAMe7cu}IS2Pj|dJXlCkreL#q> z!~f?rQ0PPHn#{W_UH_x#Jfqos8!#S?O0`M{Ds7C4QFIu!Md+}qQd)b9QhTKKrc~7) zH5v&;?NxhkF-p|lD~J_4Hvc#8_necH56}JFxyJ93j=bkKti1?|@Uu$wGOSK{tFns@ zst&OY$J!FsK`JM>c4IJaokrjbWfDe!TtM?S-ozwZt6y>HxWLsd>1}7M(|7pGOK#s` zwuiftRu0>5?AhJi*kjgCwYz*D9rxzSE`@An!=KWEu&Qjb6?+l?0itHj)GqbIEwKhm zV_dbBg~f&^_iY`xQjet-eEOZpaD4Go)FRJ)G%SKK7AEt(b$#}qX1mw~$rIO3(lThZ zoXuF~$2mf)3^1~d6@UF&Cx@YrVi^Rl03UVDd+qU4Z1tuOBlg~f@}bVMAB^N#HZUTy z4fh>_V?K?tPinkgQM%SD29VqinsI7@U<7uII2Wy%ejdGtqq?h|vzW{$+NX?dF1b@* z-9GW^_eDlN_`m5$LDii$U|Z*akGH8)B6FpB=srd-nMS2SVF-i6H62&xS?=l~jXAZd zzw|3Yd-Hd2pqP-OX@-H(r|FAt<``@^J5Mb%L)jB0PEOI3w83Y|4dZy^3||jr<81$i z+B>bdngeW*jC9r-|DoXI_P72UX*c$tX&_*D7Sd#cl<^H6n;*g3rV4xAEGE}XBqX=7 zegYBAX=eNyeAGm^*dKoP)fvS3a;#Obg8w zBm6v1!RPv)?cQ~Ry&apKDV(QBNt|(OrQZVozx(@U3Z>;ij@><k-~G zNq?jg4-^Yjl9b$(qKb6S8B+)tkhkIN0nMBeW6=8tIr^(Mq~~zy`=7tloZhSY$-ehb z?S>`w(!n7sYA~z=8wkTpu4SDrVV?JMOHe>LCzjl%Fl0hA?k+fm3|5~eTc z{M9@%N^g%6=nR}?sOJ8Ag9Q{T@ex!cG{=i=6V2E}{{4~t_qJMwOXXa>GIap%WgHI5 z5&0FaX6*xV&ZvVA@;f!vm~_m8A~7etAlCfw;YMcn zo*`-Iot#xbzhXMuOr9+XssB4X#JynUo?Bz;gTGueE5&-7C9_Jh zM||wgbdOWvl-|%~0!$W9@xr`-YnP&Ed-F+90pHH8xC8 zA3#Un*x;jRJ@BQ2%amzH!eq+pj_f-S_|m7kKpzDX7UMSX{(FstAFDd)v&B8B|91iq zQK%Pz8wq~coh{e;RH&7;6i+!D=-)A5Wgt||MA)eh)nUH+49Ii7C0LzKMn4S`%-xd`!;6+Bh*n@+F}%0P zx-at^myKistCDFs75a)a2Ie%xDx!CXfO^6ALKUNUTH-2lcNNvr0>%{@=yE71~ zwI#yarAD{}4TSb2H4rZV_%sL*Ycw2T$1I*9DQN-vP0K1Wl#R%u?h$*^Mr?7cn+iPH zXFLSuuHjYBd;~mKxD=G}_%eVwi3_q6)JY3}8P=;j>LrJ-@(MRG2RIGSn~+NDHvojxqg*Zjb5?X`}SmVt+SEVxDLRn${&;iWG_^t z{>L?o+Q&a_j`X|GwD);&7aW1u`546J??&F}uwwdX*7-`~)m5d*ATGhPlWsasmko{N zL6*tUTk>Y8uFePHzJ~Cp<)u??jFx{TLUX0%WpQwWOD22qiaXvJc}w1Hj%#CSY&b}y z&9yaw?*qvT`!7yjE{zMK0x(TjTeF`J9H2cs!qZf997~qNgsHJf>|-UJk3f6ClB4nl z`V`nHHS}b;uABRZTz1@?1hgr470x!C#WNwc-rx3Wm!|BO^^cUPes%0-E~D)DXExLNkKnqG$aZA){Mhb@Z7j}-S&dSQJ4H>& zrqTQC*!OT-_J-TF_0~NeIPjX>&lQf(tRU-jASpmy zZf!LAkfOy5F|EEHZ=aOr0?S+vc^Mupf3X?aLdLR4W@a31u6`64J>rNO^?z-&?!K&g$a|bGRAtuorvw@|xAr01wEO)L1><_E`F`(NZ%iCs6usY@nl$fx z?Xn`%bUG!tTdi#w<21bARj`&sVS9KEnb(>3UO0P>dRM6?#qHDNb<=B<3S6Cv!->9l z*UPgYmnyq0!Gar1OIhde?$2^>Su9JaWq8|D7D)>Y((Pcpb1mQDv9s9w|8t1Hl<*Dj zAFF>f3%6pTeb&X6a6M8G1l%oD{N88Sezs>_75`Hn8Ray`#I*+%dv&=3j2uzW>9R#~ z(UUVc#ppdi;Xuuqch9&I4$|7YelT})v8Ri^CS`J*UAk28yU3zP6lX>}Bro`Dl3050 zhO~z7zjdFv$FI!Gu2SFn)M>jVXE|1es#Eej_;xh->h;(hN4X8nzh%E62dq{p+220T zh$Mcrmjd>AsFe})r%Fu!Tvg;SE3%(=o6HV7xZn}C@Jn(n795r3eCrolFa#mX+&$6a zE)Eur@I;8cIOgU4nN2iG%sOUJEsYY165S6iRku@@0Pn^wzI0Yzc8*X;U*0df2{UJU@4OT+@48(*ny5TWzqzlSO*Z zWd)nQdTq*<$m7O9g9A!DGvh@#*O5^2 z-o0;49}!p9huAjcp^=x!|4iF`9b=B|M#zO{*YZ8^n8>roqv#JN~F&rODIB1S%{jdpT?qrEJhKnE3Jp(lF?fDuFG3 z&E*v$b|@(m2{QJrz^pvvh!xcI-yX2^mvT8BJNUP_ea!ny0%?-lf((Q|9oZZE?l+IU zANYnV5dZhtNP@@q3D&cFo_YgWtGVGa9MekN1SkB?8-usIT6MpTdD2o}cllNBB3{5%B@B|w~Vzq*p zV*k7KoYM1ZTjXz%fHe%mXi}kt+QL2`z6V5YDS>yE6dki}qV+~)-@aY-1lO}p+s!I+ zL5Rw7PV{Bly&4x)p(hm#pbO8zNvw^Xjs*XEz-Va&U@?0UD9?o&a3aI_vq+h4mafAV zQCpD!07m}kkmuXr+pLvu31c}N;X&O?Zh2utccAgnNgL-}l%ZKkQ9iB~;j&fs`kpky zag%nU?2H=hbVS)(c7VrjBH4_?dtAn?8G=4otXQmdy2Af-8XHg5sc7(-I6abNB+>F> zD)}3PNM@VU<9-mn%-rE!`tYi*2Q-~6naqCSNt_&gon%Lie^1WS%)wf{TfA6Rb|b0JdD^v)t-g%kW36+6P+Hx8yhgaqK|f_vA*NdI zhl+mb-yPh8y~SHQIxMV1yWB(_IC;3+u93Ab@-RylF?*Ee(N=6NEeo6DeX zP?V87)p55liViDiuhfhm7}AL4;k#vM{MOF>&pI__i&Ta!iOZ5b!Lc#z4X$_=(S0e)C_K$DX9v0QRG3a@a&A)$?v$oobmmJmHDO|coOF0cinprxup0o zdk*0vg5dfZ0$z6-$DI5JAZw@V>PjnRp()d{_BEtobJumihF+~7g#@`46Cfk}(0Dp$my8KdN-EKiW(Q{doc=7Nj#KcRS*^FKeRO3 z-c89eW)G3&I8(TLeGX+%k?mOD!0O&@ko=u*zg(ZhM32K?;*10aAD8Rva(c8~ofHJL z3BedZ*+r;>0)f=$S>sB*GH*A+{Sjas%K@Vb^P`;y5pa#6ikFs;KMur&$j}kv;>MWP zf3V*m7rvxiuL4hg9!849#I*pcWt*04-1~2QGO2n~0qn6gN1}j3ap6(+Nh=Kkt^Wa7 zyy3rfaUb_TUgLMpj*BwR2Fv^h5Wiuo5%s=xTb6ZW^eBY4!i-+rjtrqB-C#Z-@8olM z&e~w@bQ_l%Jh*{D&GU2d00aH;Q0x7eu$`;C#VlYv3xJG6?59lc(j+gynT5OWD0JvA zJEj4IhS(ZTE?w+ze)@J8qk<#C$_ysEp4l#aTIzC$-@87)bQ|xBa2TyiRa{hTpV3CV zkuKEQa$(_+E^VgF5YI%xI((q0ohbS0CyyU$n{p@1tt(2fY#T)2TPiE0e>uzq>d+I0 z;-*Twcq-EM3S^m`KV;C_M{(`+H!PmLe;Beb6R9>L(QV`bCSoZ1Yw@evhS3UX8q7kY zT?<7BC(B-bjlSxt2XFg6ZaXCLSe8JwPgyvYohhX#Orf@1gNtJJ*M9~2+Gi9mqWTq8 zHgs~~p;+_Sfs?8BvG?+f!NcrNbV7hv72NF`YMoBUdOgE?pA407Q2^&-|73-Je!hF> znilmEn+E}tAsaN<=u{(T>;Y`_X=tqI)vd~%_-c6dn`Wc!{Aax9p)s}1tv-iCfqAjt zAP|VvlT6q!;`tfIgg2JgAKmL?x%(QOt?CqIFb046Lo5Xrr$r+va=Xi=Yo=2rZX@QH zuwN`ba~&CtQ#uYP%(&{IySwV+vpYr3Xs7gl zZwSO4UhDnJ0mvBJXW`A337gn~x6at;HF^h!Dv0busHV6mW7RTarGa=S9lt`fJuTy$Jh0WQWwt5<6cHeXntTaNfHQ;YmwMKDjjTKCl@n43sX$K2ztTi ztbpUoIDc63Z)INwA%V35D6}p065vJ|yB9EN)qmd7_IgilBO_XOTdoG49kA7$YDd|y zJs++hjrR1`e7j!fh6;#P-ttRiU3>0F`b0OjE7bn!hWM;SzXT2jW3bhZ3+u}kxA6QR zJpS4cE06PF`)bBD48HN`9k>k5P&ZU0)GfhMl+iL7Q5@!?_|Klz2*h=g3PS)fRHPV^ zvFLirx%erglXO$+J|B3d#?2|vi=qgx&DQ@1c(KbK`uq*PVlCOE8r-ii;1}xX(;$F% zq3`;qHE;p08G61=GyB5c{%Zoubb7VM#`fh{`eAXzrLfH;!?%j6MAfQ2i2unZdj7X0 zzLLSWVpY!}v|gQ{&-MLXXnuEW-7$m^4ey5K51rpTd%EGvTWk1k>d&jaJE}p}p60}> za*}X@ZjIrm@S6_7iM7V((0_eqhTM_dx=?2&XlV;EO08P9VxYx6&ZtYr^gV#a3q&-;2{^HQE^)+4MDC-L7tTIk5xE_T4lYP1`@wos_G%peObxDwUSv(9GWWMnJRagu z9m}8wB8(rdt`Xuw?A%WLRT)K3aYQWrC1i@St9TgoiP4nh%Gb;ip zNlb%8R;QoUG4b&f#Ee)?lDoA11bfn=Rbm~5L15OVem+uulDUSNu!21G-2qpYjnSGe zpsv~nW?uX4BvaR;wILa*;o%)aaHdNQU{CCpJ6JZm3Vb^9TKDc|e~hRdJO0kJxw&`q z-4?D(L%GwifiJowWz+aa-5`(zWiqRTMDBCGtH{`*c8xCvLt4Lfz>_kmSsK^>2i;yg z#+%yKD2dF+F!rjd_*jAI*w9luHO-hdTycLt7+zI{!jrl zlnul>ty={baR$sQJc*17x5LxP<6mx&HacF@7w1pvU7q~?S30Q-W-+h~kGgD-o__WZ z{X2c9O3r7{|D}js>-;>Dnt%b>+e9`UYdU|s{O%H~AA{|sn4bn?)vt>~O+xW3WoX%^%2!SZU5ao;RUh)_B*A6j>CE`A{c&}?=Ux5?U5pyzNBV@H~ML) zYze<@Xx=jDgs4C1D4jzKsz!SvF~lMtn7~F>NK2fv>Wh+Y4oZ;<1jEaB9py~6oX2}< zYoLP$>||2~0c2vzcv2^>n{&i05%sE@>&sF=GcN?m9wPso$>z=H4~AhgsMh^{5E$Iy z19w@dvr76Is<7Nm`9+wFob$6$R$}01{a!0h$A7%k(ZWhH^PZNhQHa*BTv^3(49{0zs216h?$hoExpp5oNfyR?AL#1h>V!B5%zHA3?%T_fNFZhDO$0+w}o$9Fh+y z^A1a>ILy_jK6K0UI2Bx1lwFI3t{}}cBrdQ9+zezb?K=Ndg>m9?@YoA+J(2Hf0dJ43 zqYjFc&Fl7s*hWmNZ!yN<(|Fk~XR5O<|0(lmCJIC|30AM8h9*O268Z|GUhiWTt`_i% zvr+!PdD%-IEEcp-(*3B17R{0~K~cR2_=S{3=&=4@oulX?r@bg68W^P>OCBKD0B#h0IwPUqnH-g zonWc;`hS$VTW|w@n1qoRVuHD-qtpJy6(vw2&Iwa~c&3^ueTM={!>SCG20ky9J2&-0 zY0>hZ#~l<68rWJCrHa$2$)9h$Ig{n4q9RsWPkYJ3nvb@%89RKBui1FJ zf6J{)2K^yNy3G72t1rvHpv~SjpgJ6N`C1*rMTD~M>#35$=>>!lF{Rx&l>l+GFELLS zS~$zN!emT|tF z_18Omg{KNydP;v)`^P;AU{m4eyB@0IaASl@c&6<*yULAsl2!X+p%dR=a6Hqy`sAyi z9;q?qWuEgQ8tZ}|>Y>drKpLbL(w*vATx1RYXmA^YS*)<151eJ)6O=2m-q8jI z#6Ks5jA}jtKA1w?UaVu0(&j0>xlo6bvbw;i8l5f%Z z8@QiALtv(DAY+p}P57B8M6QhIs{NvJaX&Lo?WSd{ne~aUsL(sGW&v|YmbByvHQ*Q^Odxu zl-YRnub~H8mhQHp5*$cbbjsfmf{v|WC|nSlvIz}Vwf=C}#nkGaHy?DUROixXs+KVE zetd@#xV+{(rKOJ9m}@YOZ9~N0+64xpj2J6ZuwR~y>Kl|Bjy7Q1 zd^t)-Npf0j79dcOqPju9)cuOj7DmS+ZEl-%C4Bf7AGA|!{K}5}$sbK&Xb<}(y32%v zH@X1>SNNGrP7sjGiq!6RTi&-99meZg?*CW`V;3j}&>>5Tlj{vBV(jIhy<4|M9_}Km zU-@wDpm^NFRu`8&`UmrufTF(;8ZFl}59a4v_k%S)rpT~f#yrHZX|Y*(88XWS=!9ha z#J%|N{>bM=WZ1+2rC4_$J0o!VJ5DvkR$;do6`2s=H-B+|SLKa8{Z`FNh2~iq0}^?> zzstT^x=51cyZ&PS+0LI`tcK#6k#g=i({6uC=5t=!Ae;=_T(IBA`%Nv+u33k9_v%bU zK?PEFef$npb~MkVan?D?_$!r~{~+O)vM%f(cdTlS#gBh(@`exm zqc3DxhI&43cz61l%1Kp+@gMfk$B_DK1XErK4vG*26VU0?=}o|L`q{>Wa?5#_j-|hA zxL_FkQ&dr>TJHSF6dnF~8uT6~Y4S#_M(xyIY`S{Dfl;Yx|*;s+zL>=Znj z8QUZx{$p4!fX)YI0}~g0^M>XA@=X2c+vj$*s?p7d_$-e|>~CwShEv^%{BsHr2=o- zg*iIw$%?O&&v&lZUQAP_#~9S4huHkxjPe=pu3yX}IN|~U5`>`?(w|bi(CI<`;)^HO{{pBys9m6GElWNiQQ|-Sdg@HV;|n0Y(6AUn5(n5FO3CuV z3MnW)_KfMK2uMx70@t>4RV>ry&R>+3R0_4`?YZ%m*q@u5TS|!TKZ}$x<;j=)AtszF zakU%3p3_WZ6|gZ-=JI~{q$<5%k#`C+gCZGO=43kkEqTq-eemADEiTp((F8syzxLDvoBFbPC$^nLc!${gKEQi8qJa5km0;@(=H`KQs4in=KS1Cj2dca}H8?~d&jYwnnbD86}ZVL;Z}RAPl+ zxGZUvm_h6r!mo!#Qs)4>qgA$y$BMyxXk$ zWVai7+>~uU^7MPbCrVVv#^xKqJCJrV+pTo-8i>pD?zZwtvT^#p-(hFI$LE;rlufK# zWLu!mj=&lN$X(zJ`F1W3-d|LJimQ?h8b89p1b&z7(5EhR5%;sQAR#x z$Jeuet@%C~E&i!G$QdoG53=D8h7cohO%2!84xfE^_RSYErBi0`{KZ;7?Q6mc1ca*s zQzFcq1hv}QQkzc%_argp4{cPdo>v$gh{m?=?DO!*w||T_rk+F>F&T$PA}DXuv0|%# z=T!4P+=F=acNWHk=$o05{#S%wOUPG#Shq?)shThLZ{**7n$9q>xe~*;uqSJT&~S&4 zK{B4&V@8Y@2?svRBSjSx8CA0ioEljztZ&%9uzig?DE{5FAR#3hGh{n*1&8KRVFXCs zjm%(L@ocQ{@Ya7)DRfSmvHv=@TZA=bs`*-(Q1GohLcA42&2Y6M^ZlbJ8<9t5Un0{E z*~mBXVOt|pHu2va@5vN-9*Tw`!;}*Lp7iDtC=;60*fmx6hY4VFTOn#XdYH#iUf3J+ zCq{)owq0nq56gvXp85CaV+U;Cn=)IV5}4v|AFmJhV!HlrtU&1Q zcsy|Qbefadlj!6}GM08X#TEwavt~o9vYVLDgNzne@@QPs;bjkNv#fmmlzg@lL9 zOE=5D9`E_U-Y#iH@5pN2^mS{C(a&e0-wRB*zWiv0%4T9_lMa|hyPo`}dTOfh1RY3q z)r&s$D^nCIYuw-#(#Un5j`Do3brHjlvRJ0wY;DDVB*jqsCoHIWMXEWCT`8Ef9!2F% zKRRoBQcZ`106YT`qh-81q!P|IR$wLu4hG{yO!WatS74zg&8)Hv$zkc#)w0$p&%}n4 zw<{g9qbvv(Tyv;y`|Z>PT{|GAWDa$(<|Oz_E=OZ)XG#=LMDbaX>7Rfe;qyqOce~K4 z`*w`F->2D=wAmM~&m?4%JGYBrQW_zh-=^0ahwjA>rfG9spcw>w8^5epH!j zwbZ@LS~P8fCX_;hw5}lRSEHk~UUx2fvM&knOfHy5^?v;%6rO9O48w!hx(`In9)!#g zyIzH7IKYcRLq$H;`amN?y~EKZt}r2VlpF(xj~XRSV2xmWBTz}6{8FrTymoxOH+CHy zYS;YOeU*W0KLC?48!M1AJ7x92bV<0%nRa{olBv3;puciXvkJQcMG`mwf}XnvMBej- zU07!R{d^DiRY?MGHo;*1BAPQnBaL-JL)l((K2TW7J*0Fj+{Sle- zMsD5HRO&3!ZZw+2bwqj9HI?SwGh+Rg)K$U<%-E!+NXtNMmIbJ;O4_?!)>sqh*eQi3 zFGUKx6@Ac<^%0pY$wHiqL{oSfiC*_19diMnJLW7Au%I?;+DS-awn1mN?tJ%TSIbUDHRPUGIh6kzF(xjE%=QayeZZKz z?oPtD<)0ZSo9)&Z1pI)akj3l^qou!h5<_kO1GtB>a4wNrTDE*>`+RPdttHaGk>%=i zior0L4)}O_hSk{F>y%U`=m_z0A*0f_@wV?ZrN4C&d)>r_rh2$*!ovmU?nfmAK(MOh zX7*I$k_yY}NAn%Q&CNuJiMgLF`M~cGmKoOf*oyOxc3k(-5iVOLt=1@UtlRWXrC|FZ zF={Xm-Dd9bt16E1T27JA)j9qT;L?yGoU{eF>S17KA~_AKKDQ}~Px!ku z_VRRMXj!W?qO2K$3RG07N?;l3_x<`B!cwKct2h0Sf2?yl4K zY+N92Io2po`XHICE-EhwO2huAi8op1Fu(U&Cj;BTHn-yJnr^GO$e{(QUx}aU;BXAo^m;1;St)|{+_B=Wi22qDgX`tkrIt*&!-Hvs(`$qh#Fj2O zBKdzRcgNs{&QGrglX$t%2TPU}nrOs*;Fx3w+(K0F$195Hes((gdgR>k&ddiC4$+U5 z8B~}uU#!o-)z+uHt&@a4a0aY3lN8H9vbc<=4cSs#+K{_*g9Wei^kx<~p%4__Smpfe zUnA$bw%%r~hpRMt(|{1PVXW`2ayX?{pd!B`Gof&no|nIucrp68dJ2E!7&#_Hw|RAeDy#^!nJx?xNmr z7Nsu|19a4za8?93fU3qi$8Ocx#8TJ zFRs$!7T)I|Ysh`4eRo7mvxpM!?RV!}e>4UCI9xL*H-d^4o$^CUC?ILM9knQ#FY8rMfMd-i)X*ub z3!R)mE?xh@>@+#0NOif*SbSY-o>=^RDIt+Y{>VMMzR^geUy1@_*q8qKLQC?AL)++B zsnExhC})Ar;&Ori01VSV^C3kHYPdCHg_HU7Kd6`vjoOm3hL@03ywjz7j;O?2VCSv3 zcFS|7te!!mwQu2i<-<>X@prwO*(#QdZ+%YstWRs7@sQ<;qC=MZSnJ%kCWl>4DDy*> zba*dZui_@)%vvY(-ID!c*{lp->j9Ce>T!%uBI$ASZxQ^EX!FZOl9)b)qv=4E2bdJP z8+>E`mPbx-y~+8~L7|-8R{SOhaWLi3?-{6g4UzcfTg7l|EE6aaK9SeS{XP;CQl&Qr z)|77G|Jg2&lVA+)E&QucrBSmnHTq|(yjMBVHYP-Lv>t3ge^cWVRj023rJ--VNWQ`2 zF+w>3%e~Mi(ZuirmSXrwBkl3~4-v68?mPdF+RW+AL2FnQhZ?Oje=KDvO@Ip>1invX z5ZG^BcF)od6XHJpvD_n0HhS$o+kCk2eX#Qy0J4On_y@lEd6j*sASOK>D(CB4q&UsL zf3v84AKLhpQ1)BLho4LMx!1IjHl?(w7M}$)-98xqYxMH@Cr5V~0;aXed#NPk!xZNg z+5#{9^)>A9uO#H<QMuLU&qe|DT2{FSd3@)rVXZ||7$E;# z3wMHAPxFM|IIzRi1{7?1D&{7PTT+@OD-@8OzFXEK$Y&psJ0(7;a1^sVD@^iGG(T(I zZSr;7o9yo8k}WAVcx#iUx8m8IPa<`&Ks(;>qw@{Q0_EAgjl+PZGM!6s;fI0g&$5!= zJN3%BfA*o8ifdC2Y#2g~xQ5CtBkwsE)y(^k<0;SK>DcDbE`zd0_q`-4C{nqzOgN@ZkEv`5DzfXqGUIiB({K~v4 zVM}zCfR1tIoU88O+U;I@S2N4s56pZ74O**4N*2e~zuqbCjOjc4W;baY$RKe#?{Xor zt+)DJ$aU~``tm)*GK+T*9DmigI?eoQDbALL&R62xg@dM?E$K5ZIFe!tNqs?mTV1v z5N##<#rS8bKWvdj3iJ%DloUUMnoMMGyDZ|z)^!>VB;23M}n_RM^~X3o+vEt03PKK_ITdxQ1mNkqBe&AK!KYuVaRh10#V-Y59p zFLv#MCVp2k18ts2J>W(r?K(v~Zs(S;SeKM>Ilc5Ai|}4iFd3JwJ-Dn`$2|NTOQY;z zqW1U7J=mV7W%h=V5!88EC$$F8p1U?RpoQ|G&tnGs)}+%1xU{TAo~I1`DGO0>9DiI- zfO)zQN7I@AJWtnk6Q>5A%Xy92q`7OI?hZ;Ih0Ca-X*{}abgvx`iz1E8m3>$f<8y79 z)T7y^f+EKcx|&5l+7>Nw2`BU{w58 z$}CugFZi$$(~6pq5d@(;XJk3DvdT3Q7PpN;_A^Qa@K z>=mx91;m_ctg}H&AJ}aY9=Gp^_zO~~e5`;%-#n5R+B#2lrCxN$SV>cpa1h^Qa-pF_%gwiyZhF}f#SVl|cKt7RGBF4P?0$!%xOUl`k`eL;VBY@Z zE5H{tJoL&}k2!RU%N#<;PG2MSy>m9)%e054A@R_20);{K-nVV}c6J?9m`#pVLWZyh zmK3!_@l0EYsjrLeNJ!$x(mn`;%8Tz0uhXgz4M2!IxxthW%nf_nJ0j=2 zGN>SpEIUwdVT@V-;-e3*pXzkg*aJ8K3`W_zNBOBc7I^xbV-X^c6q4kN!?4 zm?%Qfm#o3kG_Qn;RbAP=hJe+%Hg8h)R$Zld!cIv$r5+#5@BE#)a_Th1RxzM|E{Rp& z4aNq2UNM&4VWRWhX7x)n2-`QWvw2g#H;3d=;zASIBmJ(E;a`n!!51LM0om@^n&C5# z@0_2UEr940RWT<;s>Z^GyiSIJM1JR;$XRW7S#8NHn^e)#fv^B6u|)s1-j&P+d~g(DnUOb5Sy zes=LomhqhWjO*ysX6kSMrn93wozu}*C(8VVbHSy?&uk4b%Z8{PMvVmVbjr2e>U2|k zvv8T@0$DhM&{OP|@hmyJBG{Ru>=WUuMF$@Q~G#bX}u#*x?I30kORHlBH>@B8@SyQ6H?_p=LJrqucFq>AtbBN`vC*y-@#L<@IUG#%SD$m!>!%LM+LCC-hwTaAofu57P<2|1`zjqsTI1_;C)a|hF6Y_5Ra_39eu6~g@*^%PXw-I#$ zY_Cj53bQ=)pc85yESF8e@)y}C2j*_35*#-1*C~YJ@Eux}XBlIy%dSX((Co!olI8hk z3x`WsY{K>s>|W;6nDJVkGLinThw`B z>Bi@NF9*w;2`Z{bsr0kclNK$)cs|B~iH~(X4vsbu6XhzdLMdC4zaA?)UYptnC^qR$ zRMtn3k~41xO4uh!QaCj5`(2c|=zCg`OTFd<3#mAKA09aQCo*ACClhMH$fg8?`AM}Z zcaKk{LUZ1}6=yW3YT@N_M0I+Rnbee@=lE;erI{0@8_hhrSj!HIT-YxE?fcOAXKP75 z3~_H>x?bauOWjU7GT5&sL1B_)N!)@)u5jv`4DZPnN9s@-ZYbByY76{dkuli>XMHfU zVNRH8xpkt)y@`gS;a$@kZvRB#a#5DlYSemsSmY|-Yx!l;z((VHR4mdtE-%oF=YpaIvFuI*f(iNN)!rs z)Tg=qsSS}qTVe!3?@6y72kQM~KD}s4y00W>l<{eyxUSv1pYU6ae=I(Q}gtI)#D>;V8Xl)c}Od!S60$YTmEF&1BsA ztxUPP`CAOtoQ<}}*u#hyGmC%(b|*RBIAe9=?9|&}i6taUryt&W;rGtco#`7j05k08 z+vlqy*0|=lV+Fq(N{!HXGYyGp;SXM69Xt52dU*oO#wE7)C2+HwVyhMxUUD9rQn;wd zU||C`p~#9Ac6ym-ehX89Rf2)(-}$3ZvjOZ%t6Ej+Yw8}&Ta&_w{~tsDqLm|>gE@#} z`xGdE<^{j5WhKS1<-iRDtqRD`gPJNo0e`wBIIrPZ8yoVV&g;px=))}={mq_s^!~ID zfBlaykXR+w-3^^$L4h0b{hcgqBNAAdSCS;mELmqN81$*%hffyQQ)U8tokcg}OOOrHMDlg9&jQ!-yN)KY;OM3-Gat}JNt zuz(c~<^x;0p%Mn2;lOJ$hdikxelzp?>IE}EI{NaxE_YBAV$`2Y=a1XfwKdfkVYS!% zDhz+6EaS*o(@ESO#M1nfE1cgsEas!KOx8!Q*nsa1r4_|Xf}D$d_TMJIOoJ@_dpi+J zKrOS#fL!2VvLj_zw1}W^?ZH#uWTuEb{hU?~9Fwbn&ghFa$-@n8*UN;l(Dr?S+xNAG zyO?uyez5d0nCUwc;40ICIjof96lV2{Bfp|7R*D`y#uJsE%`ch$d%xTfW_7ferEa0TElp%JdoeCo(KgIoC2KNg{enFym`@-j|dbc$* zKlQt!M}Mx3pVVw<-uwfm0VTS*J6#(oDIO~t748f^A#f3ikCGSEWDW{Z5?-i3e z1nXt_#h}S^XrjO3;xA8_J zCJIP-4B#-oTKx>iLFck9|JoFjf%$Y>+u~^2i!DJ-U)o~v)%?*$*u*P>BpZ5PgN4f2 z7DY~@f4b3Dt2r3GOLxTKQuI>eSa+dN-n%AU>yWd-h16&SlGxaO`$^>)5JUD}KrY`z z9a`_$=M`|3e>(vI=-aBdjqXyaGe29acB`u@)$79NeLS6vGg|>3rW!Zw+UzADLz>{Y z%&4}edzZ~x4<2lm63}~6fnH;OFS#!QMQ!W`r>0K)&2RbIOVgvnF5~PsIg%p&6?w7= zU?>-y1b)&dIe1T=h}+$4JH#@gy{R-Ybo1#IMT>vu)pQx@?3?rZ=h>Db zzrSm2Ga9)zHatcq`s|FoYT%|r@(w$lkc*#=HCb-oTo2WH<30rw1~L7+U&;9n9{t2} z!8q)Rn~b`{NlE(^D)1`G2$|>Z*8XF4_l^B-{Icd(7FJ2nP}pVV`Rg~VS9?<+zop(MBBY;@;5$&W z3dawo@ZYW^F2PzAQ7pml%I+{RhC?uESknRRm%qIq4ZBPr4W&la;gU~@vBx)qmD!olLlh}IwT>rNhn0!yhGf%J-M z6vhEYVAaF>rR8lNctah~L6vgY;;V-<>*4~T(zW!2-#TaX3D#dx_cT^ID*C^tPuczn zk%;kq_boDG*mXnae$;m(3sc*AIwmA;Z7R#euyfJXwO_y3zOe?s(P!SZ&0*Jm$Ell8 zTm-ZEP*|Eu9&YlEBRD+c@K=;ml*dCD`ZFKPw3Ub0 zr3JQ0;3(0<>qVC)Ci>Fj2OLfTb91Z$;2!<^kA8{imbEuM;|ez+vPhnW6+Vy%FFoj& zJtAzrRpk&aH}#B*^(1Uu*r+`LY1c>Dpxi#Ep~6maEqFCg6voq+ zQGVvS)trVTS4Vqv$lSpemExEtM<(oY*k=F=SMv}Pz zrHt#n6>`^ZdWAO)!cJ2vgAaY)0t<$RUZ)tYhFk4 zCVS6{>@!%fRUck>4e?aEN-rT3p;nZ9&H-D{e$mI^;O!mYWQ1%7omjZTV@&^C~8-QPp$Nuzmca zKP3HueYEC>v`n(dO%2{ienWBd%TkI04ro5G{<(JTL5VuFRhQpup-ZWyQ{{LoWPF9s zQi^G{70iWewo^YCazjavUGZkeA~1Bkl0jVmkP9EtJtHSsrL+(}<~e@Es(GQ-`*$J0 ztDHpTgY7kz`@zYs8|I9=U_*cqhC0HDP;4o3dSRSY5^a15FF-Gv1){*qKcIRX{grG# zAxD`4`M#x{OvI-PTwJG`l6XVxncFENzqoN+GAyCVKd3o+E)!WdO8gpI?tCQqw5};7 z6LxxBIo)qQin}TSTjA3fLiR8-RNMIN6(!#a-6qX~C^F`%-N>ug^eyfnBPE%YmLL|2 zCA9^m^07b%?%VOJTwG!iua4FyRnNu6_Pb9#3s|k}wUh~v`s}fc@ax42I|81sr4Ngwwv(s^uAK$_U4V;(VE9Q=B6ilR`$jKu`(u?Uh zYt%h~KRcG{gse5e7t8NW>`h2ek72rziV}5gjK;pN4H+dQUgG-reUm5ZfC6X3>Q#F7 ze{Kp6?c}!`&l|5XttblJXD&t6%}|~J=H`4PgTuh?VZr9HZD;*aJ`ZmGqKCsaq}}FM zb`CRCS8`T0J7t`5z0E0n2~G=O>aiTS2fA=`iYOa<`Hv_5bU=A}@mhI8BV90aLe2?IgyxV#LNl zC?;7;mt5^<`-4VWTJ*F1?p{g+;(H`oDO-a1xoBQbxm;CI^d;WogX-n?VDHti<1)sN z<(!;{gP;{H(CiniG{PjKw*sY$8e)JQ)+8E~72N}>xZN|Qb>^4sfgj}?@}jS!kbIBA zMC)u7cZId#%4Ubra=)a>Fycg|N(D1;C`h&aL>BbML38XO7ItdtDdpdd zbE`CP_gPHTSw)UCD8VL$Nuh(;U7N?F3kGYJ4gyQ*ieq)L#(U&77aD>l zmRdceQ3wDvnYUZ&t!+2wphi$Yb;v1@q&SLG_$A0}sh5zTBw%ee0R|Fwaq<>=OIhsq5oT>Er%jNDX!2$Wx73FjE5!Ry{ z?^_z{(umpFGJch5w&<(gC`5?BBO2+BiJT_OZsv&7@$8VFuS@THM~HoLGHgFtF%Ouw z+#mMCw@LlUNRh}ZHdVN*F!mLy-SWv(d)1_7?in+)mTKl3p~nR?-eI?*CP=&-lK&3`~kTlH=9>MYMOuAqFyz68bH9?yOdJLhBQ z6U=zBy-eZYme1-&;QOU5nKF{y*4}$U1|dUV@@dh*EX5D*Ty7q~ z$dEgckp9*Wa)AiQ;m@WXJS%+TMO^Mw9mIzp7y2s%uHD)R((F9g}^tKVh_o_r6Oob!4BiB!&m^t`GWna+_C(~86OoR+=mCp|?ZGvfO z;thB9C;Ss%5`3$2>tZnDaM|hTG&EtPHut(rLhEnYzAhHdZG4;0y9>~;1cQ|zmqKr*S~vVcST}F?a3`m~EN`bf;TT!*5u2 zSvKM?^DB1cDD$y_hR-e<6ep+hUVP!tlM2$(>ZHZ$C<8Y~+rn^XLW4`2k8BjRUk|(# z-hRuMt;{!0R6N?~UbcnLh|7Fq+6fZbtySY^35N#iZ7I!Oa!k}g^!NYpR$Q^*lg=my zb8flCl@-XYglAHa=a_cBz<6Ek>35w!VhWB9A}z#PJxbH~1wSdA?+bQw!tJv&%C>78n$sp39R&4hB#tVTbl^wUf25|BdOoT$9;u$SX>Y!AW3+&rU5Kmay zM%A=K25I)hTeVT((_37F8U!La6sC4Mj%mKD!ibKn3moD~2B@4PqeXu-APZjduL>|l zPVr5xA;R;PmpYtCe|cly82_(5sqP zTCFL=rG00JVZ&Po51lEw%#*qXxTkw7S^Yl%tbCrHrXJ!f0tS-~ibWjh9!5V*``+HE zB~7mb?^113XQKREUimz`_c44P*B=WP40&3zsk=ZT|ZJ6 zSsz11orJl(Y4xDke8;oZ|^pvlVv&~2L(nPH=D}gm(vy- zt=;S``-@Toh0y5JoFSW3hakjd(F9Jg5VfyApbbtOYHf&+yq?-h?G_QL9sOVU?_!ox zvVoJ)EgNcf=LXMpS*4Zpy^(Xoh1dN*eMmmoD+B481Nu%lDM*p(w zqL!_09(yNs%&(dlRJ4zy%pIh9zTf`fA`pcQKE#nrt%4Y9T>?Z!yhLDJ>+6FaNurEA z**iE-X~md>YPQGF-1lgGWTjTCa*Clg!O${*GNjHJgoh?JLQ-1oL)q6erq0e?y8$xX z=;W65uM6)Lq_2EaeKBDluw~m_Mub-~YES=GOVAcVGh>j(chX{|q*r%yV@63PoxkIC z*&JEkisDyPG=)cQaTL7Py$!6(z(ggh-2UxbnPl^G;(|+Op3n+oYFRpjt9UCWmdbhq znAB6@gy^soQp~w{#SZqXMBFz`kE))B)o#L@MLVWcQ^KVDy{!-4bEIyezi(55#v>d* z?El%V=-H~GVmeg5>{BWUUYy4wKUG=V?gp{C061rH4<-w?bI$jUk!NO<%e&fuW?m*06Fo<})H1^(-u*rP`FaH-yA@_GF3}yr z)3p|E>%w87kOf?c9Z{9}3Qf*WBo)L#<9$H(Q5bt_7e4q>uSwB&)9dPqt_rgj-2)z* z*Na{c<^U0SdgsjSvf6!()xFl!d|FQ^l;Ep{BiM-x>&_vpV`6S zRRVlHqmQsqq~j?W)HeiFQQrzNa-7znQM_X?hW1@SC+CAkv2R~h~I}2otTh)?B=kHzeG~y2)ac-ByFal%}cKWyzo1RM0CL=M8?~%{CuHmTAyY4 zmid)98FDuHvz>t|ax$T)=PWBF1z0@tSd4Iu={h*5oxo2A9D2te2JJMo^CxfCs*Z}j zL;0F3L!9@kNt&8Z*k@G}xE}$d1TTC$rl}=Vg=4=a!9OiELeKyAg{H3af4|SkR`Qg( z)DZq^gTFNN6z3LRDJw&!Krz=_*ZlOOWwtfy{k5oeF%K||v}yDnkXpt`n5q9Z{RynD z#2CMME!DP1UG{P=hn;O<#zf_oD8?xsu_u;>0U-3TV)b^C)VX*UbRk-z`WH%dLfMZv zQs&{L^fVTVIf5<}?Pt!q+zcdkAo?pC5+gIa`k*BB+4k-ih!0})T86=iA6Gy4OSSN2 zFO7|S{pPY_Kcr;w+wKvF8yU2M}pZdM4b_Q3p#SY5R^C^nqaNm2Xj#`DBVH5SZY@xr;OW9>sY3rdF7N zB{Z$KTp9>Krp+|GwfZpmJgUhg)^oW+t^yb{*h_L+O zkSo-&LMElZ*~U{EsJfgDU|qtxyi8~_^xK%aJ);Yy>bKU%Tt7Qx#2i2-A3`#+}w1#zP~k@TEwmy>V+ zN5-ieZyKoaL>fjPG&TPEQi4Z5bI6DWbpjaoGk%IaDFdz2I^+{}D<4}UF^*)uagcSY zR5Jvr?O%KNfbaI62IVtMrMmQPTz{00t9_(am6>$JGlk@#WtCJ$<|Be={V z74WOq6(zg4hhGJe^Iy(B?_s?lZ7$@pg6M&ace1$Wbx%*-D`_`>38B4xM$=y?3EvBQdMv(Tj_rgJwtQ<0m&pu`k= zkof6E1Mu}>#joZxeB=EIxJe70UD&?ObLq;xgTCUx@j`cQz=~Zz6wREeXDfZJwI^`- z3n`xquckpV!`^z{3LDb84NA9Fz1N0BWa!5B=n)gwvZhV5kLe2ogL(xH1u?#&mdnMz zq0r~ag$3*e4V=H&jJpnM&ie1DK1n_~~D zhNRiHI=lRd6?(N0UMZcsnRRKH@qIFfpt6F|j%IA9piYb0Pjn8!tNjM)Iw(8x`8VWg zL{gaCt=HbB5EfVT%U_X7r_1k}IOo%+>Yp;}`5mOuF4 zeZJcI9c|BIIDYn1A&ap_j{k!I>d(tC$L*ydW-f9<68A>xO5w}=h zfaetOJ*YM_J_DVQuMTqFN+ss^68FoXcY5C_U703QDTe1YlO0aBG@F#)?p42VRB|mZ zb;YB5CNLw@khS{--Y0~_6Vec~g0?qO2GSEZ)Ol>m@XCCWYVXV1zn4I{p0_@3g{I3S zt4JfCI<7B%PI+DJ;PlA@H^+)QIjEHyYo|FTB7Bywp3z@|q$?q@22Z%RoNrI<2!Aqd zHooqm><77rC~Z@Ti43ix6#?w|fI}_9LY5FWreSBAZ(|^=&C1M0ShY-)45>M*(5IIe2hD2DuY_`H--ZX=t-aX8L%H-b4Ki?Ymg>1V^ zRPaxaSsJyP8IZ5uC}XZ?;F_D8iyxbdYPY_Zt8DlKrF*SnsA`go&N#Up&xlEse_{TCCv$gE_atWz9 zpQS?r-?>})Sao7o?2x3l%xrU82x4P?CvlcQUm8>*MlMSwf|GpN} zE(eE^*QxBf&8PB~Bt?jUwO|Pk@qdJUF{(G5lZi z3_IRaD(&X486+|o&1K95`%)7R<8I%2y(zVMc`Ui5`rnAOa-*8WPE3~^soNpPpUdO2 z#~c+{zOttc+cXDCvGOou>i9BC*=}XrZiT_X)%P8qC${!zt9**6ws~Pu_eAikn8<(( z1&T3s^L!8GWXYl$DrXvKy%Xf?hQd_iTgub>rsMW_TnM9l7((9A$ABqM3+ipX-n94g z0Sw9)GnxGM=VvB_9aWf1{^>RQGJa5y{qB$@Qw$zq{qGKieL3mz(*rkMNb8UxovmW9 zD+7e#vr@B%imE#eOS9~F!z};SWbG63U>N(K?dknx^J@5B^%F1@OdG4ZXnnNJe9;}Q zGVa~HW^6+X;awzBmWwwXA2;Ih5yDQ!ck2$pn3!4E->UA?HR)A)qR1*8m6dV$po?lA zr>7Gh$JF)6q-&hUTxfwp!19Qbd5c2Bpmg1O`P+O*`fH%Bey)f9~IX8pseQC zWw@g~>^qsr#aA?0K}|LAKF(XdN>`J;RJT=xLX%0jeX20N`)R#bcN-_@%3CWVhVRK8 zub100^mo9q2W4pa!!orutDsth9_di;`>Oi|DwK!n;{OkDTw8rR{of_C??h$l=Eq_* zoVqxRwqN|kt=br@p`u-IczBw4{=I3`!=vdZt!oUg7Bxx54YNgGcjzQ$&HrwJYQBv2 zq$vN!M7VCX%%h!Q07z;`&grl39iIcbI+z8EOWs}YE#e(0XgyF-#aN8+u#Od8^9~-* zj_&EWIh%oRRDH-=QiIAtL@IOTKZK4}38E!HjN+wn6aBKR_u0XQ*amERbkg?nZ_7Di3w#)qsnY&?`}HEt;BvO>z35htUsp;wdD~p$r;qwD zG++?PhWT5TT?et)RQwYq^6)u~4J>$@N0U&Z^B(|Sby7{G3{RFQO?*pVHDs~Q-%DDA z^&s~n^nk@~knKK7{@L2c@%&pPXGvFm<(3&iG9 zVR7pkbc>Sj>BAI5jD&6mD*J-+dg^WOfv$dwg!kg)cnrj@X+SYd=PE8B^-Ya9lgJQ1 zeD!_r!Dbj0O3?Ud^Gd4avo9egS!>(5YVCg%7y*dA4YhSmb>kKWMSXL^myQx~&*&lNzUT8bH_aTeff z=|PN?^l$RO`c_QAs&2GkzJ<)^!s0`^o!jcn_L$wTpyYY6x@gHMG31B zVIG+r-fEbSUjeWR+#nT)~1FCIMUjfaWsQu|et9~*|Ruzpc%)b z+?Gz&x5rz84q1eC4MT;ysWc8k`(}sncJy%ENG?$TzMiZr+a;#Ba*ahzk0G?spADV4 zayqJvj%K5@tObv!|4AO*OD3F-!XC?0x@DOk8C?3VnfYM&lu`G((AGZ$>7aZ_fsX~U ztE0XekxTC=_3%9i)S>6l*#hDXX8hoa+b5P4gKo1t4#Wr3nw%*=+*%8B75=Ps@<~f6 zv4eFD41DVd0)=QB#pvSRXZb)}b|OIt+E%H=~jk7O@(8YyCfWPv)?EX$Oif>w1f zqRP6))z6gt{fSz!o=eV@e;|&H(49-11UZIA$0rU@-mex0tD*VKxuUe%7ziCN66-n^ z64ig6&^r($#B_=>8!So;HyLfM`6)R6BVNw#ktV-ba%qnFM5j**+p2sThC4QG_Smgl zsxsXa_0!zO$-W=q`g^tv(z5?U8_K2jP7dh6->>m}UZu2tq3B~Qc)KMiaMEE9K147hVpMP%rbokrLQm97B&ahzMzBh zZ_B40a|gyUPe5O)C~-3(_7$Gix>}CdBR=4{sP}=1!n8wREloLqxh=#*b)fJsj$KqH z^Tf~_m4lv>MyHKUL_)u-&j8DkTI?ES5G`>|r-$X~52w-8!(`mwM1#(nRz5f+SESoO z2&&{SOkz?~{znxXzgloTh^MZ4*|Rba4YjuQa-T651Gvb7H6N>{7-8(U_ujc;r%C5- z8thlTyqd}L_2suNzgq#Rd+b)AgPZ4-8l%1ti4)!`Owj|Z<{2b>2}YWg{Jy(#Qp6=U zapEFbp~fE^HT)$bIX8t3NUT48@aX-F!s}~pS*^!TAD?8sc;!4CbwTCe>2itoT#;Jl zmrWE4D{hiq(H^j#>|$Yg`X}j27~^ER+v4Z#`0WI7*Z7zz@36|PKb|%T5&EO;KVlhc z;pcRwLcbxUtJ<$495(q@K3A#G>+))^+OgM!<8m7F?>atF81|#@Kt_BnxVw)QUC$}I z;Q#z##TU#M)A+RE#p9CqlwG&HdbQ*#p%>ADYlT7%kkiR`uKWxXui`kXjTN=1mEg&P zI=>|qVUqtN&R?k6oE0+5E5$3zGP*RpQ+S%nT!udz5i;Ca3DwqhX9f**QIkGtQKKi5 z#yj21^p!i^KgyTyGHWH9u1><3TUR6xfrH9j@dT$BfAjx6%FcXe)#3{M9*|1&*?mfs6hBb(22!_9m9Ew?;|a% z8o_R6tv{npYNzCF<9g>j7=N;LM2zyI5RucnRgsXTwB!ixgKGXI?H>k4TQ^GNIEmoY zFvb0+ZG2qk7-e|L_r$x@%%xP8{n}@vs@DP|5E@Oat;lFecul#9K0cKqyo1|_AY4(e zo#`@3XTa4Wh);C_Ee>z!N_zDi^-#tB{MP4@4Lfn~J(sG~B}L%8Zho>Y0zmml;EA`2 z>mT;9@Bs>Wr(?tHj}kl0BeP!)7zs7&Q<3h)dW-0TPvwU?-W*Y%xKGV5`y~OEd^Bwn zB&Uo@Q?h+~ORQ~Klt$XQ0=*2rcYA(FW%)z;rzPIeFf6<7cbR%tHoGc^pUX3~g?$Y% zD~ySSCZFW%aiim=O|~Knv>%wy$T7s)PJwdFoCGMH$*;_kNJ*8$dvpkC@vId$M#8|5 zv^E=+WRgIqz&d28gdLk&g{)k(iKZws{&^F&IFQ5rg~p7Pyw*vse1=Td<=VE2+Y{)J z4_-Pws3RL~Xfcb7S@##nMRY$BA_xrY!{0 zu#t&gX8CumDkfQdWTGe+4RKqt=r7nXSZ{^k_cc3;A2Cs_jx+E5uPmYp3;kynsD>P@ z@Q)54rb~IucwJK1PAxmChfXI)878dHOPw6Cdt2H3Ai7+^F!{5wS4bt7daJ7`AoRQr zGjWCCW+O%B$15h3N-w<{Exz6VM$i8#NM&-a04IyJnvHv>AP%K+&>5y^MHZq_pL0S$ zNXW47HQ7Eid>t>_?fb!pa)!eFF}u|aKS9vcJH`ExuAEGlQRk76pnFHvf|!ZC6DsFz zmD4`@!G1Q|rZjGRr(XfMFS+8ltD!tI)iC%)&_O6w(f4nKcgTLq_YZe4S31j{Mp&1L z+@B(Kt_&OdVZ`Ej5l_tEys60FUx*|53dRnrcr`*IUtphoDHKG(4C@y^=7it2_dKgeo&!0x(ikFh%U$oV!k?u5-gjbzCn z)y9(D%GS*XuRyI&y{wrAsT9G1Qutn%GCXXZ!eZ%5F9mP@!8LJLa>fQlCp#gn=F*d6Zlqn!-pYFle zH5lb(yY=->0pGrD!`^TNU(7_2L-V~hgWHvt%69F2IfpcqsVE92m!*M9hc7S`pw2@*Rhszn=%qnG~!q4C32JzA#uyx2-kjQ()b51s^Mjlky&~`be*Omozp|}V; z<>||UMN!SlR4@HIF=Jhk8mZIaJF{Hdo9f(B{Z%vvghoU8O}r3y|Baz@SIkq~I3n(q42jE!vGMqYR~Oz_XmVwkHnW3W}KP=?Fxy z|CZF~=uF+KJ;@nunoKVt|GnM4WKEO$;VX~T9X1yVS+mZUaH{QOgL^VZKwK!f^h5R- zA8|N2jMO6!aA}ff=q$6M*^OD`EOvWs^LOR!@ny99DkY)dr{r}v*qrvLZ~?1y?i699 zMj^}aPam~SGs~;ZNUk#tect3Qgu%vdzGtAoyJa=7;9DMNvuG)a)?>8zHZuV zYw4w)U?***B+;lxy$c0(i**O(+^nr8V91$S$!qWK6tCT)ONtKQj+TnzqiCcuIiNX+NCW6XwNh*Z;tWmYE2%{DcRKF5a0N!;<-U`Th zuuUfE96}lCVgCR^FACFuuS9@NG7es)!ZlTuN1y4#!o(iDxSAT1=h^VvzDp9Bwr)xT z)#^8uUsz~3&->BhetLv&yj|}}jnFG8PVP&1stM=o(7VF&E1aJ47T>kB%P%}$c(rIIN|azf8TKvQQH z$f%m8-x%zNV27N5EM40c_&Rp{-Qfa*X;%+?4W$!4(+jXu5rdootLs<|_h8DVS9~k{ zSNzsZvnEKRy!0VtikRc*J+2FffVYl> z%O?Npmo`*H+DKWd`Vh;>)!-)0vlwg(+rOYxnifh>MSB)a1<784UrNsDPQJz`ARa}j zm^KGU!EpD*0zXP*lJfeC7JoYo6L%<-66^DJCbLvkEDku5Z zBN(eC7TAEr&n{t+O)AVFZL}D86I7(JG#pTmd}zX{=q46Ed`lzF1jvQ&?n%GRRWPLQAiF* z#3{+*xMPlu*2%$giGQ9cWfG3p3wobPKNqb5nJ`sb&sev9%-nEI*x|W%2r^OI+tdrP zl30}&7%unhRAOwH)&YFaaIsX5RqA{$?`cHO>x&(VD^;Sgh98L(7mCU*>jaSHq;5s3 zP(zJO5pBog^+&jg9Gd$YKU}DH#L1E5%O0LUk`CkKbwDO9!5`qA@q$&l;Ar{e^QnF6K0%=(k`$Y6aW zPz9la8fBBiuHMGwwC7$im=5n4X$G-Z?G-r#c8`|}CHtT7QOTd~gBP_IbUJzKE}**) zmqZcoK(zg73tyNG^8KT4U+>nUnNgLTnjaN!02_h^UKI<}}*aIr+r*XAV;Qp&pJ&H*)+Snb$i zCtsp^@P4ll_0B~!rW6~F_Q_G@K9v#Gx*Vqk)P;s34sc#C^cw;>!SsJMjZ0h-{$s5S7c;0hra$6{-zl(&covc<`<$B@_Mvr|O zjd*iGr+)3GIjlz}&5*G|eiNL3RLpw?!Lp!c4JbLR&=noQG_BWD5<8|<<0@*6$rW)+ z3>=)`ZIkc;RM#vPwuXGnSNhL&EMh%=q{izJ(8@i7XOCGs{N=5N?Pf59kl4nrE~ZP( zhq3Erf;s}`TJQyBbQy8ILfmuD_7qMI%05soOqVG5o)mV?SG||Os+qqLqx%<`_amh=QoZ4TyzlvLF<*}&G5ayrYI|FY#5Riv zk~;g9Ar9i2Aszj$*#p0ew|~!KD2ElDKH&{O?p8}EeBiTV;h8$j5leyv{A;+; zQzQERKGtWwEB1M=?*cE^F^4cAEm_ZhA5ul3Y%L?4LWNn(9y!Di`o+2;u-Qx&FK+^qBOl{O?fNF*(tQd^V{P-sm2N|NfqI zY^vc$!(WeT{PYVyQ5v^+JQ=f)OX1J7jNfjwylTL3H8);_zZiMsEjYwds&5hA8N|QC zzy2htlka)B9R9Vxw&u0%w+0D9p#w1L@YDihC%fQ4r-I-=_tGP?ocO9G1^tLQBCNT- zbdNWh`JJ_cF2~g!)as2^iKNv@EF7};{R6mD41(jb!I;d0Kx7fRFO~4@hKBKE^-~+8R(EHv@|zcVBgJ;5l*9Z>ukJVk z>?Q16&Cy;rgHKK3jSnhWBWk_!%U0AMG-D(<35k!1%BY#D+Qp~U77^4cu5bPhc$sB+ zdmS-VwFvLxgkT!t{ZI20L|% zNJ!IpVR{nzx6**ZpQKH>Z205XbF;U1@^9Znls4)KbCS{(QRoSmvp3Y!ELNmQAW Date: Sun, 17 Aug 2025 12:56:46 +0100 Subject: [PATCH 138/253] Move assert location for clarity. --- python/PiFinder/integrator.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 4a4e125b2..b33a0201e 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -175,9 +175,10 @@ def update_imu(solved, last_image_solve, imu, imu_dead_reckoning): """ if not(last_image_solve and imu_dead_reckoning.tracking): return # Need all of these to do IMU dead-reckoning + + assert isinstance(imu["quat"] , quaternion.quaternion), "Expecting quaternion.quaternion type" # TODO: Can be removed later # When moving, switch to tracking using the IMU - assert isinstance(imu["quat"] , quaternion.quaternion), "Expecting quaternion.quaternion type" # TODO: Can be removed later angle_moved = qt.get_quat_angular_diff(last_image_solve["imu_quat"], imu["quat"]) if angle_moved > IMU_MOVED_ANG_THRESHOLD: # Estimate camera pointing using IMU dead-reckoning From 6e4c51995712198c3e78aa90a5cbc77372a98c66 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 17 Aug 2025 13:16:57 +0100 Subject: [PATCH 139/253] Update README --- python/PiFinder/pointing_model/README.md | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/python/PiFinder/pointing_model/README.md b/python/PiFinder/pointing_model/README.md index ce746cc35..04743ea29 100644 --- a/python/PiFinder/pointing_model/README.md +++ b/python/PiFinder/pointing_model/README.md @@ -207,6 +207,10 @@ rotation `q_imu2cam` that rotates the IMU frame to the camera frame. ![Image](docs/PiFinder_Flat_bare_PCB_camera_coords.jpg) +The transformations will be approximate and there will be small errors in +`q_imu2cam` due to mechanical tolerances. These errors will contribute to the +tracking error between the plate solved coordinates and the IMU dead-reckoning. + ## Roll The roll (as given by Tetra3) is defined as the rotation of the north pole From f7ce9f4f91e1cb801b666e4d20b8b6ad178f3240 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 17 Aug 2025 13:17:19 +0100 Subject: [PATCH 140/253] Update q_imu2cam transformations for other types (not all done yet) --- .../pointing_model/imu_dead_reckoning.py | 28 ++++++++++++++++--- 1 file changed, 24 insertions(+), 4 deletions(-) diff --git a/python/PiFinder/pointing_model/imu_dead_reckoning.py b/python/PiFinder/pointing_model/imu_dead_reckoning.py index 4986ecea9..c8a972d53 100644 --- a/python/PiFinder/pointing_model/imu_dead_reckoning.py +++ b/python/PiFinder/pointing_model/imu_dead_reckoning.py @@ -188,14 +188,34 @@ def get_screen_direction_q_imu2cam(screen_direction: str) -> np.quaternion: q_imu2cam: Quaternion that rotates the IMU frame to the camera frame. """ if screen_direction == "left": - raise ValueError('Unsupported screen_direction: left') + # Left: + # Rotate 90° around x_imu so that z_imu' points along z_camera + q1 = qt.axis_angle2quat([1, 0, 0], np.pi / 2) + # Rotate 90° around z_imu' to align with the camera cooridnates + q2 = qt.axis_angle2quat([0, 0, 1], np.pi / 2) + q_imu2cam = (q1 * q2).normalized() elif screen_direction == "right": - raise ValueError('Unsupported screen_direction: right') + # Right: + # Rotate -90° around y_imu so that z_imu' points along z_camera + q1 = qt.axis_angle2quat([0, 1, 0], np.pi / 2) + # Rotate 90° around z_imu' to align with the camera cooridnates + q2 = qt.axis_angle2quat([0, 0, 1], -np.pi / 2) + q_imu2cam = (q1 * q2).normalized() elif screen_direction == "straight": - raise ValueError('Unsupported screen_direction: straight') + # Straight: + # Rotate 180° around y_imu so that z_imu' points along z_camera + q1 = qt.axis_angle2quat([0, 1, 0], np.pi / 2) + # Rotate -90° around z_imu' to align with the camera cooridnates + q2 = qt.axis_angle2quat([0, 0, 1], -np.pi / 2) + q_imu2cam = (q1 * q2).normalized() elif screen_direction == "flat3": # Flat v3: - raise ValueError('Unsupported screen_direction: flat3') + # Rotate -XX° around y_imu so that z_imu' points along z_camera + q1 = qt.axis_angle2quat([0, 1, 0], -np.pi / 2) + # Rotate -90° around z_imu' to align with the camera cooridnates + q2 = qt.axis_angle2quat([0, 0, 1], -np.pi / 2) + q_imu2cam = (q1 * q2).normalized() + raise ValueError('Unsupported screen_direction: flat3') # TODO: Update the unknown tilt and remove this elif screen_direction == "flat": # Flat v2: # Rotate -90° around y_imu so that z_imu' points along z_camera From 603fb0527b8af010e70b826be30678d1b6f27a5b Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 17 Aug 2025 13:23:11 +0100 Subject: [PATCH 141/253] Update comments --- python/PiFinder/pointing_model/imu_dead_reckoning.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/python/PiFinder/pointing_model/imu_dead_reckoning.py b/python/PiFinder/pointing_model/imu_dead_reckoning.py index c8a972d53..b7ad95b4c 100644 --- a/python/PiFinder/pointing_model/imu_dead_reckoning.py +++ b/python/PiFinder/pointing_model/imu_dead_reckoning.py @@ -41,7 +41,7 @@ class ImuDeadReckoning(): imu_dead_reckoning.update_imu(q_x2imu) """ # Alignment: - q_scope2cam: np.quaternion # ****Do we need this?? + q_scope2cam: np.quaternion # TODO: Do we need this?? q_cam2scope: np.quaternion # IMU orientation: q_imu2cam: np.quaternion @@ -51,7 +51,7 @@ class ImuDeadReckoning(): # The poinging of the camera and scope frames wrt the Equatorial frame. # These get updated by plate solving and IMU dead-reckoning. - q_eq2cam: np.quaternion # ***Do we need to keep q_eq2cam? + q_eq2cam: np.quaternion # True when q_eq2cam is estimated by IMU dead-reckoning. # False when set by plate solving From a566de28aa698386c853a53f6cf79934106f83aa Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 17 Aug 2025 13:27:47 +0100 Subject: [PATCH 142/253] Remove commented out code that change the IMU output axes. --- python/PiFinder/imu_pi.py | 40 +++++++-------------------------------- 1 file changed, 7 insertions(+), 33 deletions(-) diff --git a/python/PiFinder/imu_pi.py b/python/PiFinder/imu_pi.py index 4065ebbf5..42b277303 100644 --- a/python/PiFinder/imu_pi.py +++ b/python/PiFinder/imu_pi.py @@ -23,6 +23,12 @@ class Imu: + """ + Previous version modified the IMU axes but the IMU now outputs the + measurements using its native axes and the transformation from the IMU + axes to the camera frame is done by the IMU dead-reckonig functionality. + """ + def __init__(self): i2c = board.I2C() self.sensor = adafruit_bno055.BNO055_I2C(i2c) @@ -30,39 +36,7 @@ def __init__(self): self.sensor.mode = adafruit_bno055.IMUPLUS_MODE # self.sensor.mode = adafruit_bno055.NDOF_MODE cfg = config.Config() - """ Disable rotating the IMU axes. Use its native form - if ( - cfg.get_option("screen_direction") == "flat" - or cfg.get_option("screen_direction") == "straight" - or cfg.get_option("screen_direction") == "flat3" - ): - self.sensor.axis_remap = ( - adafruit_bno055.AXIS_REMAP_Y, - adafruit_bno055.AXIS_REMAP_X, - adafruit_bno055.AXIS_REMAP_Z, - adafruit_bno055.AXIS_REMAP_POSITIVE, - adafruit_bno055.AXIS_REMAP_POSITIVE, - adafruit_bno055.AXIS_REMAP_NEGATIVE, - ) - elif cfg.get_option("screen_direction") == "as_dream": - self.sensor.axis_remap = ( - adafruit_bno055.AXIS_REMAP_X, - adafruit_bno055.AXIS_REMAP_Z, - adafruit_bno055.AXIS_REMAP_Y, - adafruit_bno055.AXIS_REMAP_POSITIVE, - adafruit_bno055.AXIS_REMAP_POSITIVE, - adafruit_bno055.AXIS_REMAP_POSITIVE, - ) - else: - self.sensor.axis_remap = ( - adafruit_bno055.AXIS_REMAP_Z, - adafruit_bno055.AXIS_REMAP_Y, - adafruit_bno055.AXIS_REMAP_X, - adafruit_bno055.AXIS_REMAP_POSITIVE, - adafruit_bno055.AXIS_REMAP_POSITIVE, - adafruit_bno055.AXIS_REMAP_POSITIVE, - ) - """ + self.quat_history = [(0, 0, 0, 0)] * QUEUE_LEN self._flip_count = 0 self.calibration = 0 From 3e31adfd5f4c3365b729c9fb3b1c58e8c8f2c2cc Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Sun, 17 Aug 2025 14:48:00 +0200 Subject: [PATCH 143/253] Add type hints to integrator --- python/PiFinder/integrator.py | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index b33a0201e..95d0a1dc1 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -7,6 +7,7 @@ """ +import datetime import queue import time import copy @@ -91,7 +92,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr # ======== Wrapper and helper functions =============================== -def estimate_roll_offset(solved, dt): +def estimate_roll_offset(solved: dict, dt: datetime.datetime) -> float: """ Estimate the roll offset due to misalignment of the camera sensor with the mount/scope's coordinate system. The offset is calculated at the @@ -111,7 +112,7 @@ def estimate_roll_offset(solved, dt): return roll_offset -def update_plate_solve_and_imu(imu_dead_reckoning, solved): +def update_plate_solve_and_imu(imu_dead_reckoning: ImuDeadReckoning, solved: dict): """ Wrapper for ImuDeadReckoning.update_plate_solve_and_imu() to interface angles in degrees to radians. @@ -144,7 +145,7 @@ def update_plate_solve_and_imu(imu_dead_reckoning, solved): set_alignment(imu_dead_reckoning, solved) -def set_alignment(imu_dead_reckoning, solved): +def set_alignment(imu_dead_reckoning: ImuDeadReckoning, solved: dict): """ Set alignment. TODO: Do this once at alignment @@ -168,7 +169,7 @@ def set_alignment(imu_dead_reckoning, solved): imu_dead_reckoning.set_alignment(q_scope2cam) -def update_imu(solved, last_image_solve, imu, imu_dead_reckoning): +def update_imu(solved: dict, last_image_solve: dict, imu: np.quaternion, imu_dead_reckoning: ImuDeadReckoning): """ Updates the solved dictionary using IMU dead-reckoning from the last solved pointing. @@ -176,7 +177,7 @@ def update_imu(solved, last_image_solve, imu, imu_dead_reckoning): if not(last_image_solve and imu_dead_reckoning.tracking): return # Need all of these to do IMU dead-reckoning - assert isinstance(imu["quat"] , quaternion.quaternion), "Expecting quaternion.quaternion type" # TODO: Can be removed later + assert isinstance(imu["quat"] , np.quaternion), "Expecting np.quaternion type" # TODO: Can be removed later # When moving, switch to tracking using the IMU angle_moved = qt.get_quat_angular_diff(last_image_solve["imu_quat"], imu["quat"]) From af30980473806dfb40984fb9cbb4e7e3c729ead0 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Sun, 17 Aug 2025 14:54:06 +0200 Subject: [PATCH 144/253] Update README --- python/PiFinder/pointing_model/imu_dead_reckoning.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/python/PiFinder/pointing_model/imu_dead_reckoning.py b/python/PiFinder/pointing_model/imu_dead_reckoning.py index b7ad95b4c..cf52bbd9f 100644 --- a/python/PiFinder/pointing_model/imu_dead_reckoning.py +++ b/python/PiFinder/pointing_model/imu_dead_reckoning.py @@ -29,7 +29,7 @@ class ImuDeadReckoning(): All angles are in radians. None is not allowed as inputs (use np.nan). - EXAMPLE: + EXAMPLE: TODO: Update # Set up: imu_dead_reckoning = ImuDeadReckoning('flat') imu_dead_reckoning.set_alignment(q_scope2cam) From 9a09ec33b1b67a59006bc99a3c052d90402bb1b8 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Sun, 17 Aug 2025 14:54:37 +0200 Subject: [PATCH 145/253] Reorder input parameter order for consistency --- python/PiFinder/integrator.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 95d0a1dc1..22955d6b2 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -73,7 +73,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr # the last plate solved coordinates. imu = shared_state.imu() if imu: - update_imu(solved, last_image_solve, imu, imu_dead_reckoning) + update_imu(imu_dead_reckoning, solved, last_image_solve, imu) # Is the solution new? if solved["RA"] and solved["solve_time"] > last_solve_time: @@ -169,7 +169,7 @@ def set_alignment(imu_dead_reckoning: ImuDeadReckoning, solved: dict): imu_dead_reckoning.set_alignment(q_scope2cam) -def update_imu(solved: dict, last_image_solve: dict, imu: np.quaternion, imu_dead_reckoning: ImuDeadReckoning): +def update_imu(imu_dead_reckoning: ImuDeadReckoning, solved: dict, last_image_solve: dict, imu: np.quaternion): """ Updates the solved dictionary using IMU dead-reckoning from the last solved pointing. From 07f24f1c45fda602257b52e8d2ac80f0381ac032 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Tue, 19 Aug 2025 19:33:07 +0200 Subject: [PATCH 146/253] Update set_screen_direction with v3 Flat and as_dream --- .../PiFinder/pointing_model/imu_dead_reckoning.py | 14 ++++++++++---- 1 file changed, 10 insertions(+), 4 deletions(-) diff --git a/python/PiFinder/pointing_model/imu_dead_reckoning.py b/python/PiFinder/pointing_model/imu_dead_reckoning.py index cf52bbd9f..7caac1849 100644 --- a/python/PiFinder/pointing_model/imu_dead_reckoning.py +++ b/python/PiFinder/pointing_model/imu_dead_reckoning.py @@ -210,12 +210,12 @@ def get_screen_direction_q_imu2cam(screen_direction: str) -> np.quaternion: q_imu2cam = (q1 * q2).normalized() elif screen_direction == "flat3": # Flat v3: - # Rotate -XX° around y_imu so that z_imu' points along z_camera - q1 = qt.axis_angle2quat([0, 1, 0], -np.pi / 2) + # Camera is tilted a further 30° compared to Flat v2 + # Rotate -120° around y_imu so that z_imu' points along z_camera + q1 = qt.axis_angle2quat([0, 1, 0], -np.pi * 2 / 3) # Rotate -90° around z_imu' to align with the camera cooridnates q2 = qt.axis_angle2quat([0, 0, 1], -np.pi / 2) q_imu2cam = (q1 * q2).normalized() - raise ValueError('Unsupported screen_direction: flat3') # TODO: Update the unknown tilt and remove this elif screen_direction == "flat": # Flat v2: # Rotate -90° around y_imu so that z_imu' points along z_camera @@ -224,7 +224,13 @@ def get_screen_direction_q_imu2cam(screen_direction: str) -> np.quaternion: q2 = qt.axis_angle2quat([0, 0, 1], -np.pi / 2) q_imu2cam = (q1 * q2).normalized() elif screen_direction == "as_dream": - raise ValueError('Unsupported screen_direction: as_dream') + # As Dream: + # Camera points back up from the screen + # NOTE: Need to check if the orientation of the camera is correct + # Rotate +90° around z_imu to align with the camera cooridnates + # (+y_cam is along -x_imu) + q2 = qt.axis_angle2quat([0, 0, 1], +np.pi / 2) + q_imu2cam = (q1 * q2).normalized() else: raise ValueError(f'Unsupported screen_direction: {screen_direction}') From c15c12a68cfffd429c6d6d07c8c63b6b85a43cd5 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Tue, 19 Aug 2025 21:20:53 +0200 Subject: [PATCH 147/253] Update comments --- python/PiFinder/pointing_model/imu_dead_reckoning.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/python/PiFinder/pointing_model/imu_dead_reckoning.py b/python/PiFinder/pointing_model/imu_dead_reckoning.py index 7caac1849..32595b8a3 100644 --- a/python/PiFinder/pointing_model/imu_dead_reckoning.py +++ b/python/PiFinder/pointing_model/imu_dead_reckoning.py @@ -94,7 +94,7 @@ def update_plate_solve_and_imu(self, solved_cam_ra: float, time) is available, q_x2imu (the unknown drifting reference frame) will be solved for. - INPUTS: + INPUTS: TODO: Update these solved_cam_az: [rad] Azimuth of the camera pointing from plate solving. solved_cam_alt: [rad] Alt of the camera pointing from plate solving. solved_cam_roll_offset: [rad] Roll offset of the camera frame +y ("up") From 700f77c9792397083ecda0216dbc32b669d367c0 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Tue, 19 Aug 2025 22:21:43 +0100 Subject: [PATCH 148/253] Add get_roll_by_mount_type(). --> Desktop-tested --- python/PiFinder/integrator.py | 79 ++++++++++++++++++++++++----------- 1 file changed, 55 insertions(+), 24 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 22955d6b2..bf6a1adc5 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -30,9 +30,10 @@ IMU_MOVED_ANG_THRESHOLD = np.deg2rad(0.1) # Use IMU tracking if the angle moved is above this -def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=True): # TODO: Change back is_debug=False +def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=False): MultiprocLogging.configurer(log_queue) """ """ + is_debug = True # TODO: For development. Remove later. if is_debug: logger.setLevel(logging.DEBUG) logger.debug("Starting Integrator") @@ -40,6 +41,9 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr try: solved = get_initialized_solved_dict() # Dict of RA, Dec, etc. initialized to None. cfg = config.Config() + + mount_type = cfg.get_option("mount_type") + logger.debug(f"mount_type = {mount_type}") # Set up dead-reckoning tracking by the IMU: imu_dead_reckoning = ImuDeadReckoning(cfg.get_option("screen_direction")) @@ -78,10 +82,17 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr # Is the solution new? if solved["RA"] and solved["solve_time"] > last_solve_time: last_solve_time = time.time() + + # Set the roll so that the chart is displayed appropriately for the mount type + solved["Roll"] \ + = get_roll_by_mount_type(shared_state, solved["RA"], + solved["Dec"], mount_type) + # Update remaining solved keys solved["constellation"] = calc_utils.sf_utils.radec_to_constellation( solved["RA"], solved["Dec"] ) + # add solution shared_state.set_solution(solved) shared_state.set_solve_state(True) @@ -92,27 +103,9 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Tr # ======== Wrapper and helper functions =============================== -def estimate_roll_offset(solved: dict, dt: datetime.datetime) -> float: - """ - Estimate the roll offset due to misalignment of the camera sensor with - the mount/scope's coordinate system. The offset is calculated at the - center of the camera's FoV. - - To calculate the roll with offset: roll = calculated_roll + roll_offset - - TODO: This is currently not being used! - """ - # Calculate the expected roll at the camera center given the RA/Dec of - # of the camera center. - roll_camera_calculated = calc_utils.sf_utils.radec_to_roll( - solved["camera_center"]["RA"], solved["camera_center"]["Dec"], dt - ) - roll_offset = solved["camera_center"]["Roll"] - roll_camera_calculated - - return roll_offset - -def update_plate_solve_and_imu(imu_dead_reckoning: ImuDeadReckoning, solved: dict): +def update_plate_solve_and_imu(imu_dead_reckoning: ImuDeadReckoning, + solved: dict): """ Wrapper for ImuDeadReckoning.update_plate_solve_and_imu() to interface angles in degrees to radians. @@ -125,6 +118,7 @@ def update_plate_solve_and_imu(imu_dead_reckoning: ImuDeadReckoning, solved: dic else: # Successfully plate solved & camera pointing exists if solved["imu_quat"] is None: + # TODO: This Do not run the rest of the code? q_x2imu = np.quaternion(np.nan) else: q_x2imu = solved["imu_quat"] # IMU measurement at the time of plate solving @@ -134,9 +128,6 @@ def update_plate_solve_and_imu(imu_dead_reckoning: ImuDeadReckoning, solved: dic solved_cam_dec = np.deg2rad(solved["camera_center"]["Dec"]) solved_cam_roll = np.deg2rad(solved["camera_center"]["Roll"]) - # TODO: Target roll isn't calculated by Tetra3. Set to zero here - solved["Roll"] = 0 - # Update: imu_dead_reckoning.update_plate_solve_and_imu( solved_cam_ra, solved_cam_dec, solved_cam_roll, q_x2imu) @@ -207,3 +198,43 @@ def update_imu(imu_dead_reckoning: ImuDeadReckoning, solved: dict, last_image_so solved["solve_time"] = time.time() solved["solve_source"] = "IMU" + + +def get_roll_by_mount_type(shared_state, ra_deg: float, dec_deg:float, + mount_type: str) -> float: + """ + Returns the roll (in degrees) depending on the mount type so that the chart + is displayed appropriately for the mount type. The RA and Dec of the target + should be provided (in degrees). + + * Alt/Az mount: Display the chart in the horizontal coordinate so the + * EQ mount: Display the chart in the equatorial coordinate system with the + NCP up so roll = 0. + """ + if mount_type == "Alt/Az": + # Altaz mounts: Display chart in horizontal coordinates + # Try to set date and time + location = shared_state.location() + dt = shared_state.datetime() + + if location and dt: + # We have location and time/date + calc_utils.sf_utils.set_location( + location.lat, + location.lon, + location.altitude, + ) + # Find the roll at the target RA/Dec in the horizontal frame + roll_deg = calc_utils.sf_utils.radec_to_roll(ra_deg, dec_deg, dt) + else: + # No position or time/date available, so set roll to 0 + roll_deg = 0 + + elif mount_type == "EQ": + # EQ-mounts: Display chart with NCP up so roll = 0 + roll_deg = 0 + else: + logger.error(f"Unknown mount type: {mount_type}. Cannot set roll.") + roll_deg = 0 + + return roll_deg From 4ce00122150328ce11897779923f6c58aa20477d Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Tue, 19 Aug 2025 23:36:49 +0100 Subject: [PATCH 149/253] Updated README with sky test observations --> Sky Test --- python/PiFinder/pointing_model/README.md | 35 +++++++++++++++++------- 1 file changed, 25 insertions(+), 10 deletions(-) diff --git a/python/PiFinder/pointing_model/README.md b/python/PiFinder/pointing_model/README.md index 04743ea29..d5ad16e67 100644 --- a/python/PiFinder/pointing_model/README.md +++ b/python/PiFinder/pointing_model/README.md @@ -16,20 +16,35 @@ README: IMU support prototyping * Go through TODOs * Discuss requirements.txt with Richard +Later: +* Update imu_pi.py + # Sky test log >Remove this before release! -* 20250817: 5cf8aae - * Tested on altaz and eq mounts - * **altaz:** Tracked fine. When the PiFinder was non-upright, I got the - feeling it tended to jump after an IMU track and got a plate-solve. This - wasn't seen when the PiFinder was upright. When non-upright, the crosshair - moved diagonally when the scope was moved in az or alt. The rotated - constellations in the chart were hard to make out. - * **EQ:** Seemed to work fine but I'm not experienced with EQ. The display on - SkySafari showed RA movement along the horizontal direction and Dec along - the vertical. This seemed to make sense. +## 20250819: 700f77c (tested 19/20 Aug) + +* Tested on altaz mount in altaz & eq mode +* OK: + * Changed chart display so that altaz is in horizontal frame and EQ mode displays in equatorial + coordinates. This appears to work. + * Tracking on chart and SkySafari OK. +* Issues: + * Catalog crashes in altaz mode (ok in EQ mode). Probably because we don't calculate altaz in integrator.py? Same behaviour under test mode so we could do desktop tests. + + +## 20250817: 5cf8aae + +* Tested on altaz and eq mounts +* **altaz:** Tracked fine. When the PiFinder was non-upright, I got the + feeling it tended to jump after an IMU track and got a plate-solve. This + wasn't seen when the PiFinder was upright. When non-upright, the crosshair + moved diagonally when the scope was moved in az or alt. The rotated + constellations in the chart were hard to make out. +* **EQ:** Seemed to work fine but I'm not experienced with EQ. The display on + SkySafari showed RA movement along the horizontal direction and Dec along + the vertical. This seemed to make sense. # Installation & set up From b9df702a3d6ac60c338f9ab05b5b41952cee514e Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Wed, 20 Aug 2025 00:42:46 +0100 Subject: [PATCH 150/253] Update TODO --- python/PiFinder/pointing_model/README.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/python/PiFinder/pointing_model/README.md b/python/PiFinder/pointing_model/README.md index d5ad16e67..08d377ab3 100644 --- a/python/PiFinder/pointing_model/README.md +++ b/python/PiFinder/pointing_model/README.md @@ -7,12 +7,12 @@ README: IMU support prototyping >Remove this before release! -* Support other PiFinder types +* Done: Support other PiFinder types * Use RaDecRoll class * Type hints for integrator.py * Lint using Nox -* Roll offset -* Alignment +* Done: Adjust Roll depending on mount_type for charts +* Use alignment rather than calculating every loop * Go through TODOs * Discuss requirements.txt with Richard From c7b65f0c5e9b5c7d714070f864db96da663c4219 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Wed, 20 Aug 2025 00:46:34 +0100 Subject: [PATCH 151/253] Update altaz in integrator.py to see if this helps with the catalog issue? --- python/PiFinder/integrator.py | 12 ++++++++++-- 1 file changed, 10 insertions(+), 2 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index bf6a1adc5..97d48e347 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -92,7 +92,15 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa solved["constellation"] = calc_utils.sf_utils.radec_to_constellation( solved["RA"], solved["Dec"] ) - + + # Set Alt/Az because it's needed for the catalogs for the + # Alt/Az mount type: + dt = shared_state.datetime() + if dt: + # TODO: Is it ok to not set location? Check. Pass dt to get_roll_by_mount_type? + solved["Alt"], solved["Az"] \ + = calc_utils.sf_utils.radec_to_altaz(solved["RA"], solved["Dec"], dt) + # add solution shared_state.set_solution(solved) shared_state.set_solve_state(True) @@ -218,7 +226,7 @@ def get_roll_by_mount_type(shared_state, ra_deg: float, dec_deg:float, dt = shared_state.datetime() if location and dt: - # We have location and time/date + # We have location and time/date TODO: Is it necessary to set location? calc_utils.sf_utils.set_location( location.lat, location.lon, From 8d4346f0ec5a711ec0b2a2f97438df587d375085 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Wed, 20 Aug 2025 01:08:39 +0100 Subject: [PATCH 152/253] Refactored altaz calcuatlion. Now catalog works in altaz mount mode. --- python/PiFinder/integrator.py | 38 +++++++++++++++++------------------ 1 file changed, 18 insertions(+), 20 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 97d48e347..5ea7ea6ae 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -83,10 +83,16 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa if solved["RA"] and solved["solve_time"] > last_solve_time: last_solve_time = time.time() + # Try to set date and time + location = shared_state.location() + dt = shared_state.datetime() + # Set location for roll and altaz calculations. TODO: Is it necessary to set location? + calc_utils.sf_utils.set_location(location.lat, location.lon, + location.altitude) + # Set the roll so that the chart is displayed appropriately for the mount type - solved["Roll"] \ - = get_roll_by_mount_type(shared_state, solved["RA"], - solved["Dec"], mount_type) + solved["Roll"] = get_roll_by_mount_type(solved["RA"], solved["Dec"], + location, dt, mount_type) # Update remaining solved keys solved["constellation"] = calc_utils.sf_utils.radec_to_constellation( @@ -94,10 +100,9 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa ) # Set Alt/Az because it's needed for the catalogs for the - # Alt/Az mount type: + # Alt/Az mount type. TODO: Can this be moved to the catalog? dt = shared_state.datetime() - if dt: - # TODO: Is it ok to not set location? Check. Pass dt to get_roll_by_mount_type? + if location and dt: solved["Alt"], solved["Az"] \ = calc_utils.sf_utils.radec_to_altaz(solved["RA"], solved["Dec"], dt) @@ -208,8 +213,8 @@ def update_imu(imu_dead_reckoning: ImuDeadReckoning, solved: dict, last_image_so solved["solve_source"] = "IMU" -def get_roll_by_mount_type(shared_state, ra_deg: float, dec_deg:float, - mount_type: str) -> float: +def get_roll_by_mount_type(ra_deg: float, dec_deg:float, location, + dt: datetime.datetime, mount_type: str) -> float: """ Returns the roll (in degrees) depending on the mount type so that the chart is displayed appropriately for the mount type. The RA and Dec of the target @@ -218,21 +223,14 @@ def get_roll_by_mount_type(shared_state, ra_deg: float, dec_deg:float, * Alt/Az mount: Display the chart in the horizontal coordinate so the * EQ mount: Display the chart in the equatorial coordinate system with the NCP up so roll = 0. + + Assumes that location has already been set in calc_utils.sf_utils. """ if mount_type == "Alt/Az": - # Altaz mounts: Display chart in horizontal coordinates - # Try to set date and time - location = shared_state.location() - dt = shared_state.datetime() - + # Altaz mounts: Display chart in horizontal coordinates if location and dt: - # We have location and time/date TODO: Is it necessary to set location? - calc_utils.sf_utils.set_location( - location.lat, - location.lon, - location.altitude, - ) - # Find the roll at the target RA/Dec in the horizontal frame + # We have location and time/date (and assume that location has been set) + # Roll at the target RA/Dec in the horizontal frame roll_deg = calc_utils.sf_utils.radec_to_roll(ra_deg, dec_deg, dt) else: # No position or time/date available, so set roll to 0 From c0d1a8845d70f46ca54c2a90e89f6e836d1469b5 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Wed, 20 Aug 2025 01:09:33 +0100 Subject: [PATCH 153/253] Add note --- python/PiFinder/pointing_model/astro_coords.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/python/PiFinder/pointing_model/astro_coords.py b/python/PiFinder/pointing_model/astro_coords.py index fcd323c1e..2620b3eb2 100644 --- a/python/PiFinder/pointing_model/astro_coords.py +++ b/python/PiFinder/pointing_model/astro_coords.py @@ -71,7 +71,7 @@ def get_initialized_solved_dict() -> dict: "RA": None, "Dec": None, "Roll": None, - "Alt": None, # TODO: Remove Alt, Az keys later? + "Alt": None, # NOTE: Altaz needed by catalogs for altaz mounts "Az": None, }, "camera_solve": { # camera_solve is NOT updated by IMU dead-reckoning From e33780512c46c65f19cade5f64eb44e69456d602 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Wed, 20 Aug 2025 10:32:52 +0200 Subject: [PATCH 154/253] Update README --- python/PiFinder/pointing_model/README.md | 194 +++++++---------------- 1 file changed, 58 insertions(+), 136 deletions(-) diff --git a/python/PiFinder/pointing_model/README.md b/python/PiFinder/pointing_model/README.md index 08d377ab3..212d16917 100644 --- a/python/PiFinder/pointing_model/README.md +++ b/python/PiFinder/pointing_model/README.md @@ -48,13 +48,17 @@ Later: # Installation & set up -## Set up a virtual environment to test the PiFinder +## Install additional packages -We need to install additional Python packages for the changes by creating a conda environment. +This branch needs the `numpy.quaternion` package. For desktop-testing, you +could install it in a virtual environment. For field-testing, it's more +practical to install it as default. -## Create a virtual environment +### Create a virtual environment -The first step is to create a virtual environment using `venv`. Connect to the PiFinder using `ssh` and install venv to create a virtual environment: +Skip this section if you want to install the packages as default. + +This step creates a virtual environment using `venv`. Connect to the PiFinder using `ssh` and install venv to create a virtual environment: ```bash sudo apt-get install python3-venv @@ -75,6 +79,8 @@ Type this to activate the environment: source .venv_imu/bin/activate ``` +Follow the next step to install the packages in the virtual environmnet. + At the end, it can be de-activated by typing: ```bash @@ -198,8 +204,9 @@ We define the following reference frames: $\theta_{az}$ followed by a rotation around the mount's altitude axis by $\theta_{alt}$. -#### Scope frame (altaz) -* +z is boresight, +y is the vertical direction of the scope and +x is the +#### Scope frame +* +z is boresight. +* On an altaz mount, we define +y as the vertical direction of the scope and +x as the horizontal direction to the left when looking along the boresight. * In the ideal case, the Scope frame is assumed to be the same as the Gimbal frame. In reality, there may be errors due to mounting or gravity. @@ -210,7 +217,11 @@ We define the following reference frames: * $+z$ is the boresight of the camera, $+y$ and $+x$ are respectively the vertical and horizontal (to the left) directions of the camera. -## IMU and camera coordinate frames +#### IMU frame +* The IMU frame is the local coordinates that the IMU outputs the data in. +* The diagram below illustrates the IMU coordinate frame for the v2 PiFinder with the Adafruit BNO055 IMU. + +### IMU and camera coordinate frames To use the IMU for dead-reckoning, we need to know the transformation between the IMU's own coordinate frame and the PiFinder's camera coordinate frame @@ -226,7 +237,7 @@ The transformations will be approximate and there will be small errors in `q_imu2cam` due to mechanical tolerances. These errors will contribute to the tracking error between the plate solved coordinates and the IMU dead-reckoning. -## Roll +### Roll The roll (as given by Tetra3) is defined as the rotation of the north pole relative to the camera image's "up" direction ($+y$). A positive roll angle @@ -242,121 +253,62 @@ plate-solved RA and Dec for a camera on a perfect horizontal mount (i.e. the "up" $+y$ direction of the camera always points to the zenith). The camera pose is rotated by the angle `roll_offset` around its boresight. -## Telescope coordinate transformations and dead-reckoning using the IMU +### Telescope coordinate transformations -We will use quaternions to rotate between the coordinate frames. For example, -the quaternion `q_horiz2mnt` rotates the Horizontal frame to the Mount frame. -The quaternions can be multiplied to apply successive *intrinsic* rotation from -the Horizontal frame to the Camera; +We can use quaternions to rotate between the coordinate frames. +For example, the quaternion `q_horiz2mnt` rotates the Horizontal frame to the +Mount frame. The quaternions can be multiplied to apply successive *intrinsic* +rotation from the Horizontal frame to the Camera frame; ```python q_horiz2camera = q_horiz2mnt * q_mnt2gimb * q_gimb2scope * q_scope2camera ``` -`q_mnt2gimb` depends on the gimbal angles, which is what we can control to move -the scope. +Note that this convention makes it clear when applying intrinsic rotations (right-multiply). -## Coordinate frame transformation for altaz mounts *(remove functionality?)* +The Mount and Gimbal frames are not used in the current implementation but this +framework could be used to extend the implementation to control the mount. For +example, `q_mnt2gimb` depends on the gimbal angles, which is what we can +control to move the scope. -During normal operation, we want to find the pointing of the scope, expressed -using $q_{hor2scope}$, which is the quaternion that rotates the scope axis in -the horizontal frame from the *home* position to the current pointing. +## Coordinate frame transformation -### Plate solving +We will use the equatorial frame as the reference frame. The goal is determine the scope pointing in RA and Dec. The pointing of the scope relative to the equatorial frame can be described by quaternion $q_{eq2scope}$. -Plate solving returns the pointing of the PiFinder camera in RA/Dec/Roll -coordinates which can be converted to the quaternion rotation $q_{hor2cam}$. +The PiFinder uses the coordinates from plate-solving but this is at a low rate and plate-solving may not succeed when the scope is moving so the IMU measurements can be used to infer the pointing between plate-solving by dead-reckoning. -Plate solving also returns the roll but this is probably less accurate. For -this reason, we will will initially assume a perfect altaz mount with the -PiFinder mounted upright. +### Plate solving -The alignment offset $q_{cam2scope}$ between the PiFinder camera frame and the -scope frame is determined during alignment of the PiFinder with the scope. -Assuming that this offset is constant, we can infer the pointing of the scope -at time step $k$: +Plate-solving returns the pointing of the PiFinder camera in (RA, Dec, Roll) coordinates. The quaternion rotation of the camera pointing relative to the equatorial frame for time step $k$ is given by $q_{eq2cam}(k)$ and the scope pointing is give by, $$q_{hor2scope}(k) = q_{hor2cam}(k) \; q_{cam2scope}$$ -We will use the PiFinder's camera frame as the reference because plate solving -is done relative to the camera frame. - -The quaternion $q_{hor2cam}$ represents the orientation of the PiFinder camera -relative to the Horizontal frame. Using the axis-angle interpretation, the axis -points along the altaz of the camera center and rotated by the roll offset -(explained above). +We use the PiFinder's camera frame as the reference because plate solving is done relative to the +camera frame. $q_{cam2scope}$ is the quaternion that represents the alignment offset between the +PiFinder camera frame and the scope frame ### Alignment -As already mentioned, the alignment of the PiFinder determines $q_{cam2scope}$ -and we assume that this is fixed. - -During alignment, plate solving gives the RA/Dec of the the camera frame -pointing which can be used to estimate $q_{hor2cam}$ assuming a perfect altaz -mount. The roll measurement by the camera could be used to determine the -rotation of the camera frame around its $z_{cam}$ axis if the roll measurement -is accurate enough. Otherwise the roll will need to be inferred assuming that -the PiFinder is mounted upright. +The alignment offset between the PiFinder camera frame and the +scope frame is determined during alignment of the PiFinder with the scope and is assumed to be fixed. The goal of alignment is to determine the quaternion $q_{cam2scope}$. -At the same time, the user selects the target seen by the scope, which gives -the RA/Dec of the scope pointing. We can use this to get a fix on -$q_{hor2scope}$ (assuming a perfect altaz mount); +During alignment, the user user selects the target seen in the center the scope, which gives the (RA, Dec) of the scope pointing but not the roll. We can assume some arbitrary roll value (say roll = 0) and get $q_{eq2scope}$. At the same time, plate solving measures the (RA, Dec, Roll) at the camera center or $q_{eq2cam}$. We can express the relation by, -$$q_{hor2scope}(k) = q_{hor2cam}(k) \; q_{cam2scope}$$ +$$q_{eq2scope} = q_{eq2cam} \; q_{cam2scope}$$ Rearranging this gives, -$$q_{cam2scope} = q_{hor2cam}^{-1}(k) \; q_{hor2scope}(k)$$ +$$q_{cam2scope} = q_{hor2cam}^{-1} \; q_{hor2scope}$$ Note that for unit quaternions, we can also use the conjugate $q^*$ instead of $q^{-1}$, because the conjugate is slightly faster to compute. -Some scopes and focusers can be rotated around its axis which also rotates the -PiFinder with it. This would currently require a re-alignment. +Roll returned by plate-solving is not relevant for pointing and it can be arbitrary but it is needed for full three degrees-of-freedom dead-reckoning by the IMU. ### Dead-reckoning -Between plate solving, the IMU extrapolates the scope orientation by dead -reckoning. Suppose that at the $k$ th time step, plate solves finds the camera -pointing, $q_{hor2cam}(k)$. It can be related to the IMU measurement -$q_{x2imu}(k)$ by, - -$$q_{hor2cam}(k) = q_{hor2x}(k) \; q_{x2imu}(k) \; q_{imu2cam}$$ - -The IMU outputs its orientation $q_{x2imu}$ relative to a frame $X$ which is -similar to the horizontal frame but drifts over time; in particular, it will -predominantly drift by rotating around the $z_{hor}$ axis because the IMU with -just accelerometer/gyro fusion has no means to determine the bearing. -$q_{imu2cam}$ rotates the IMU frame to the scope frame. It depends on the -PiFinder type and is assumed to be fixed. Because of small errors in the -alignmet of the IMU relative to the camera, there will be errors that will not -be captured by the preset $q_{imu2cam}$. This will introduce errors in the -dead-reckoning. - -The drift $q_{hor2x}$ is unknown but it drifts slowly enough that we can assume -that it will be constant between successive plate solves. - -$$q_{hor2x}(k) = q_{hor2cam}(k) \; q_{imu2cam}^{-1} \; q_{x2imu}^{-1}(k)$$ - -In subsequent time steps, the drift, $q_{hor2x}(k)$, estimated in the last -plate solve can be used. At time step $k+l$ without plate solving, the the -camera pointing can be esimated by: - -$$\hat{q}_{hor2cam}(k+l) = q_{hor2x}(k) \; q_{x2imu}(k+l) \; q_{imu2cam}$$ - -Where $\hat{q}_{hor2cam}$ represents an estimate of the camera pointing using -dead-reckoning from the IMU. From this, we can make a dead-reckoning estimate -of the scope pointing; - -$$q_{hor2scope}(k + l) = \hat{q}_{hor2cam}(k + l) \; q_{cam2scope}$$ - -## Coordinate frame transformation using equatorial coordinates - -We can also use the equatorial frame as the reference, using (RA, Dec, Roll) -from the PiFinder camera as the inputs without the need to convert to altaz -coordinates. - -The pointing of the scope at time step `k` using IMU dead-reckoning is given by +Between plate solving, the IMU extrapolates the scope orientation by dead reckoning. Suppose that we +want to use the IMU measurement at time step $k$ to estimate the scope pointing; ```python q_eq2scope(k) = q_eq2cam(k-m) * q_cam2imu * q_x2imu(k-m).conj() * q_x2imu(k) * q_imu2cam * q_cam2scope @@ -370,9 +322,9 @@ Where 3. Note that the quaternion `q_x2imu(k-m).conj() * q_x2imu(k)` rotates the IMU body from the orientation in the last solve (at time step `k-m`) to to the current orientation (at time step `k`). -4. `q_cam2imu = q_imu2cam.conj()` is the alignment of the IMU to the camera and -depends on the PiFinder configuration. There will be some error in this which -will propagate to the pointing error when using the IMU. +4. `q_cam2imu = q_imu2cam.conj()` is the alignment of the IMU to the camera and depends on the +PiFinder configuration. There will be some error due to mechanical tolerances which will propagate +to the pointing error when using the IMU. We can pre-compute the first three terms after plate solving at time step `k-m`, which corresponds to the quaternion rotation from the `eq` frame to the @@ -382,56 +334,26 @@ IMU's reference frame `x`. q_eq2x(k-m) = q_eq2cam(k-m) * q_cam2imu * q_x2imu(k-m).conj() ``` -## Next steps in the development - -The current implementation reproduces the existing functionality of the -PiFinder. The phase are: - -1. Reproduce PiFinder functionality using quaternion transformaitons for altaz - mounts. [Done] -2. Enable PiFinder to be mounted at any angle, not just upright. -3. Extend to equatorial mount. -4. Enable scopes to be rotated (i.e. rotate the PiFinder around the axis of the - scope). - -### Approach to support general PiFinder mounting angle - -Currently, we do not use the roll measurement in the alignment of the PiFinder -with the scope; $q_{cam2scope}$ only rotates in the alt/az directions. By using -the roll measurement, we will also account for rotation of the PiFinder around -the scope axis. This should (probably) enable the PiFinder to be mounted at any -angle rotated around the scope axis. - - -### Approach for equatorial mounts - -It should be possible to take a similar approach for an equatorial mounts. - -One issue is that it's common to rotate EQ-mounteed scopes (particularly -Newtoninans) around its axis so that the eyepiece is at a comfortable position. -As mentioned in the alignment section, this would require a re-alignment. That -would need to be resolved in a future step. - -#### Future improvements +## Potential future improvements -The next step would be to use a Kalman filter framework to estimate the -pointing. Some of the benefits are: +A potential next step could be to use a Kalman filter framework to estimate the pointing. Some of +the benefits are: * Smoother, filtered pointing estimate. -* Improve the accuracy of the pointing estimate (possibly more beneficial when - using the PiFinder estimate to control driven mounts). +* Improves the accuracy of the pointing estimate. Accuracy may be more beneficial when using the + PiFinder estimate to control driven mounts. * Potentially enable any generic IMU (with gyro and accelerometer) to be used without internal fusion FW, which tends to add to the BOM cost. -* If required, could take fewer plate-solving frames by only triggering a plate -solve when the uncertainty of the Kalman filter estimate based on IMU -dead-reckoning exceeds some limit. +* If required, could take fewer plate-solving frames by only triggering a plate solve when the +uncertainty of the Kalman filter estimate based on IMU dead-reckoning exceeds some limit. This can +reduce power consumption and allow for a cheaper, less powerful computing platform to be used. -The accuracy improvement will come from the following sources: +The accuracy improvement will likely come from the following sources: * Filtering benefits from the averaging effects of using multiple measurements. * The Kalman filter will estimate the accelerometer and gyro bias online. The calibration will be done in conjunction with the plate-solved measurements so it will be better than an IMU-only calibration. * The orientation of the IMU to the camera frame, $q_{imu2cam}$, has errors -because of alignment errors. The Kalman filter will calibrate for this online. +because of mechanical tolerances. The Kalman filter will calibrate for this online. This will improve the accuracy and enable other non-standard form-factors. From 06ac22499c98c6e394be6d74d1f8a6f3273659de Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Wed, 20 Aug 2025 10:33:06 +0200 Subject: [PATCH 155/253] Add note to requirements_dev.txt --- python/requirements_dev.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/python/requirements_dev.txt b/python/requirements_dev.txt index d00428a4f..c3ab3e871 100644 --- a/python/requirements_dev.txt +++ b/python/requirements_dev.txt @@ -9,4 +9,4 @@ pygame==2.6.0 pre-commit==3.7.1 Babel==2.16.0 xlrd==2.0.2 -numpy-quaternion # For testing IMU +numpy-quaternion # For testing IMU (TODO: move to requirements.txt) From f3acc7cef0327c9e1b5e8049ed58a7dd4ef3bf36 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Wed, 20 Aug 2025 16:05:21 +0100 Subject: [PATCH 156/253] Ruff: camera_interface.py --- python/PiFinder/camera_interface.py | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/python/PiFinder/camera_interface.py b/python/PiFinder/camera_interface.py index 7b40ad71c..b673988da 100644 --- a/python/PiFinder/camera_interface.py +++ b/python/PiFinder/camera_interface.py @@ -14,7 +14,6 @@ import time from PIL import Image import numpy as np -import quaternion # Numpy quaternion from typing import Tuple import logging @@ -114,22 +113,23 @@ def get_image_loop( # see if we moved during exposure pointing_diff = 0.0 - + # TODO: REMOVE - #if imu_start and imu_end: + # if imu_start and imu_end: # pointing_diff = ( # abs(imu_start["pos"][0] - imu_end["pos"][0]) # + abs(imu_start["pos"][1] - imu_end["pos"][1]) # + abs(imu_start["pos"][2] - imu_end["pos"][2]) # ) - + # # Quaternion version if imu_start and imu_end: # Returns the pointing difference between successive IMU quaternions as - # an angle (radians). Note that this also accounts for rotation around the + # an angle (radians). Note that this also accounts for rotation around the # scope axis. Returns an angle in radians. pointing_diff = qt.get_quat_angular_diff( - imu_start["quat"], imu_end["quat"]) + imu_start["quat"], imu_end["quat"] + ) camera_image.paste(base_image) shared_state.set_last_image_metadata( From 215f78a5db60db9939695ba9b2d936c4da524b6c Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Wed, 20 Aug 2025 16:06:56 +0100 Subject: [PATCH 157/253] Ruff: imu_pi.py --- python/PiFinder/imu_pi.py | 30 ++++++++++++++++++++---------- 1 file changed, 20 insertions(+), 10 deletions(-) diff --git a/python/PiFinder/imu_pi.py b/python/PiFinder/imu_pi.py index 42b277303..0fef468f1 100644 --- a/python/PiFinder/imu_pi.py +++ b/python/PiFinder/imu_pi.py @@ -24,11 +24,11 @@ class Imu: """ - Previous version modified the IMU axes but the IMU now outputs the + Previous version modified the IMU axes but the IMU now outputs the measurements using its native axes and the transformation from the IMU - axes to the camera frame is done by the IMU dead-reckonig functionality. + axes to the camera frame is done by the IMU dead-reckonig functionality. """ - + def __init__(self): i2c = board.I2C() self.sensor = adafruit_bno055.BNO055_I2C(i2c) @@ -36,7 +36,7 @@ def __init__(self): self.sensor.mode = adafruit_bno055.IMUPLUS_MODE # self.sensor.mode = adafruit_bno055.NDOF_MODE cfg = config.Config() - + self.quat_history = [(0, 0, 0, 0)] * QUEUE_LEN self._flip_count = 0 self.calibration = 0 @@ -166,8 +166,14 @@ def imu_monitor(shared_state, console_queue, log_queue): "moving": False, "move_start": None, "move_end": None, - "pos": [0, 0, 0], # Corresponds to [Az, related_to_roll, Alt] --> **TO REMOVE LATER - "quat": np.quaternion(0, 0, 0, 0), # Scalar-first numpy quaternion(w, x, y, z) - Init to invalid quaternion + "pos": [ + 0, + 0, + 0, + ], # Corresponds to [Az, related_to_roll, Alt] --> **TO REMOVE LATER + "quat": np.quaternion( + 0, 0, 0, 0 + ), # Scalar-first numpy quaternion(w, x, y, z) - Init to invalid quaternion "start_pos": [0, 0, 0], "status": 0, } @@ -184,8 +190,10 @@ def imu_monitor(shared_state, console_queue, log_queue): imu_data["start_pos"] = imu_data["pos"] imu_data["move_start"] = time.time() # DISABLE old method - #imu_data["pos"] = imu.get_euler() # TODO: Remove this later. Was used to store Euler angles - imu_data["quat"] = quaternion.from_float_array(imu.avg_quat) # Scalar-first (w, x, y, z) + # imu_data["pos"] = imu.get_euler() # TODO: Remove this later. Was used to store Euler angles + imu_data["quat"] = quaternion.from_float_array( + imu.avg_quat + ) # Scalar-first (w, x, y, z) else: if imu_data["moving"]: # If we were moving and we now stopped @@ -193,8 +201,10 @@ def imu_monitor(shared_state, console_queue, log_queue): imu_data["moving"] = False imu_data["move_end"] = time.time() # DISABLE old method - #imu_data["pos"] = imu.get_euler() - imu_data["quat"] = quaternion.from_float_array(imu.avg_quat) # Scalar-first (w, x, y, z) + # imu_data["pos"] = imu.get_euler() + imu_data["quat"] = quaternion.from_float_array( + imu.avg_quat + ) # Scalar-first (w, x, y, z) if not imu_calibrated: if imu_data["status"] == 3: From 3921c81f7bb9fe68887552c085183d86339dbb37 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Wed, 20 Aug 2025 16:10:27 +0100 Subject: [PATCH 158/253] Ruff: imu_print_measurements.py --- python/PiFinder/imu_print_measurements.py | 28 +++++++++++++---------- 1 file changed, 16 insertions(+), 12 deletions(-) diff --git a/python/PiFinder/imu_print_measurements.py b/python/PiFinder/imu_print_measurements.py index 5e955e232..23b47379b 100644 --- a/python/PiFinder/imu_print_measurements.py +++ b/python/PiFinder/imu_print_measurements.py @@ -3,18 +3,20 @@ """ For testing the IMU: Not for use by PiFinder main loop. Prints the IMU measurements (based on imu_pi.py) + +TODO: Remove this in the future. """ import time import board import adafruit_bno055 -#import logging +# import logging from scipy.spatial.transform import Rotation -#from PiFinder import config +# from PiFinder import config -#logger = logging.getLogger("IMU.pi") +# logger = logging.getLogger("IMU.pi") QUEUE_LEN = 10 MOVE_CHECK_LEN = 2 @@ -26,7 +28,7 @@ def __init__(self): self.sensor = adafruit_bno055.BNO055_I2C(i2c) self.sensor.mode = adafruit_bno055.IMUPLUS_MODE # self.sensor.mode = adafruit_bno055.NDOF_MODE - + # Unlike Imu(), we use the IMU's native orientation self.quat_history = [(0, 0, 0, 0)] * QUEUE_LEN self._flip_count = 0 @@ -45,7 +47,7 @@ def __init__(self): self.__moving_threshold = (0.0005, 0.0003) def quat_to_euler(self, quat): - """ + """ INPUTS: quat: Scalar last quaternion (x, y, z, w) @@ -80,12 +82,12 @@ def update(self): # Throw out non-calibrated data self.calibration = self.sensor.calibration_status[1] if self.calibration == 0: - #logger.warning("NOIMU CAL") + # logger.warning("NOIMU CAL") return True # adafruit_bno055 gives quaternion convention (w, x, y, z) quat = self.sensor.quaternion if quat[0] is None: - #logger.warning("IMU: Failed to get sensor values") + # logger.warning("IMU: Failed to get sensor values") return _quat_diff = [] @@ -134,11 +136,13 @@ def update(self): self.__moving = True def get_euler(self): - return list(self.quat_to_euler(self.avg_quat)) # !! Expect scalar-last but avg_quat is scalar-first?? + return list( + self.quat_to_euler(self.avg_quat) + ) # !! Expect scalar-last but avg_quat is scalar-first?? def imu_monitor(): - #MultiprocLogging.configurer(log_queue) + # MultiprocLogging.configurer(log_queue) imu = ImuSimple() imu_calibrated = False imu_data = { @@ -156,7 +160,7 @@ def imu_monitor(): imu_data["status"] = imu.calibration if imu.moving(): if not imu_data["moving"]: - #logger.debug("IMU: move start") + # logger.debug("IMU: move start") imu_data["moving"] = True imu_data["start_pos"] = imu_data["pos"] imu_data["move_start"] = time.time() @@ -168,7 +172,7 @@ def imu_monitor(): else: if imu_data["moving"]: # If we were moving and we now stopped - #logger.debug("IMU: move end") + # logger.debug("IMU: move end") imu_data["moving"] = False imu_data["pos"] = imu.get_euler() imu_data["quat"] = imu.avg_quat @@ -177,7 +181,7 @@ def imu_monitor(): if not imu_calibrated: if imu_data["status"] == 3: imu_calibrated = True - #console_queue.put("IMU: NDOF Calibrated!") + # console_queue.put("IMU: NDOF Calibrated!") if __name__ == "__main__": From f84b6e7b933aea1447efb2a5c2070275ee633253 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Wed, 20 Aug 2025 16:11:35 +0100 Subject: [PATCH 159/253] Move imu_print_measurements.py to pointing_model/ --- python/PiFinder/{ => pointing_model}/imu_print_measurements.py | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename python/PiFinder/{ => pointing_model}/imu_print_measurements.py (100%) diff --git a/python/PiFinder/imu_print_measurements.py b/python/PiFinder/pointing_model/imu_print_measurements.py similarity index 100% rename from python/PiFinder/imu_print_measurements.py rename to python/PiFinder/pointing_model/imu_print_measurements.py From 8836d3624059f53179705a93c40e0b6b24331e15 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Wed, 20 Aug 2025 16:14:53 +0100 Subject: [PATCH 160/253] Ruff: integrator.py --- python/PiFinder/integrator.py | 108 ++++++++++++++++++++-------------- 1 file changed, 65 insertions(+), 43 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 5ea7ea6ae..b4a879efb 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -19,7 +19,7 @@ from PiFinder import state_utils import PiFinder.calc_utils as calc_utils from PiFinder.multiproclogging import MultiprocLogging -from PiFinder.pointing_model.astro_coords import RaDecRoll, get_initialized_solved_dict +from PiFinder.pointing_model.astro_coords import get_initialized_solved_dict from PiFinder.pointing_model.imu_dead_reckoning import ImuDeadReckoning import PiFinder.pointing_model.quaternion_transforms as qt @@ -27,7 +27,9 @@ logger = logging.getLogger("IMU.Integrator") # Constants: -IMU_MOVED_ANG_THRESHOLD = np.deg2rad(0.1) # Use IMU tracking if the angle moved is above this +IMU_MOVED_ANG_THRESHOLD = np.deg2rad( + 0.1 +) # Use IMU tracking if the angle moved is above this def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=False): @@ -39,15 +41,17 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa logger.debug("Starting Integrator") try: - solved = get_initialized_solved_dict() # Dict of RA, Dec, etc. initialized to None. + solved = ( + get_initialized_solved_dict() + ) # Dict of RA, Dec, etc. initialized to None. cfg = config.Config() mount_type = cfg.get_option("mount_type") logger.debug(f"mount_type = {mount_type}") - + # Set up dead-reckoning tracking by the IMU: imu_dead_reckoning = ImuDeadReckoning(cfg.get_option("screen_direction")) - #imu_dead_reckoning.set_alignment(q_scope2cam) # TODO: Enable when q_scope2cam is available + # imu_dead_reckoning.set_alignment(q_scope2cam) # TODO: Enable when q_scope2cam is available # This holds the last image solve position info # so we can delta for IMU updates @@ -87,25 +91,28 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa location = shared_state.location() dt = shared_state.datetime() # Set location for roll and altaz calculations. TODO: Is it necessary to set location? - calc_utils.sf_utils.set_location(location.lat, location.lon, - location.altitude) + calc_utils.sf_utils.set_location( + location.lat, location.lon, location.altitude + ) # Set the roll so that the chart is displayed appropriately for the mount type - solved["Roll"] = get_roll_by_mount_type(solved["RA"], solved["Dec"], - location, dt, mount_type) + solved["Roll"] = get_roll_by_mount_type( + solved["RA"], solved["Dec"], location, dt, mount_type + ) # Update remaining solved keys solved["constellation"] = calc_utils.sf_utils.radec_to_constellation( solved["RA"], solved["Dec"] ) - + # Set Alt/Az because it's needed for the catalogs for the # Alt/Az mount type. TODO: Can this be moved to the catalog? - dt = shared_state.datetime() + dt = shared_state.datetime() if location and dt: - solved["Alt"], solved["Az"] \ - = calc_utils.sf_utils.radec_to_altaz(solved["RA"], solved["Dec"], dt) - + solved["Alt"], solved["Az"] = calc_utils.sf_utils.radec_to_altaz( + solved["RA"], solved["Dec"], dt + ) + # add solution shared_state.set_solution(solved) shared_state.set_solve_state(True) @@ -117,8 +124,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa # ======== Wrapper and helper functions =============================== -def update_plate_solve_and_imu(imu_dead_reckoning: ImuDeadReckoning, - solved: dict): +def update_plate_solve_and_imu(imu_dead_reckoning: ImuDeadReckoning, solved: dict): """ Wrapper for ImuDeadReckoning.update_plate_solve_and_imu() to interface angles in degrees to radians. @@ -128,38 +134,39 @@ def update_plate_solve_and_imu(imu_dead_reckoning: ImuDeadReckoning, """ if (solved["RA"] is None) or (solved["Dec"] is None): return # No update - else: + else: # Successfully plate solved & camera pointing exists if solved["imu_quat"] is None: # TODO: This Do not run the rest of the code? q_x2imu = np.quaternion(np.nan) else: q_x2imu = solved["imu_quat"] # IMU measurement at the time of plate solving - + # Convert to radians: - solved_cam_ra = np.deg2rad(solved["camera_center"]["RA"]) + solved_cam_ra = np.deg2rad(solved["camera_center"]["RA"]) solved_cam_dec = np.deg2rad(solved["camera_center"]["Dec"]) solved_cam_roll = np.deg2rad(solved["camera_center"]["Roll"]) # Update: imu_dead_reckoning.update_plate_solve_and_imu( - solved_cam_ra, solved_cam_dec, solved_cam_roll, q_x2imu) - + solved_cam_ra, solved_cam_dec, solved_cam_roll, q_x2imu + ) + # Set alignment. TODO: Do this once at alignment. Move out of here. set_alignment(imu_dead_reckoning, solved) def set_alignment(imu_dead_reckoning: ImuDeadReckoning, solved: dict): """ - Set alignment. + Set alignment. TODO: Do this once at alignment """ # Convert to radians: - solved_cam_ra = np.deg2rad(solved["camera_center"]["RA"]) + solved_cam_ra = np.deg2rad(solved["camera_center"]["RA"]) solved_cam_dec = np.deg2rad(solved["camera_center"]["Dec"]) solved_cam_roll = np.deg2rad(solved["camera_center"]["Roll"]) # Convert to radians: - target_ra = np.deg2rad(solved["RA"]) + target_ra = np.deg2rad(solved["RA"]) target_dec = np.deg2rad(solved["Dec"]) solved["Roll"] = 0 # TODO: Target roll isn't calculated by Tetra3. Set to zero here target_roll = np.deg2rad(solved["Roll"]) @@ -173,61 +180,76 @@ def set_alignment(imu_dead_reckoning: ImuDeadReckoning, solved: dict): imu_dead_reckoning.set_alignment(q_scope2cam) -def update_imu(imu_dead_reckoning: ImuDeadReckoning, solved: dict, last_image_solve: dict, imu: np.quaternion): +def update_imu( + imu_dead_reckoning: ImuDeadReckoning, + solved: dict, + last_image_solve: dict, + imu: np.quaternion, +): """ Updates the solved dictionary using IMU dead-reckoning from the last - solved pointing. + solved pointing. """ - if not(last_image_solve and imu_dead_reckoning.tracking): + if not (last_image_solve and imu_dead_reckoning.tracking): return # Need all of these to do IMU dead-reckoning - - assert isinstance(imu["quat"] , np.quaternion), "Expecting np.quaternion type" # TODO: Can be removed later + + assert isinstance( + imu["quat"], np.quaternion + ), "Expecting np.quaternion type" # TODO: Can be removed later # When moving, switch to tracking using the IMU angle_moved = qt.get_quat_angular_diff(last_image_solve["imu_quat"], imu["quat"]) - if angle_moved > IMU_MOVED_ANG_THRESHOLD: + if angle_moved > IMU_MOVED_ANG_THRESHOLD: # Estimate camera pointing using IMU dead-reckoning - logger.debug("Track using IMU. Angle moved since last_image_solve = " - "{:}(> threshold = {:})".format(np.rad2deg(angle_moved), - np.rad2deg(IMU_MOVED_ANG_THRESHOLD))) - + logger.debug( + "Track using IMU. Angle moved since last_image_solve = " + "{:}(> threshold = {:})".format( + np.rad2deg(angle_moved), np.rad2deg(IMU_MOVED_ANG_THRESHOLD) + ) + ) + # Dead-reckoning using IMU imu_dead_reckoning.update_imu(imu["quat"]) # Latest IMU meas - + # Store current camera pointing estimate: ra_cam, dec_cam, roll_cam = imu_dead_reckoning.get_cam_radec() solved["camera_center"]["RA"] = np.rad2deg(ra_cam) solved["camera_center"]["Dec"] = np.rad2deg(dec_cam) solved["camera_center"]["Roll"] = np.rad2deg(roll_cam) - + # Store the current scope pointing estimate ra_target, dec_target, roll_target = imu_dead_reckoning.get_scope_radec() solved["RA"] = np.rad2deg(ra_target) solved["Dec"] = np.rad2deg(dec_target) - solved["Roll"] = np.rad2deg(roll_target) + solved["Roll"] = np.rad2deg(roll_target) q_x2imu = imu["quat"] - logger.debug(" IMU quat = ({:}, {:}, {:}, {:}".format(q_x2imu.w, q_x2imu.x, q_x2imu.y, q_x2imu.z)) + logger.debug( + " IMU quat = ({:}, {:}, {:}, {:}".format( + q_x2imu.w, q_x2imu.x, q_x2imu.y, q_x2imu.z + ) + ) solved["solve_time"] = time.time() solved["solve_source"] = "IMU" -def get_roll_by_mount_type(ra_deg: float, dec_deg:float, location, - dt: datetime.datetime, mount_type: str) -> float: - """ +def get_roll_by_mount_type( + ra_deg: float, dec_deg: float, location, dt: datetime.datetime, mount_type: str +) -> float: + """ Returns the roll (in degrees) depending on the mount type so that the chart is displayed appropriately for the mount type. The RA and Dec of the target should be provided (in degrees). - * Alt/Az mount: Display the chart in the horizontal coordinate so the + * Alt/Az mount: Display the chart in the horizontal coordinate so the * EQ mount: Display the chart in the equatorial coordinate system with the NCP up so roll = 0. Assumes that location has already been set in calc_utils.sf_utils. """ if mount_type == "Alt/Az": - # Altaz mounts: Display chart in horizontal coordinates + # Altaz mounts: Display chart in horizontal coordinates if location and dt: # We have location and time/date (and assume that location has been set) # Roll at the target RA/Dec in the horizontal frame From 36e5709d8b9af7731fcab0b540b1ef2afc381fe0 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Wed, 20 Aug 2025 16:15:23 +0100 Subject: [PATCH 161/253] Ruff: astro_coords.py --- .../PiFinder/pointing_model/astro_coords.py | 36 +++++++++++-------- 1 file changed, 21 insertions(+), 15 deletions(-) diff --git a/python/PiFinder/pointing_model/astro_coords.py b/python/PiFinder/pointing_model/astro_coords.py index 2620b3eb2..b318f708a 100644 --- a/python/PiFinder/pointing_model/astro_coords.py +++ b/python/PiFinder/pointing_model/astro_coords.py @@ -1,47 +1,53 @@ """ Various astronomical coordinates functions """ + from dataclasses import dataclass import numpy as np from typing import Union # When updated to Python 3.10+, remove and use new type hints @dataclass -class RaDecRoll(): +class RaDecRoll: """ - Data class for equatorial coordinates defined by (RA, Dec, Roll). - + Data class for equatorial coordinates defined by (RA, Dec, Roll). + The set methods allow values to be float or None but internally, None will be stored as np.nan so that the type is consistent. the get methods will return None if the value is np.nan. TODO: Migrate to something like this from the current "solved" dict? - + NOTE: All angles are in radians. """ + ra: float = np.nan dec: float = np.nan roll: float = np.nan - def set(self, ra:Union[float, None], dec:Union[float, None], - roll:Union[float, None]): + def set( + self, ra: Union[float, None], dec: Union[float, None], roll: Union[float, None] + ): """ """ self.ra = ra if ra is not None else np.nan self.dec = dec if dec is not None else np.nan self.roll = roll if roll is not None else np.nan - def set_from_deg(self, ra_deg:Union[float, None], - dec_deg:Union[float, None], roll_deg:Union[float, None]): + def set_from_deg( + self, + ra_deg: Union[float, None], + dec_deg: Union[float, None], + roll_deg: Union[float, None], + ): """ """ ra = np.deg2rad(ra_deg) if ra_deg is not None else np.nan dec = np.deg2rad(dec_deg) if dec_deg is not None else np.nan roll = np.deg2rad(roll_deg) if roll_deg is not None else np.nan self.set(ra, dec, roll) - - def get(self) -> tuple[Union[float, None], Union[float, None], - Union[float, None]]: - """ Returns (ra, dec, roll) in radians """ + + def get(self) -> tuple[Union[float, None], Union[float, None], Union[float, None]]: + """Returns (ra, dec, roll) in radians""" ra = self.ra if not np.isnan(self.ra) else None dec = self.dec if not np.isnan(self.dec) else None roll = self.roll if not np.isnan(self.roll) else None @@ -55,7 +61,7 @@ def get_deg(self) -> tuple[float, float, float]: def get_initialized_solved_dict() -> dict: """ - Returns an initialized 'solved' dictionary with cooridnate and other + Returns an initialized 'solved' dictionary with cooridnate and other information. TODO: The solved dict is used by other components. Move this func @@ -74,7 +80,7 @@ def get_initialized_solved_dict() -> dict: "Alt": None, # NOTE: Altaz needed by catalogs for altaz mounts "Az": None, }, - "camera_solve": { # camera_solve is NOT updated by IMU dead-reckoning + "camera_solve": { # camera_solve is NOT updated by IMU dead-reckoning "RA": None, "Dec": None, "Roll": None, @@ -89,5 +95,5 @@ def get_initialized_solved_dict() -> dict: "cam_solve_time": 0, "constellation": None, } - + return solved From db274ce12177e4d60528a41ca6f004f26ceb4ac2 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Wed, 20 Aug 2025 16:17:02 +0100 Subject: [PATCH 162/253] Ruff: imu_dead_reckoning.py --- .../pointing_model/imu_dead_reckoning.py | 89 +++++++++---------- 1 file changed, 44 insertions(+), 45 deletions(-) diff --git a/python/PiFinder/pointing_model/imu_dead_reckoning.py b/python/PiFinder/pointing_model/imu_dead_reckoning.py index 32595b8a3..6801f8a57 100644 --- a/python/PiFinder/pointing_model/imu_dead_reckoning.py +++ b/python/PiFinder/pointing_model/imu_dead_reckoning.py @@ -6,25 +6,24 @@ NOTE: All angles are in radians. """ -from typing import Union # When updated to Python 3.10+, remove and use new type hints + import numpy as np import quaternion -from PiFinder.pointing_model.astro_coords import RaDecRoll import PiFinder.pointing_model.quaternion_transforms as qt -class ImuDeadReckoning(): +class ImuDeadReckoning: """ Use the plate-solved coordinates and IMU measurements to estimate the pointing using plate solving when available or dead-reckoning using the IMU - when plate solving isn't available (e.g. when the scope is moving or + when plate solving isn't available (e.g. when the scope is moving or between frames). - - For an explanation of the theory and conventions used, see + + For an explanation of the theory and conventions used, see PiFinder/pointing_model/README.md. - This class uses the Equatorial frame as the reference and expects + This class uses the Equatorial frame as the reference and expects plate-solved coordinates in (ra, dec). All angles are in radians. None is not allowed as inputs (use np.nan). @@ -33,13 +32,14 @@ class ImuDeadReckoning(): # Set up: imu_dead_reckoning = ImuDeadReckoning('flat') imu_dead_reckoning.set_alignment(q_scope2cam) - + # Update with plate solved and IMU data: imu_dead_reckoning.update_plate_solve_and_imu(solved_cam_ra, solved_cam_dec, solved_cam_roll, q_x2imu) - + # Dead-reckoning using IMU imu_dead_reckoning.update_imu(q_x2imu) """ + # Alignment: q_scope2cam: np.quaternion # TODO: Do we need this?? q_cam2scope: np.quaternion @@ -53,23 +53,21 @@ class ImuDeadReckoning(): # These get updated by plate solving and IMU dead-reckoning. q_eq2cam: np.quaternion - # True when q_eq2cam is estimated by IMU dead-reckoning. + # True when q_eq2cam is estimated by IMU dead-reckoning. # False when set by plate solving - dead_reckoning: bool = False + dead_reckoning: bool = False tracking: bool = False # True when previous plate solve exists and tracking - # The IMU's unkonwn drifting reference frame X. This is solved for + # The IMU's unkonwn drifting reference frame X. This is solved for # every time we have a simultaneous plate solve and IMU measurement. q_eq2x: np.quaternion = np.quaternion(np.nan) # nan means not set - - def __init__(self, screen_direction:str): + def __init__(self, screen_direction: str): """ """ # IMU-to-camera orientation. Fixed by PiFinder type self._set_screen_direction(screen_direction) - - def set_alignment(self, - q_scope2cam: np.quaternion): + + def set_alignment(self, q_scope2cam: np.quaternion): """ Set the alignment between the PiFinder camera center and the scope pointing. @@ -84,32 +82,34 @@ def set_alignment(self, self.q_cam2scope = self.q_scope2cam.conj() self.q_imu2scope = self.q_imu2cam * self.q_cam2scope - def update_plate_solve_and_imu(self, solved_cam_ra: float, - solved_cam_dec: float, - solved_cam_roll: float, - q_x2imu: np.quaternion): - """ + def update_plate_solve_and_imu( + self, + solved_cam_ra: float, + solved_cam_dec: float, + solved_cam_roll: float, + q_x2imu: np.quaternion, + ): + """ Update the state with the az/alt measurements from plate solving in the - camera frame. If the IMU measurement (which should be taken at the same + camera frame. If the IMU measurement (which should be taken at the same time) is available, q_x2imu (the unknown drifting reference frame) will - be solved for. + be solved for. INPUTS: TODO: Update these solved_cam_az: [rad] Azimuth of the camera pointing from plate solving. solved_cam_alt: [rad] Alt of the camera pointing from plate solving. solved_cam_roll_offset: [rad] Roll offset of the camera frame +y ("up") relative to the pole. - q_x2imu: [quaternion] Raw IMU measurement quaternions. This is the IMU + q_x2imu: [quaternion] Raw IMU measurement quaternions. This is the IMU frame orientation wrt unknown drifting reference frame X. """ if np.isnan(solved_cam_ra) or np.isnan(solved_cam_dec): return # No update - + # Update plate-solved coord: Camera frame relative to the Equatorial # frame where the +y camera frame (i.e. "up") points to the North # Celestial Pole (NCP) -- i.e. zero roll offset: - self.q_eq2cam = qt.get_q_eq2cam(solved_cam_ra, solved_cam_dec, - solved_cam_roll) + self.q_eq2cam = qt.get_q_eq2cam(solved_cam_ra, solved_cam_dec, solved_cam_roll) self.dead_reckoning = False # Update IMU: Calculate the IMU's unknown reference frame X using the @@ -121,8 +121,7 @@ def update_plate_solve_and_imu(self, solved_cam_ra: float, self.q_eq2x = self.q_eq2x.normalized() self.tracking = True # We have a plate solve and IMU measurement - def update_imu(self, - q_x2imu: np.quaternion): + def update_imu(self, q_x2imu: np.quaternion): """ Update the state with the raw IMU measurement. Does a dead-reckoning estimate of the camera and scope pointing. @@ -132,7 +131,7 @@ def update_imu(self, reference frame X used by the IMU. """ if not np.isnan(self.q_eq2x): - # Dead reckoning estimate by IMU if q_hor2x has been estimated by a + # Dead reckoning estimate by IMU if q_hor2x has been estimated by a # previous plate solve. self.q_eq2cam = self.q_eq2x * q_x2imu * self.q_imu2cam self.q_eq2cam = self.q_eq2cam.normalized() @@ -143,7 +142,7 @@ def update_imu(self, self.dead_reckoning = True def get_cam_radec(self) -> tuple[float, float, float, bool]: - """ + """ Returns the (ra, dec, roll) of the camera and a Boolean dead_reckoning to indicate if the estimate is from dead-reckoning (True) or from plate solving (False). @@ -152,7 +151,7 @@ def get_cam_radec(self) -> tuple[float, float, float, bool]: return ra, dec, roll # Angles are in radians def get_scope_radec(self) -> tuple[float, float, float, bool]: - """ + """ Returns the (ra, dec, roll) of the scope and a Boolean dead_reckoning to indicate if the estimate is from dead-reckoning (True) or from plate solving (False). @@ -190,36 +189,36 @@ def get_screen_direction_q_imu2cam(screen_direction: str) -> np.quaternion: if screen_direction == "left": # Left: # Rotate 90° around x_imu so that z_imu' points along z_camera - q1 = qt.axis_angle2quat([1, 0, 0], np.pi / 2) + q1 = qt.axis_angle2quat([1, 0, 0], np.pi / 2) # Rotate 90° around z_imu' to align with the camera cooridnates q2 = qt.axis_angle2quat([0, 0, 1], np.pi / 2) - q_imu2cam = (q1 * q2).normalized() + q_imu2cam = (q1 * q2).normalized() elif screen_direction == "right": # Right: # Rotate -90° around y_imu so that z_imu' points along z_camera - q1 = qt.axis_angle2quat([0, 1, 0], np.pi / 2) + q1 = qt.axis_angle2quat([0, 1, 0], np.pi / 2) # Rotate 90° around z_imu' to align with the camera cooridnates q2 = qt.axis_angle2quat([0, 0, 1], -np.pi / 2) - q_imu2cam = (q1 * q2).normalized() + q_imu2cam = (q1 * q2).normalized() elif screen_direction == "straight": - # Straight: + # Straight: # Rotate 180° around y_imu so that z_imu' points along z_camera - q1 = qt.axis_angle2quat([0, 1, 0], np.pi / 2) + q1 = qt.axis_angle2quat([0, 1, 0], np.pi / 2) # Rotate -90° around z_imu' to align with the camera cooridnates q2 = qt.axis_angle2quat([0, 0, 1], -np.pi / 2) - q_imu2cam = (q1 * q2).normalized() + q_imu2cam = (q1 * q2).normalized() elif screen_direction == "flat3": # Flat v3: # Camera is tilted a further 30° compared to Flat v2 # Rotate -120° around y_imu so that z_imu' points along z_camera - q1 = qt.axis_angle2quat([0, 1, 0], -np.pi * 2 / 3) + q1 = qt.axis_angle2quat([0, 1, 0], -np.pi * 2 / 3) # Rotate -90° around z_imu' to align with the camera cooridnates q2 = qt.axis_angle2quat([0, 0, 1], -np.pi / 2) q_imu2cam = (q1 * q2).normalized() elif screen_direction == "flat": # Flat v2: # Rotate -90° around y_imu so that z_imu' points along z_camera - q1 = qt.axis_angle2quat([0, 1, 0], -np.pi / 2) + q1 = qt.axis_angle2quat([0, 1, 0], -np.pi / 2) # Rotate -90° around z_imu' to align with the camera cooridnates q2 = qt.axis_angle2quat([0, 0, 1], -np.pi / 2) q_imu2cam = (q1 * q2).normalized() @@ -230,8 +229,8 @@ def get_screen_direction_q_imu2cam(screen_direction: str) -> np.quaternion: # Rotate +90° around z_imu to align with the camera cooridnates # (+y_cam is along -x_imu) q2 = qt.axis_angle2quat([0, 0, 1], +np.pi / 2) - q_imu2cam = (q1 * q2).normalized() + q_imu2cam = (q1 * q2).normalized() else: - raise ValueError(f'Unsupported screen_direction: {screen_direction}') - + raise ValueError(f"Unsupported screen_direction: {screen_direction}") + return q_imu2cam From 684228ab1e94c320c91cc8a588f4790d0120c11b Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Wed, 20 Aug 2025 16:18:00 +0100 Subject: [PATCH 163/253] Ruff: quaternion_transforms.py --- .../pointing_model/quaternion_transforms.py | 52 +++++++++++-------- 1 file changed, 30 insertions(+), 22 deletions(-) diff --git a/python/PiFinder/pointing_model/quaternion_transforms.py b/python/PiFinder/pointing_model/quaternion_transforms.py index 85822841c..527394697 100644 --- a/python/PiFinder/pointing_model/quaternion_transforms.py +++ b/python/PiFinder/pointing_model/quaternion_transforms.py @@ -9,25 +9,24 @@ q_a2c = q_a2b * q_a2c -NOTE: +NOTE: * All angles are in radians. * The quaternions use numpy quaternions and are scalar-first. -* Some of the constant quaternion terms can be speeded up by not using +* Some of the constant quaternion terms can be speeded up by not using trigonometric functions. -* The methods do not normalize the quaternions because this incurs a small -computational overhead. Normalization should be done manually as and when +* The methods do not normalize the quaternions because this incurs a small +computational overhead. Normalization should be done manually as and when necessary. """ -from typing import Union # When updated to Python 3.10+, remove and use new type hints import numpy as np import quaternion from PiFinder.pointing_model.astro_coords import RaDecRoll -def axis_angle2quat(axis, theta:float) -> np.quaternion: +def axis_angle2quat(axis, theta: float) -> np.quaternion: """ Convert from axis-angle representation to a quaternion @@ -35,46 +34,51 @@ def axis_angle2quat(axis, theta:float) -> np.quaternion: axis: (3,) Axis of rotation (doesn't need to be a unit vector) angle: Angle of rotation [rad] """ - assert len(axis) == 3, 'axis should be a list or numpy array of length 3.' + assert len(axis) == 3, "axis should be a list or numpy array of length 3." # Define the vector part of the quaternion v = np.array(axis) / np.linalg.norm(axis) * np.sin(theta / 2) return np.quaternion(np.cos(theta / 2), v[0], v[1], v[2]) -def get_quat_angular_diff(q1:np.quaternion, q2:np.quaternion) -> float: +def get_quat_angular_diff(q1: np.quaternion, q2: np.quaternion) -> float: """ Calculates the relative rotation between quaternions `q1` and `q2`. Accounts for the double-cover property of quaternions so that if q1 and q2 are close, you get small angle d_theta rather than something around 2 * np.pi. """ dq = q1.conj() * q2 - d_theta = 2 * np.arctan2(np.linalg.norm(dq.vec), dq.w) # atan2 is more robust than using acos + d_theta = 2 * np.arctan2( + np.linalg.norm(dq.vec), dq.w + ) # atan2 is more robust than using acos # Account for double cover where q2 = -q1 gives d_theta = 2 * pi if d_theta > np.pi: d_theta = 2 * np.pi - d_theta - + return d_theta # In radians # ========== Equatorial frame functions ============================ -def get_q_eq2cam(ra_rad:float, dec_rad:float, roll_rad:float) -> np.quaternion: # TODO: Rename to q_eq2frame? - """ - Express the coordinates of a camera pointing at RA, Dec, Roll (in radians) + +def get_q_eq2cam( + ra_rad: float, dec_rad: float, roll_rad: float +) -> np.quaternion: # TODO: Rename to q_eq2frame? + """ + Express the coordinates of a camera pointing at RA, Dec, Roll (in radians) in the relative to the Equatorial frame. """ # Intrinsic rotation of q_ra followed by q_dec gives a quaternion rotation # that points +z towards the boresight of the camera. +y to the left and - # +x down. + # +x down. q_ra = axis_angle2quat([0, 0, 1], ra_rad) # Rotate frame around z (NCP) q_dec = axis_angle2quat([0, 1, 0], np.pi / 2 - dec_rad) # Rotate around y' - # Need to rotate this +90 degrees around z_cam so that +y_cam points up + # Need to rotate this +90 degrees around z_cam so that +y_cam points up # and +x_cam points to the left of the Camera frame. In addition, need to # account for the roll offset of the camera (zero if +y_cam points up along - # the great circle towards the NCP) + # the great circle towards the NCP) q_roll = axis_angle2quat([0, 0, 1], np.pi / 2 + roll_rad) # Intrinsic rotation: @@ -82,22 +86,24 @@ def get_q_eq2cam(ra_rad:float, dec_rad:float, roll_rad:float) -> np.quaternion: return q_eq2cam -def get_radec_of_q_eq(q_eq2frame:np.quaternion) -> tuple[float, float, float]: +def get_radec_of_q_eq(q_eq2frame: np.quaternion) -> tuple[float, float, float]: """ Returns the (ra, dec, roll) angles of the quaterion rotation relative to - the equatorial frame. + the equatorial frame. """ # Pure quaternion along camera boresight - pz_frame = q_eq2frame * np.quaternion(0, 0, 0, 1) * q_eq2frame.conj() + pz_frame = q_eq2frame * np.quaternion(0, 0, 0, 1) * q_eq2frame.conj() # Calculate RA, Dec from the camera boresight: dec = np.arcsin(pz_frame.z) ra = np.arctan2(pz_frame.y, pz_frame.x) # Pure quaternion along y_cam which points to NCP when roll = 0 - py_cam = q_eq2frame * np.quaternion(0, 0, 1, 0) * q_eq2frame.conj() + py_cam = q_eq2frame * np.quaternion(0, 0, 1, 0) * q_eq2frame.conj() # Local East and North vectors (roll is the angle between py_cam and the north vector) vec_east = np.array([-np.sin(ra), np.cos(ra), 0]) - vec_north = np.array([-np.sin(dec) * np.cos(ra), -np.sin(dec) * np.sin(ra), np.cos(dec)]) + vec_north = np.array( + [-np.sin(dec) * np.cos(ra), -np.sin(dec) * np.sin(ra), np.cos(dec)] + ) roll = -np.arctan2(np.dot(py_cam.vec, vec_east), np.dot(py_cam.vec, vec_north)) return ra, dec, roll # In radians @@ -109,7 +115,9 @@ def get_q_scope2cam(target_eq: RaDecRoll, cam_eq: RaDecRoll) -> np.quaternion: TODO: Update? """ q_eq2cam = get_q_eq2cam(cam_eq.ra, cam_eq.dec, cam_eq.roll) - q_eq2scope = get_q_eq2cam(target_eq.ra, target_eq.dec, target_eq.roll) # This assumes an EQ mount - We don't know the roll of the scope frame + q_eq2scope = get_q_eq2cam( + target_eq.ra, target_eq.dec, target_eq.roll + ) # This assumes an EQ mount - We don't know the roll of the scope frame q_scope2cam = q_eq2scope.conj() * q_eq2cam NotImplementedError # Needs more workk From b8e0a955a608a85b9a20b3bb3335eb7d2e28c3f1 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Wed, 20 Aug 2025 16:25:34 +0100 Subject: [PATCH 164/253] Move pip numpy-quaternion from requirements_dev.txt to requirements.txt --- python/requirements.txt | 1 + python/requirements_dev.txt | 1 - 2 files changed, 1 insertion(+), 1 deletion(-) diff --git a/python/requirements.txt b/python/requirements.txt index 5f92091ab..62023dfe9 100644 --- a/python/requirements.txt +++ b/python/requirements.txt @@ -10,6 +10,7 @@ luma.oled==3.12.0 luma.lcd==2.11.0 pillow==10.4.0 numpy==1.26.2 +numpy-quaternion=2023.0.4 pandas==1.5.3 pydeepskylog==1.3.2 pyjwt==2.8.0 diff --git a/python/requirements_dev.txt b/python/requirements_dev.txt index c3ab3e871..6bb063416 100644 --- a/python/requirements_dev.txt +++ b/python/requirements_dev.txt @@ -9,4 +9,3 @@ pygame==2.6.0 pre-commit==3.7.1 Babel==2.16.0 xlrd==2.0.2 -numpy-quaternion # For testing IMU (TODO: move to requirements.txt) From 9d8e7566934e36897a6f97749d68bcc86ebcbcfe Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Wed, 20 Aug 2025 16:31:53 +0100 Subject: [PATCH 165/253] Fix screen_direction calculation bug for as_dream --- python/PiFinder/pointing_model/imu_dead_reckoning.py | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/python/PiFinder/pointing_model/imu_dead_reckoning.py b/python/PiFinder/pointing_model/imu_dead_reckoning.py index 6801f8a57..df4d71cb1 100644 --- a/python/PiFinder/pointing_model/imu_dead_reckoning.py +++ b/python/PiFinder/pointing_model/imu_dead_reckoning.py @@ -228,8 +228,7 @@ def get_screen_direction_q_imu2cam(screen_direction: str) -> np.quaternion: # NOTE: Need to check if the orientation of the camera is correct # Rotate +90° around z_imu to align with the camera cooridnates # (+y_cam is along -x_imu) - q2 = qt.axis_angle2quat([0, 0, 1], +np.pi / 2) - q_imu2cam = (q1 * q2).normalized() + q_imu2cam = qt.axis_angle2quat([0, 0, 1], +np.pi / 2) else: raise ValueError(f"Unsupported screen_direction: {screen_direction}") From bea3d506dd2003fe0334c1d9d551cd2761e22c98 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Wed, 20 Aug 2025 16:33:48 +0100 Subject: [PATCH 166/253] Convert np.quaternion --> quaternion.quaternion to be compatible with Ruff --- python/PiFinder/integrator.py | 24 ++++++++++--------- .../pointing_model/imu_dead_reckoning.py | 22 ++++++++--------- .../pointing_model/quaternion_transforms.py | 16 ++++++------- 3 files changed, 32 insertions(+), 30 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index b4a879efb..8fc329b66 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -27,9 +27,8 @@ logger = logging.getLogger("IMU.Integrator") # Constants: -IMU_MOVED_ANG_THRESHOLD = np.deg2rad( - 0.1 -) # Use IMU tracking if the angle moved is above this +# Use IMU tracking if the angle moved is above this +IMU_MOVED_ANG_THRESHOLD = np.deg2rad(0.1) def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=False): @@ -41,9 +40,8 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa logger.debug("Starting Integrator") try: - solved = ( - get_initialized_solved_dict() - ) # Dict of RA, Dec, etc. initialized to None. + # Dict of RA, Dec, etc. initialized to None: + solved = (get_initialized_solved_dict()) cfg = config.Config() mount_type = cfg.get_option("mount_type") @@ -138,7 +136,7 @@ def update_plate_solve_and_imu(imu_dead_reckoning: ImuDeadReckoning, solved: dic # Successfully plate solved & camera pointing exists if solved["imu_quat"] is None: # TODO: This Do not run the rest of the code? - q_x2imu = np.quaternion(np.nan) + q_x2imu = quaternion.quaternion(np.nan) else: q_x2imu = solved["imu_quat"] # IMU measurement at the time of plate solving @@ -184,7 +182,7 @@ def update_imu( imu_dead_reckoning: ImuDeadReckoning, solved: dict, last_image_solve: dict, - imu: np.quaternion, + imu: quaternion.quaternion, ): """ Updates the solved dictionary using IMU dead-reckoning from the last @@ -194,8 +192,8 @@ def update_imu( return # Need all of these to do IMU dead-reckoning assert isinstance( - imu["quat"], np.quaternion - ), "Expecting np.quaternion type" # TODO: Can be removed later + imu["quat"], quaternion.quaternion + ), "Expecting quaternion.quaternion type" # TODO: Can be removed later # When moving, switch to tracking using the IMU angle_moved = qt.get_quat_angular_diff(last_image_solve["imu_quat"], imu["quat"]) @@ -235,7 +233,11 @@ def update_imu( def get_roll_by_mount_type( - ra_deg: float, dec_deg: float, location, dt: datetime.datetime, mount_type: str + ra_deg: float, + dec_deg: float, + location, + dt: datetime.datetime, + mount_type: str ) -> float: """ Returns the roll (in degrees) depending on the mount type so that the chart diff --git a/python/PiFinder/pointing_model/imu_dead_reckoning.py b/python/PiFinder/pointing_model/imu_dead_reckoning.py index df4d71cb1..b3725d22f 100644 --- a/python/PiFinder/pointing_model/imu_dead_reckoning.py +++ b/python/PiFinder/pointing_model/imu_dead_reckoning.py @@ -41,17 +41,17 @@ class ImuDeadReckoning: """ # Alignment: - q_scope2cam: np.quaternion # TODO: Do we need this?? - q_cam2scope: np.quaternion + q_scope2cam: quaternion.quaternion # TODO: Do we need this?? + q_cam2scope: quaternion.quaternion # IMU orientation: - q_imu2cam: np.quaternion - q_cam2imu: np.quaternion + q_imu2cam: quaternion.quaternion + q_cam2imu: quaternion.quaternion # Putting them together: - q_imu2scope: np.quaternion + q_imu2scope: quaternion.quaternion # The poinging of the camera and scope frames wrt the Equatorial frame. # These get updated by plate solving and IMU dead-reckoning. - q_eq2cam: np.quaternion + q_eq2cam: quaternion.quaternion # True when q_eq2cam is estimated by IMU dead-reckoning. # False when set by plate solving @@ -60,14 +60,14 @@ class ImuDeadReckoning: # The IMU's unkonwn drifting reference frame X. This is solved for # every time we have a simultaneous plate solve and IMU measurement. - q_eq2x: np.quaternion = np.quaternion(np.nan) # nan means not set + q_eq2x: quaternion.quaternion = quaternion.quaternion(np.nan) # nan means not set def __init__(self, screen_direction: str): """ """ # IMU-to-camera orientation. Fixed by PiFinder type self._set_screen_direction(screen_direction) - def set_alignment(self, q_scope2cam: np.quaternion): + def set_alignment(self, q_scope2cam: quaternion.quaternion): """ Set the alignment between the PiFinder camera center and the scope pointing. @@ -87,7 +87,7 @@ def update_plate_solve_and_imu( solved_cam_ra: float, solved_cam_dec: float, solved_cam_roll: float, - q_x2imu: np.quaternion, + q_x2imu: quaternion.quaternion, ): """ Update the state with the az/alt measurements from plate solving in the @@ -121,7 +121,7 @@ def update_plate_solve_and_imu( self.q_eq2x = self.q_eq2x.normalized() self.tracking = True # We have a plate solve and IMU measurement - def update_imu(self, q_x2imu: np.quaternion): + def update_imu(self, q_x2imu: quaternion.quaternion): """ Update the state with the raw IMU measurement. Does a dead-reckoning estimate of the camera and scope pointing. @@ -175,7 +175,7 @@ def _set_screen_direction(self, screen_direction: str): self.q_cam2imu = self.q_imu2cam.conj() -def get_screen_direction_q_imu2cam(screen_direction: str) -> np.quaternion: +def get_screen_direction_q_imu2cam(screen_direction: str) -> quaternion.quaternion: """ Returns the quaternion that rotates the IMU frame to the camera frame based on the screen direction. diff --git a/python/PiFinder/pointing_model/quaternion_transforms.py b/python/PiFinder/pointing_model/quaternion_transforms.py index 527394697..b476ed8c3 100644 --- a/python/PiFinder/pointing_model/quaternion_transforms.py +++ b/python/PiFinder/pointing_model/quaternion_transforms.py @@ -26,7 +26,7 @@ from PiFinder.pointing_model.astro_coords import RaDecRoll -def axis_angle2quat(axis, theta: float) -> np.quaternion: +def axis_angle2quat(axis, theta: float) -> quaternion.quaternion: """ Convert from axis-angle representation to a quaternion @@ -38,10 +38,10 @@ def axis_angle2quat(axis, theta: float) -> np.quaternion: # Define the vector part of the quaternion v = np.array(axis) / np.linalg.norm(axis) * np.sin(theta / 2) - return np.quaternion(np.cos(theta / 2), v[0], v[1], v[2]) + return quaternion.quaternion(np.cos(theta / 2), v[0], v[1], v[2]) -def get_quat_angular_diff(q1: np.quaternion, q2: np.quaternion) -> float: +def get_quat_angular_diff(q1: quaternion.quaternion, q2: quaternion.quaternion) -> float: """ Calculates the relative rotation between quaternions `q1` and `q2`. Accounts for the double-cover property of quaternions so that if q1 and q2 @@ -64,7 +64,7 @@ def get_quat_angular_diff(q1: np.quaternion, q2: np.quaternion) -> float: def get_q_eq2cam( ra_rad: float, dec_rad: float, roll_rad: float -) -> np.quaternion: # TODO: Rename to q_eq2frame? +) -> quaternion.quaternion: # TODO: Rename to q_eq2frame? """ Express the coordinates of a camera pointing at RA, Dec, Roll (in radians) in the relative to the Equatorial frame. @@ -86,19 +86,19 @@ def get_q_eq2cam( return q_eq2cam -def get_radec_of_q_eq(q_eq2frame: np.quaternion) -> tuple[float, float, float]: +def get_radec_of_q_eq(q_eq2frame: quaternion.quaternion) -> tuple[float, float, float]: """ Returns the (ra, dec, roll) angles of the quaterion rotation relative to the equatorial frame. """ # Pure quaternion along camera boresight - pz_frame = q_eq2frame * np.quaternion(0, 0, 0, 1) * q_eq2frame.conj() + pz_frame = q_eq2frame * quaternion.quaternion(0, 0, 0, 1) * q_eq2frame.conj() # Calculate RA, Dec from the camera boresight: dec = np.arcsin(pz_frame.z) ra = np.arctan2(pz_frame.y, pz_frame.x) # Pure quaternion along y_cam which points to NCP when roll = 0 - py_cam = q_eq2frame * np.quaternion(0, 0, 1, 0) * q_eq2frame.conj() + py_cam = q_eq2frame * quaternion.quaternion(0, 0, 1, 0) * q_eq2frame.conj() # Local East and North vectors (roll is the angle between py_cam and the north vector) vec_east = np.array([-np.sin(ra), np.cos(ra), 0]) vec_north = np.array( @@ -109,7 +109,7 @@ def get_radec_of_q_eq(q_eq2frame: np.quaternion) -> tuple[float, float, float]: return ra, dec, roll # In radians -def get_q_scope2cam(target_eq: RaDecRoll, cam_eq: RaDecRoll) -> np.quaternion: +def get_q_scope2cam(target_eq: RaDecRoll, cam_eq: RaDecRoll) -> quaternion.quaternion: """ Returns the quaternion that rotates from the scope frame to the camera frame. TODO: Update? From 355dc106befbf70e039cdeebabe5994ad7549f62 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Wed, 20 Aug 2025 16:37:07 +0100 Subject: [PATCH 167/253] requirements.txt: Fix missing = --- python/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/python/requirements.txt b/python/requirements.txt index 62023dfe9..c4aace437 100644 --- a/python/requirements.txt +++ b/python/requirements.txt @@ -10,7 +10,7 @@ luma.oled==3.12.0 luma.lcd==2.11.0 pillow==10.4.0 numpy==1.26.2 -numpy-quaternion=2023.0.4 +numpy-quaternion==2023.0.4 pandas==1.5.3 pydeepskylog==1.3.2 pyjwt==2.8.0 From 270a29519f69847a8917ec0792dea4e8377591c5 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Wed, 20 Aug 2025 16:40:06 +0100 Subject: [PATCH 168/253] Ruff: imu_pi.py: Remove config that's no longer used because screen_direction isn't set here. --- python/PiFinder/imu_pi.py | 3 --- 1 file changed, 3 deletions(-) diff --git a/python/PiFinder/imu_pi.py b/python/PiFinder/imu_pi.py index 0fef468f1..0e11933f3 100644 --- a/python/PiFinder/imu_pi.py +++ b/python/PiFinder/imu_pi.py @@ -14,8 +14,6 @@ import quaternion # Numpy quaternion from scipy.spatial.transform import Rotation -from PiFinder import config - logger = logging.getLogger("IMU.pi") QUEUE_LEN = 10 @@ -35,7 +33,6 @@ def __init__(self): # IMPLUS mode: Accelerometer + Gyro + Fusion data self.sensor.mode = adafruit_bno055.IMUPLUS_MODE # self.sensor.mode = adafruit_bno055.NDOF_MODE - cfg = config.Config() self.quat_history = [(0, 0, 0, 0)] * QUEUE_LEN self._flip_count = 0 From 0c46ce1a4ca453d3140c7194addb7c0616043171 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Wed, 20 Aug 2025 16:41:15 +0100 Subject: [PATCH 169/253] Ruff --- python/PiFinder/integrator.py | 10 +++------- .../PiFinder/pointing_model/quaternion_transforms.py | 5 ++++- python/PiFinder/ui/status.py | 2 +- 3 files changed, 8 insertions(+), 9 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 8fc329b66..709788233 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -28,7 +28,7 @@ # Constants: # Use IMU tracking if the angle moved is above this -IMU_MOVED_ANG_THRESHOLD = np.deg2rad(0.1) +IMU_MOVED_ANG_THRESHOLD = np.deg2rad(0.1) def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=False): @@ -41,7 +41,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa try: # Dict of RA, Dec, etc. initialized to None: - solved = (get_initialized_solved_dict()) + solved = get_initialized_solved_dict() cfg = config.Config() mount_type = cfg.get_option("mount_type") @@ -233,11 +233,7 @@ def update_imu( def get_roll_by_mount_type( - ra_deg: float, - dec_deg: float, - location, - dt: datetime.datetime, - mount_type: str + ra_deg: float, dec_deg: float, location, dt: datetime.datetime, mount_type: str ) -> float: """ Returns the roll (in degrees) depending on the mount type so that the chart diff --git a/python/PiFinder/pointing_model/quaternion_transforms.py b/python/PiFinder/pointing_model/quaternion_transforms.py index b476ed8c3..9f0d430df 100644 --- a/python/PiFinder/pointing_model/quaternion_transforms.py +++ b/python/PiFinder/pointing_model/quaternion_transforms.py @@ -41,7 +41,10 @@ def axis_angle2quat(axis, theta: float) -> quaternion.quaternion: return quaternion.quaternion(np.cos(theta / 2), v[0], v[1], v[2]) -def get_quat_angular_diff(q1: quaternion.quaternion, q2: quaternion.quaternion) -> float: +def get_quat_angular_diff( + q1: quaternion.quaternion, + q2: quaternion.quaternion +) -> float: """ Calculates the relative rotation between quaternions `q1` and `q2`. Accounts for the double-cover property of quaternions so that if q1 and q2 diff --git a/python/PiFinder/ui/status.py b/python/PiFinder/ui/status.py index 0dde8bcab..836bbeaae 100644 --- a/python/PiFinder/ui/status.py +++ b/python/PiFinder/ui/status.py @@ -265,7 +265,7 @@ def update_status_dict(self): self.status_dict["IMU"] = f"{mtext : >11}" + " " + str(imu["status"]) self.status_dict["IMU PS"] = ( "imu NA" - #f"{imu['quat'][0] : >6.1f}/{imu['quat'][2] : >6.1f}" # TODO: Quick hack for now. This was changed from imu["pos"] and should be changed. + # f"{imu['quat'][0] : >6.1f}/{imu['quat'][2] : >6.1f}" # TODO: Quick hack for now. This was changed from imu["pos"] and should be changed. ) location = self.shared_state.location() sats = self.shared_state.sats() From 8be03fdb3a4d5e3f15daecc277bfdead07906877 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Wed, 20 Aug 2025 19:47:04 +0200 Subject: [PATCH 170/253] Fix type hints --- python/PiFinder/pointing_model/imu_dead_reckoning.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/python/PiFinder/pointing_model/imu_dead_reckoning.py b/python/PiFinder/pointing_model/imu_dead_reckoning.py index b3725d22f..a1d8e7188 100644 --- a/python/PiFinder/pointing_model/imu_dead_reckoning.py +++ b/python/PiFinder/pointing_model/imu_dead_reckoning.py @@ -141,7 +141,7 @@ def update_imu(self, q_x2imu: quaternion.quaternion): self.dead_reckoning = True - def get_cam_radec(self) -> tuple[float, float, float, bool]: + def get_cam_radec(self) -> tuple[float, float, float]: """ Returns the (ra, dec, roll) of the camera and a Boolean dead_reckoning to indicate if the estimate is from dead-reckoning (True) or from plate @@ -150,7 +150,7 @@ def get_cam_radec(self) -> tuple[float, float, float, bool]: ra, dec, roll = qt.get_radec_of_q_eq(self.q_eq2cam) return ra, dec, roll # Angles are in radians - def get_scope_radec(self) -> tuple[float, float, float, bool]: + def get_scope_radec(self) -> tuple[float, float, float]: """ Returns the (ra, dec, roll) of the scope and a Boolean dead_reckoning to indicate if the estimate is from dead-reckoning (True) or from plate From 92b898d6c99d9fb1407f60696c6d3a3d1c19de18 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Sat, 23 Aug 2025 17:30:18 +0200 Subject: [PATCH 171/253] Lint --- python/PiFinder/integrator.py | 6 +++++- python/PiFinder/pointing_model/astro_coords.py | 6 ++++-- 2 files changed, 9 insertions(+), 3 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 709788233..9542b8593 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -233,7 +233,11 @@ def update_imu( def get_roll_by_mount_type( - ra_deg: float, dec_deg: float, location, dt: datetime.datetime, mount_type: str + ra_deg: float, + dec_deg: float, + location, + dt: datetime.datetime, + mount_type: str ) -> float: """ Returns the roll (in degrees) depending on the mount type so that the chart diff --git a/python/PiFinder/pointing_model/astro_coords.py b/python/PiFinder/pointing_model/astro_coords.py index b318f708a..ac35e70ec 100644 --- a/python/PiFinder/pointing_model/astro_coords.py +++ b/python/PiFinder/pointing_model/astro_coords.py @@ -20,13 +20,15 @@ class RaDecRoll: NOTE: All angles are in radians. """ - ra: float = np.nan dec: float = np.nan roll: float = np.nan def set( - self, ra: Union[float, None], dec: Union[float, None], roll: Union[float, None] + self, + ra: Union[float, None], + dec: Union[float, None], + roll: Union[float, None] ): """ """ self.ra = ra if ra is not None else np.nan From 001da0580d1a6e82fe50f66c5ea37b566031a26c Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Tue, 26 Aug 2025 20:36:43 +0200 Subject: [PATCH 172/253] RaDecRoll: Add .initialize() method --- .../PiFinder/pointing_model/astro_coords.py | 50 ++++++++++++++----- 1 file changed, 38 insertions(+), 12 deletions(-) diff --git a/python/PiFinder/pointing_model/astro_coords.py b/python/PiFinder/pointing_model/astro_coords.py index ac35e70ec..ed570bcff 100644 --- a/python/PiFinder/pointing_model/astro_coords.py +++ b/python/PiFinder/pointing_model/astro_coords.py @@ -10,8 +10,9 @@ @dataclass class RaDecRoll: """ - Data class for equatorial coordinates defined by (RA, Dec, Roll). - + Data class for equatorial coordinates defined by (RA, Dec, Roll). This + makes it easier to convert between radians and degrees. + The set methods allow values to be float or None but internally, None will be stored as np.nan so that the type is consistent. the get methods will return None if the value is np.nan. @@ -23,6 +24,14 @@ class RaDecRoll: ra: float = np.nan dec: float = np.nan roll: float = np.nan + is_set = False + + def initialize(self): + """ Initializes to unset state """ + self.ra = np.nan + self.dec = np.nan + self.roll = np.nan + self.is_set = False def set( self, @@ -30,10 +39,11 @@ def set( dec: Union[float, None], roll: Union[float, None] ): - """ """ + """ Set using radians """ self.ra = ra if ra is not None else np.nan self.dec = dec if dec is not None else np.nan self.roll = roll if roll is not None else np.nan + self.is_set = True def set_from_deg( self, @@ -41,24 +51,40 @@ def set_from_deg( dec_deg: Union[float, None], roll_deg: Union[float, None], ): - """ """ + """ Set using degrees """ ra = np.deg2rad(ra_deg) if ra_deg is not None else np.nan dec = np.deg2rad(dec_deg) if dec_deg is not None else np.nan roll = np.deg2rad(roll_deg) if roll_deg is not None else np.nan self.set(ra, dec, roll) - def get(self) -> tuple[Union[float, None], Union[float, None], Union[float, None]]: - """Returns (ra, dec, roll) in radians""" - ra = self.ra if not np.isnan(self.ra) else None - dec = self.dec if not np.isnan(self.dec) else None - roll = self.roll if not np.isnan(self.roll) else None + def get(self, use_none=False) -> tuple[Union[float, None], Union[float, None], Union[float, None]]: + """ + Returns (ra, dec, roll) in radians. If use_none is True, returns None + for any unset (nan) values. + """ + if use_none: + ra = self.ra if not np.isnan(self.ra) else None + dec = self.dec if not np.isnan(self.dec) else None + roll = self.roll if not np.isnan(self.roll) else None + else: + ra, dec, roll = self.ra, self.dec, self.roll return ra, dec, roll - def get_deg(self) -> tuple[float, float, float]: - """ """ - return np.rad2deg(self.ra), np.rad2deg(self.dec), np.rad2deg(self.roll) + def get_deg(self, reurn_none=False) -> tuple[Union[float, None], Union[float, None], Union[float, None]]: + """ + Returns (ra, dec, roll) in degrees. If use_none is True, returns None + for any unset (nan) values. + """ + if reurn_none: + ra = np.rad2deg(self.ra) if not np.isnan(self.ra) else None + dec = np.rad2deg(self.dec) if not np.isnan(self.dec) else None + roll = np.rad2deg(self.roll) if not np.isnan(self.roll) else None + else: + ra, dec, roll = np.rad2deg(self.ra), np.rad2deg(self.dec), np.rad2deg(self.roll) + + return ra, dec, roll def get_initialized_solved_dict() -> dict: From 312d6cdbea5dff59ff6db2903cf43bb5a6fda049 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Tue, 26 Aug 2025 20:55:50 +0200 Subject: [PATCH 173/253] Rename --> .reset() --- python/PiFinder/pointing_model/astro_coords.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/python/PiFinder/pointing_model/astro_coords.py b/python/PiFinder/pointing_model/astro_coords.py index ed570bcff..6303356b3 100644 --- a/python/PiFinder/pointing_model/astro_coords.py +++ b/python/PiFinder/pointing_model/astro_coords.py @@ -26,8 +26,8 @@ class RaDecRoll: roll: float = np.nan is_set = False - def initialize(self): - """ Initializes to unset state """ + def reset(self): + """ Reset to unset state """ self.ra = np.nan self.dec = np.nan self.roll = np.nan @@ -72,12 +72,12 @@ def get(self, use_none=False) -> tuple[Union[float, None], Union[float, None], U return ra, dec, roll - def get_deg(self, reurn_none=False) -> tuple[Union[float, None], Union[float, None], Union[float, None]]: + def get_deg(self, use_none=False) -> tuple[Union[float, None], Union[float, None], Union[float, None]]: """ Returns (ra, dec, roll) in degrees. If use_none is True, returns None for any unset (nan) values. """ - if reurn_none: + if use_none: ra = np.rad2deg(self.ra) if not np.isnan(self.ra) else None dec = np.rad2deg(self.dec) if not np.isnan(self.dec) else None roll = np.rad2deg(self.roll) if not np.isnan(self.roll) else None From d89455c2360f47d8c1031adc8a9a065ef9d22265 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Tue, 26 Aug 2025 22:23:16 +0200 Subject: [PATCH 174/253] RaDecRoll: Add method to set using quaternions --- python/PiFinder/pointing_model/astro_coords.py | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/python/PiFinder/pointing_model/astro_coords.py b/python/PiFinder/pointing_model/astro_coords.py index 6303356b3..15b57341b 100644 --- a/python/PiFinder/pointing_model/astro_coords.py +++ b/python/PiFinder/pointing_model/astro_coords.py @@ -4,8 +4,11 @@ from dataclasses import dataclass import numpy as np +import quaternion from typing import Union # When updated to Python 3.10+, remove and use new type hints +import PiFinder.pointing_model.quaternion_transforms as qt + @dataclass class RaDecRoll: @@ -58,6 +61,11 @@ def set_from_deg( self.set(ra, dec, roll) + def set_from_quaternion(self, q_eq: quaternion.quaternion): + """ Set from a quaternion rotation relative to the Equatorial frame """ + ra, dec, roll = qt.get_radec_of_q_eq(q_eq) + self.set(ra, dec, roll) + def get(self, use_none=False) -> tuple[Union[float, None], Union[float, None], Union[float, None]]: """ Returns (ra, dec, roll) in radians. If use_none is True, returns None From daf4391c6cbd5109bc91af31af4edff9c5b8e04b Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Tue, 26 Aug 2025 22:23:46 +0200 Subject: [PATCH 175/253] Change to using RaDecRoll class for inerfacing --- python/PiFinder/integrator.py | 51 +++++++++---------- .../pointing_model/imu_dead_reckoning.py | 44 ++++++++-------- 2 files changed, 46 insertions(+), 49 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 9542b8593..4aa71d6d1 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -19,7 +19,7 @@ from PiFinder import state_utils import PiFinder.calc_utils as calc_utils from PiFinder.multiproclogging import MultiprocLogging -from PiFinder.pointing_model.astro_coords import get_initialized_solved_dict +from PiFinder.pointing_model.astro_coords import get_initialized_solved_dict, RaDecRoll from PiFinder.pointing_model.imu_dead_reckoning import ImuDeadReckoning import PiFinder.pointing_model.quaternion_transforms as qt @@ -89,6 +89,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa location = shared_state.location() dt = shared_state.datetime() # Set location for roll and altaz calculations. TODO: Is it necessary to set location? + # TODO: Altaz doesn't seem to be required for catalogs when in EQ mode? Could be disabled in future when in EQ mode? calc_utils.sf_utils.set_location( location.lat, location.lon, location.altitude ) @@ -140,15 +141,12 @@ def update_plate_solve_and_imu(imu_dead_reckoning: ImuDeadReckoning, solved: dic else: q_x2imu = solved["imu_quat"] # IMU measurement at the time of plate solving - # Convert to radians: - solved_cam_ra = np.deg2rad(solved["camera_center"]["RA"]) - solved_cam_dec = np.deg2rad(solved["camera_center"]["Dec"]) - solved_cam_roll = np.deg2rad(solved["camera_center"]["Roll"]) - # Update: - imu_dead_reckoning.update_plate_solve_and_imu( - solved_cam_ra, solved_cam_dec, solved_cam_roll, q_x2imu - ) + solved_cam = RaDecRoll() + solved_cam.set_from_deg(solved["camera_center"]["RA"], + solved["camera_center"]["Dec"], + solved["camera_center"]["Roll"]) + imu_dead_reckoning.update_plate_solve_and_imu(solved_cam, q_x2imu) # Set alignment. TODO: Do this once at alignment. Move out of here. set_alignment(imu_dead_reckoning, solved) @@ -159,19 +157,20 @@ def set_alignment(imu_dead_reckoning: ImuDeadReckoning, solved: dict): Set alignment. TODO: Do this once at alignment """ - # Convert to radians: - solved_cam_ra = np.deg2rad(solved["camera_center"]["RA"]) - solved_cam_dec = np.deg2rad(solved["camera_center"]["Dec"]) - solved_cam_roll = np.deg2rad(solved["camera_center"]["Roll"]) - # Convert to radians: - target_ra = np.deg2rad(solved["RA"]) - target_dec = np.deg2rad(solved["Dec"]) + # RA, Dec of camera center:: + solved_cam = RaDecRoll() + solved_cam.set_from_deg(solved["camera_center"]["RA"], + solved["camera_center"]["Dec"], + solved["camera_center"]["Roll"]) + + # RA, Dec of target (where scope is pointing): solved["Roll"] = 0 # TODO: Target roll isn't calculated by Tetra3. Set to zero here - target_roll = np.deg2rad(solved["Roll"]) + solved_scope = RaDecRoll() + solved_scope.set_from_deg(solved["RA"], solved["Dec"], solved["Roll"]) # Calculate q_scope2cam (alignment) - q_eq2cam = qt.get_q_eq2cam(solved_cam_ra, solved_cam_dec, solved_cam_roll) - q_eq2scope = qt.get_q_eq2cam(target_ra, target_dec, target_roll) + q_eq2cam = qt.get_q_eq2cam(solved_cam.ra, solved_cam.dec, solved_cam.roll) + q_eq2scope = qt.get_q_eq2cam(solved_scope.ra, solved_scope.dec, solved_scope.roll) q_scope2cam = q_eq2scope.conjugate() * q_eq2cam # Set alignment in imu_dead_reckoning @@ -210,16 +209,14 @@ def update_imu( imu_dead_reckoning.update_imu(imu["quat"]) # Latest IMU meas # Store current camera pointing estimate: - ra_cam, dec_cam, roll_cam = imu_dead_reckoning.get_cam_radec() - solved["camera_center"]["RA"] = np.rad2deg(ra_cam) - solved["camera_center"]["Dec"] = np.rad2deg(dec_cam) - solved["camera_center"]["Roll"] = np.rad2deg(roll_cam) + cam_eq = imu_dead_reckoning.get_cam_radec() + solved["camera_center"]["RA"], + solved["camera_center"]["Dec"], + solved["camera_center"]["Roll"] = cam_eq.get_deg(use_none=True) # Store the current scope pointing estimate - ra_target, dec_target, roll_target = imu_dead_reckoning.get_scope_radec() - solved["RA"] = np.rad2deg(ra_target) - solved["Dec"] = np.rad2deg(dec_target) - solved["Roll"] = np.rad2deg(roll_target) + target_eq = imu_dead_reckoning.get_scope_radec() + solved["RA"], solved["Dec"], solved["Roll"] = target_eq.get_deg(use_none=True) q_x2imu = imu["quat"] logger.debug( diff --git a/python/PiFinder/pointing_model/imu_dead_reckoning.py b/python/PiFinder/pointing_model/imu_dead_reckoning.py index a1d8e7188..e42642af4 100644 --- a/python/PiFinder/pointing_model/imu_dead_reckoning.py +++ b/python/PiFinder/pointing_model/imu_dead_reckoning.py @@ -10,6 +10,7 @@ import numpy as np import quaternion +from PiFinder.pointing_model.astro_coords import RaDecRoll import PiFinder.pointing_model.quaternion_transforms as qt @@ -56,7 +57,7 @@ class ImuDeadReckoning: # True when q_eq2cam is estimated by IMU dead-reckoning. # False when set by plate solving dead_reckoning: bool = False - tracking: bool = False # True when previous plate solve exists and tracking + tracking: bool = False # True when previous plate solve exists and is tracking # The IMU's unkonwn drifting reference frame X. This is solved for # every time we have a simultaneous plate solve and IMU measurement. @@ -84,9 +85,7 @@ def set_alignment(self, q_scope2cam: quaternion.quaternion): def update_plate_solve_and_imu( self, - solved_cam_ra: float, - solved_cam_dec: float, - solved_cam_roll: float, + solved_cam: RaDecRoll, q_x2imu: quaternion.quaternion, ): """ @@ -95,22 +94,19 @@ def update_plate_solve_and_imu( time) is available, q_x2imu (the unknown drifting reference frame) will be solved for. - INPUTS: TODO: Update these - solved_cam_az: [rad] Azimuth of the camera pointing from plate solving. - solved_cam_alt: [rad] Alt of the camera pointing from plate solving. - solved_cam_roll_offset: [rad] Roll offset of the camera frame +y ("up") - relative to the pole. + INPUTS: + solved_cam: RA/Dec/Roll of the camera pointing from plate solving. q_x2imu: [quaternion] Raw IMU measurement quaternions. This is the IMU frame orientation wrt unknown drifting reference frame X. """ - if np.isnan(solved_cam_ra) or np.isnan(solved_cam_dec): + if not solved_cam.is_set: return # No update # Update plate-solved coord: Camera frame relative to the Equatorial # frame where the +y camera frame (i.e. "up") points to the North # Celestial Pole (NCP) -- i.e. zero roll offset: - self.q_eq2cam = qt.get_q_eq2cam(solved_cam_ra, solved_cam_dec, solved_cam_roll) - self.dead_reckoning = False + self.q_eq2cam = qt.get_q_eq2cam(solved_cam.ra, solved_cam.dec, solved_cam.roll) + self.dead_reckoning = False # Using plate solve, no dead_reckoning # Update IMU: Calculate the IMU's unknown reference frame X using the # plate solved coordinates and IMU measurements taken from the same @@ -141,23 +137,27 @@ def update_imu(self, q_x2imu: quaternion.quaternion): self.dead_reckoning = True - def get_cam_radec(self) -> tuple[float, float, float]: + def get_cam_radec(self) -> RaDecRoll: """ - Returns the (ra, dec, roll) of the camera and a Boolean dead_reckoning - to indicate if the estimate is from dead-reckoning (True) or from plate - solving (False). + Returns the (ra, dec, roll) of the camera centre and a Boolean + dead_reckoning to indicate if the estimate is from dead-reckoning + (True) or from plate solving (False). """ - ra, dec, roll = qt.get_radec_of_q_eq(self.q_eq2cam) - return ra, dec, roll # Angles are in radians + ra_dec_roll = RaDecRoll() + ra_dec_roll.set_from_quaternion(self.q_eq2cam) - def get_scope_radec(self) -> tuple[float, float, float]: + return ra_dec_roll + + def get_scope_radec(self) -> RaDecRoll: """ Returns the (ra, dec, roll) of the scope and a Boolean dead_reckoning to indicate if the estimate is from dead-reckoning (True) or from plate solving (False). """ - ra, dec, roll = qt.get_radec_of_q_eq(self.q_eq2scope) - return ra, dec, roll # Angles are in radians + ra_dec_roll = RaDecRoll() + ra_dec_roll.set_from_quaternion(self.q_eq2scope) + + return ra_dec_roll def reset(self): """ @@ -222,7 +222,7 @@ def get_screen_direction_q_imu2cam(screen_direction: str) -> quaternion.quaterni # Rotate -90° around z_imu' to align with the camera cooridnates q2 = qt.axis_angle2quat([0, 0, 1], -np.pi / 2) q_imu2cam = (q1 * q2).normalized() - elif screen_direction == "as_dream": + elif screen_direction == "as_dream": # TODO: Propose o rename to "back"? # As Dream: # Camera points back up from the screen # NOTE: Need to check if the orientation of the camera is correct From 06c636fe5d09010f78d94cba2bedd2415aacb731 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Tue, 26 Aug 2025 22:24:21 +0200 Subject: [PATCH 176/253] Update comments --- python/PiFinder/pointing_model/quaternion_transforms.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/python/PiFinder/pointing_model/quaternion_transforms.py b/python/PiFinder/pointing_model/quaternion_transforms.py index 9f0d430df..a69942fb8 100644 --- a/python/PiFinder/pointing_model/quaternion_transforms.py +++ b/python/PiFinder/pointing_model/quaternion_transforms.py @@ -64,7 +64,7 @@ def get_quat_angular_diff( # ========== Equatorial frame functions ============================ - +# TODO: Rename to get_q_eq2frame? def get_q_eq2cam( ra_rad: float, dec_rad: float, roll_rad: float ) -> quaternion.quaternion: # TODO: Rename to q_eq2frame? @@ -122,6 +122,6 @@ def get_q_scope2cam(target_eq: RaDecRoll, cam_eq: RaDecRoll) -> quaternion.quate target_eq.ra, target_eq.dec, target_eq.roll ) # This assumes an EQ mount - We don't know the roll of the scope frame q_scope2cam = q_eq2scope.conj() * q_eq2cam - NotImplementedError # Needs more workk + NotImplementedError # TODO: Needs more work return q_scope2cam From 4f7edd69c76ed857d8864c21236f1f295338e9e3 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Tue, 26 Aug 2025 22:31:35 +0200 Subject: [PATCH 177/253] Update README --- python/PiFinder/pointing_model/README.md | 22 ++++++++++++++++------ 1 file changed, 16 insertions(+), 6 deletions(-) diff --git a/python/PiFinder/pointing_model/README.md b/python/PiFinder/pointing_model/README.md index 212d16917..7adfcf123 100644 --- a/python/PiFinder/pointing_model/README.md +++ b/python/PiFinder/pointing_model/README.md @@ -7,18 +7,28 @@ README: IMU support prototyping >Remove this before release! -* Done: Support other PiFinder types -* Use RaDecRoll class -* Type hints for integrator.py -* Lint using Nox -* Done: Adjust Roll depending on mount_type for charts +Issues: +* Doesn't run wih v3 Flat. Issue in main branch? +* Issue in requirements? Can't get it to work in a new env. +* Doesn't pass Nox +* In EQ mode flickers between 0° and 359°. This is also in the main branch. + +TODO: +* Use RaDecRoll class --> Done. Need to test. * Use alignment rather than calculating every loop -* Go through TODOs +* Go through TODOs in code * Discuss requirements.txt with Richard Later: * Update imu_pi.py +Done: +* Support other PiFinder types +* Adjust Roll depending on mount_type for charts +* Lint +* Type hints for integrator.py + + # Sky test log >Remove this before release! From 40b04660ff9eee2ffb1a25c037cb5a2ef3fcf84d Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Tue, 26 Aug 2025 21:45:51 +0100 Subject: [PATCH 178/253] Fix circular import. Desktop test --> OK --- .../pointing_model/quaternion_transforms.py | 14 ++++++-------- 1 file changed, 6 insertions(+), 8 deletions(-) diff --git a/python/PiFinder/pointing_model/quaternion_transforms.py b/python/PiFinder/pointing_model/quaternion_transforms.py index a69942fb8..8690f8734 100644 --- a/python/PiFinder/pointing_model/quaternion_transforms.py +++ b/python/PiFinder/pointing_model/quaternion_transforms.py @@ -23,9 +23,6 @@ import numpy as np import quaternion -from PiFinder.pointing_model.astro_coords import RaDecRoll - - def axis_angle2quat(axis, theta: float) -> quaternion.quaternion: """ Convert from axis-angle representation to a quaternion @@ -111,12 +108,12 @@ def get_radec_of_q_eq(q_eq2frame: quaternion.quaternion) -> tuple[float, float, return ra, dec, roll # In radians - +""" def get_q_scope2cam(target_eq: RaDecRoll, cam_eq: RaDecRoll) -> quaternion.quaternion: - """ - Returns the quaternion that rotates from the scope frame to the camera frame. - TODO: Update? - """ + #Returns the quaternion that rotates from the scope frame to the camera frame. + #TODO: Update? + # TODO: Cannot use RaDecRoll here because it'll cause a circular import + q_eq2cam = get_q_eq2cam(cam_eq.ra, cam_eq.dec, cam_eq.roll) q_eq2scope = get_q_eq2cam( target_eq.ra, target_eq.dec, target_eq.roll @@ -125,3 +122,4 @@ def get_q_scope2cam(target_eq: RaDecRoll, cam_eq: RaDecRoll) -> quaternion.quate NotImplementedError # TODO: Needs more work return q_scope2cam +""" From 90d06200d6e0d2386d775b037cc3c07fd3dda296 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Tue, 26 Aug 2025 21:53:48 +0100 Subject: [PATCH 179/253] Nox format --- python/PiFinder/integrator.py | 26 ++++++------ .../PiFinder/pointing_model/astro_coords.py | 40 +++++++++++-------- .../pointing_model/quaternion_transforms.py | 6 ++- 3 files changed, 40 insertions(+), 32 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 4aa71d6d1..23688772d 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -143,9 +143,11 @@ def update_plate_solve_and_imu(imu_dead_reckoning: ImuDeadReckoning, solved: dic # Update: solved_cam = RaDecRoll() - solved_cam.set_from_deg(solved["camera_center"]["RA"], - solved["camera_center"]["Dec"], - solved["camera_center"]["Roll"]) + solved_cam.set_from_deg( + solved["camera_center"]["RA"], + solved["camera_center"]["Dec"], + solved["camera_center"]["Roll"], + ) imu_dead_reckoning.update_plate_solve_and_imu(solved_cam, q_x2imu) # Set alignment. TODO: Do this once at alignment. Move out of here. @@ -159,9 +161,11 @@ def set_alignment(imu_dead_reckoning: ImuDeadReckoning, solved: dict): """ # RA, Dec of camera center:: solved_cam = RaDecRoll() - solved_cam.set_from_deg(solved["camera_center"]["RA"], - solved["camera_center"]["Dec"], - solved["camera_center"]["Roll"]) + solved_cam.set_from_deg( + solved["camera_center"]["RA"], + solved["camera_center"]["Dec"], + solved["camera_center"]["Roll"], + ) # RA, Dec of target (where scope is pointing): solved["Roll"] = 0 # TODO: Target roll isn't calculated by Tetra3. Set to zero here @@ -210,8 +214,8 @@ def update_imu( # Store current camera pointing estimate: cam_eq = imu_dead_reckoning.get_cam_radec() - solved["camera_center"]["RA"], - solved["camera_center"]["Dec"], + (solved["camera_center"]["RA"],) + (solved["camera_center"]["Dec"],) solved["camera_center"]["Roll"] = cam_eq.get_deg(use_none=True) # Store the current scope pointing estimate @@ -230,11 +234,7 @@ def update_imu( def get_roll_by_mount_type( - ra_deg: float, - dec_deg: float, - location, - dt: datetime.datetime, - mount_type: str + ra_deg: float, dec_deg: float, location, dt: datetime.datetime, mount_type: str ) -> float: """ Returns the roll (in degrees) depending on the mount type so that the chart diff --git a/python/PiFinder/pointing_model/astro_coords.py b/python/PiFinder/pointing_model/astro_coords.py index 15b57341b..515b0f0c7 100644 --- a/python/PiFinder/pointing_model/astro_coords.py +++ b/python/PiFinder/pointing_model/astro_coords.py @@ -15,7 +15,7 @@ class RaDecRoll: """ Data class for equatorial coordinates defined by (RA, Dec, Roll). This makes it easier to convert between radians and degrees. - + The set methods allow values to be float or None but internally, None will be stored as np.nan so that the type is consistent. the get methods will return None if the value is np.nan. @@ -24,25 +24,23 @@ class RaDecRoll: NOTE: All angles are in radians. """ + ra: float = np.nan dec: float = np.nan roll: float = np.nan is_set = False def reset(self): - """ Reset to unset state """ + """Reset to unset state""" self.ra = np.nan self.dec = np.nan self.roll = np.nan - self.is_set = False + self.is_set = False def set( - self, - ra: Union[float, None], - dec: Union[float, None], - roll: Union[float, None] + self, ra: Union[float, None], dec: Union[float, None], roll: Union[float, None] ): - """ Set using radians """ + """Set using radians""" self.ra = ra if ra is not None else np.nan self.dec = dec if dec is not None else np.nan self.roll = roll if roll is not None else np.nan @@ -54,7 +52,7 @@ def set_from_deg( dec_deg: Union[float, None], roll_deg: Union[float, None], ): - """ Set using degrees """ + """Set using degrees""" ra = np.deg2rad(ra_deg) if ra_deg is not None else np.nan dec = np.deg2rad(dec_deg) if dec_deg is not None else np.nan roll = np.deg2rad(roll_deg) if roll_deg is not None else np.nan @@ -62,12 +60,14 @@ def set_from_deg( self.set(ra, dec, roll) def set_from_quaternion(self, q_eq: quaternion.quaternion): - """ Set from a quaternion rotation relative to the Equatorial frame """ + """Set from a quaternion rotation relative to the Equatorial frame""" ra, dec, roll = qt.get_radec_of_q_eq(q_eq) - self.set(ra, dec, roll) + self.set(ra, dec, roll) - def get(self, use_none=False) -> tuple[Union[float, None], Union[float, None], Union[float, None]]: - """ + def get( + self, use_none=False + ) -> tuple[Union[float, None], Union[float, None], Union[float, None]]: + """ Returns (ra, dec, roll) in radians. If use_none is True, returns None for any unset (nan) values. """ @@ -80,8 +80,10 @@ def get(self, use_none=False) -> tuple[Union[float, None], Union[float, None], U return ra, dec, roll - def get_deg(self, use_none=False) -> tuple[Union[float, None], Union[float, None], Union[float, None]]: - """ + def get_deg( + self, use_none=False + ) -> tuple[Union[float, None], Union[float, None], Union[float, None]]: + """ Returns (ra, dec, roll) in degrees. If use_none is True, returns None for any unset (nan) values. """ @@ -89,8 +91,12 @@ def get_deg(self, use_none=False) -> tuple[Union[float, None], Union[float, None ra = np.rad2deg(self.ra) if not np.isnan(self.ra) else None dec = np.rad2deg(self.dec) if not np.isnan(self.dec) else None roll = np.rad2deg(self.roll) if not np.isnan(self.roll) else None - else: - ra, dec, roll = np.rad2deg(self.ra), np.rad2deg(self.dec), np.rad2deg(self.roll) + else: + ra, dec, roll = ( + np.rad2deg(self.ra), + np.rad2deg(self.dec), + np.rad2deg(self.roll), + ) return ra, dec, roll diff --git a/python/PiFinder/pointing_model/quaternion_transforms.py b/python/PiFinder/pointing_model/quaternion_transforms.py index 8690f8734..cf53c32e5 100644 --- a/python/PiFinder/pointing_model/quaternion_transforms.py +++ b/python/PiFinder/pointing_model/quaternion_transforms.py @@ -23,6 +23,7 @@ import numpy as np import quaternion + def axis_angle2quat(axis, theta: float) -> quaternion.quaternion: """ Convert from axis-angle representation to a quaternion @@ -39,8 +40,7 @@ def axis_angle2quat(axis, theta: float) -> quaternion.quaternion: def get_quat_angular_diff( - q1: quaternion.quaternion, - q2: quaternion.quaternion + q1: quaternion.quaternion, q2: quaternion.quaternion ) -> float: """ Calculates the relative rotation between quaternions `q1` and `q2`. @@ -61,6 +61,7 @@ def get_quat_angular_diff( # ========== Equatorial frame functions ============================ + # TODO: Rename to get_q_eq2frame? def get_q_eq2cam( ra_rad: float, dec_rad: float, roll_rad: float @@ -108,6 +109,7 @@ def get_radec_of_q_eq(q_eq2frame: quaternion.quaternion) -> tuple[float, float, return ra, dec, roll # In radians + """ def get_q_scope2cam(target_eq: RaDecRoll, cam_eq: RaDecRoll) -> quaternion.quaternion: #Returns the quaternion that rotates from the scope frame to the camera frame. From 8b4de5406d9882484ac37eb1a58551c6bff45e51 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 31 Aug 2025 20:12:18 +0100 Subject: [PATCH 180/253] Fix issue from linting that was causing align to fail --- python/PiFinder/integrator.py | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 23688772d..e89a3d943 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -214,9 +214,8 @@ def update_imu( # Store current camera pointing estimate: cam_eq = imu_dead_reckoning.get_cam_radec() - (solved["camera_center"]["RA"],) - (solved["camera_center"]["Dec"],) - solved["camera_center"]["Roll"] = cam_eq.get_deg(use_none=True) + (solved["camera_center"]["RA"], solved["camera_center"]["Dec"], + solved["camera_center"]["Roll"]) = cam_eq.get_deg(use_none=True) # Store the current scope pointing estimate target_eq = imu_dead_reckoning.get_scope_radec() From af358e3f94231e1735b19ce551b9508d0e83a86c Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 31 Aug 2025 20:12:53 +0100 Subject: [PATCH 181/253] Refactor. Destop test --> OK (inc. align) --- python/PiFinder/integrator.py | 32 ++++++++++++++++---------------- 1 file changed, 16 insertions(+), 16 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index e89a3d943..1461a0994 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -185,7 +185,7 @@ def update_imu( imu_dead_reckoning: ImuDeadReckoning, solved: dict, last_image_solve: dict, - imu: quaternion.quaternion, + imu: dict, ): """ Updates the solved dictionary using IMU dead-reckoning from the last @@ -197,20 +197,21 @@ def update_imu( assert isinstance( imu["quat"], quaternion.quaternion ), "Expecting quaternion.quaternion type" # TODO: Can be removed later + q_x2imu = imu["quat"] # Current IMU measurement (quaternion) # When moving, switch to tracking using the IMU - angle_moved = qt.get_quat_angular_diff(last_image_solve["imu_quat"], imu["quat"]) + angle_moved = qt.get_quat_angular_diff(last_image_solve["imu_quat"], q_x2imu) if angle_moved > IMU_MOVED_ANG_THRESHOLD: # Estimate camera pointing using IMU dead-reckoning logger.debug( - "Track using IMU. Angle moved since last_image_solve = " - "{:}(> threshold = {:})".format( - np.rad2deg(angle_moved), np.rad2deg(IMU_MOVED_ANG_THRESHOLD) + "Track using IMU: Angle moved since last_image_solve = " + "{:}(> threshold = {:}) | IMU quat = ({:}, {:}, {:}, {:})".format( + np.rad2deg(angle_moved), np.rad2deg(IMU_MOVED_ANG_THRESHOLD), + q_x2imu.w, q_x2imu.x, q_x2imu.y, q_x2imu.z) ) - ) # Dead-reckoning using IMU - imu_dead_reckoning.update_imu(imu["quat"]) # Latest IMU meas + imu_dead_reckoning.update_imu(q_x2imu) # Latest IMU measurement # Store current camera pointing estimate: cam_eq = imu_dead_reckoning.get_cam_radec() @@ -218,19 +219,18 @@ def update_imu( solved["camera_center"]["Roll"]) = cam_eq.get_deg(use_none=True) # Store the current scope pointing estimate - target_eq = imu_dead_reckoning.get_scope_radec() - solved["RA"], solved["Dec"], solved["Roll"] = target_eq.get_deg(use_none=True) - - q_x2imu = imu["quat"] - logger.debug( - " IMU quat = ({:}, {:}, {:}, {:}".format( - q_x2imu.w, q_x2imu.x, q_x2imu.y, q_x2imu.z - ) - ) + scope_eq = imu_dead_reckoning.get_scope_radec() + solved["RA"], solved["Dec"], solved["Roll"] = scope_eq.get_deg(use_none=True) solved["solve_time"] = time.time() solved["solve_source"] = "IMU" + # Logging for states updated in solved: + logger.debug("scope: RA: {:}, Dec: {:}, Roll: {:}".format( + solved["RA"], solved["Dec"], solved["Roll"])) + logger.debug("camera_center: RA: {:}, Dec: {:}, Roll: {:}".format( + solved["camera_center"]["RA"], solved["camera_center"]["Dec"], + solved["camera_center"]["Roll"])) def get_roll_by_mount_type( ra_deg: float, dec_deg: float, location, dt: datetime.datetime, mount_type: str From 60b78ea80c4ae501b69da5fb319f4554c9094584 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 6 Sep 2025 10:38:01 +0100 Subject: [PATCH 182/253] Move functionality from integrator.py to imu_dead_reckoning.py --- python/PiFinder/integrator.py | 12 ++++-------- python/PiFinder/pointing_model/imu_dead_reckoning.py | 10 +++++++++- 2 files changed, 13 insertions(+), 9 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 1461a0994..22f886711 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -172,13 +172,8 @@ def set_alignment(imu_dead_reckoning: ImuDeadReckoning, solved: dict): solved_scope = RaDecRoll() solved_scope.set_from_deg(solved["RA"], solved["Dec"], solved["Roll"]) - # Calculate q_scope2cam (alignment) - q_eq2cam = qt.get_q_eq2cam(solved_cam.ra, solved_cam.dec, solved_cam.roll) - q_eq2scope = qt.get_q_eq2cam(solved_scope.ra, solved_scope.dec, solved_scope.roll) - q_scope2cam = q_eq2scope.conjugate() * q_eq2cam - # Set alignment in imu_dead_reckoning - imu_dead_reckoning.set_alignment(q_scope2cam) + imu_dead_reckoning.set_alignment(solved_cam, solved_scope) def update_imu( @@ -226,12 +221,13 @@ def update_imu( solved["solve_source"] = "IMU" # Logging for states updated in solved: - logger.debug("scope: RA: {:}, Dec: {:}, Roll: {:}".format( + logger.debug("IMU update: scope: RA: {:}, Dec: {:}, Roll: {:}".format( solved["RA"], solved["Dec"], solved["Roll"])) - logger.debug("camera_center: RA: {:}, Dec: {:}, Roll: {:}".format( + logger.debug("IMU update: camera_center: RA: {:}, Dec: {:}, Roll: {:}".format( solved["camera_center"]["RA"], solved["camera_center"]["Dec"], solved["camera_center"]["Roll"])) + def get_roll_by_mount_type( ra_deg: float, dec_deg: float, location, dt: datetime.datetime, mount_type: str ) -> float: diff --git a/python/PiFinder/pointing_model/imu_dead_reckoning.py b/python/PiFinder/pointing_model/imu_dead_reckoning.py index e42642af4..3098fccbb 100644 --- a/python/PiFinder/pointing_model/imu_dead_reckoning.py +++ b/python/PiFinder/pointing_model/imu_dead_reckoning.py @@ -68,7 +68,10 @@ def __init__(self, screen_direction: str): # IMU-to-camera orientation. Fixed by PiFinder type self._set_screen_direction(screen_direction) - def set_alignment(self, q_scope2cam: quaternion.quaternion): + def set_alignment( + self, + solved_cam: RaDecRoll, + solved_scope: RaDecRoll): """ Set the alignment between the PiFinder camera center and the scope pointing. @@ -78,6 +81,11 @@ def set_alignment(self, q_scope2cam: quaternion.quaternion): INPUTS: q_scope2cam: Quaternion that rotates the scope frame to the camera frame. """ + # Calculate q_scope2cam (alignment) + q_eq2cam = qt.get_q_eq2cam(solved_cam.ra, solved_cam.dec, solved_cam.roll) + q_eq2scope = qt.get_q_eq2cam(solved_scope.ra, solved_scope.dec, solved_scope.roll) + q_scope2cam = q_eq2scope.conjugate() * q_eq2cam + # TODO: Use qt.get_q_scope2cam(target_eq, cam_eq) self.q_scope2cam = q_scope2cam.normalized() self.q_cam2scope = self.q_scope2cam.conj() From a79f922af9e33df17eaba0eeecd46cbb3e65941e Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 6 Sep 2025 10:38:19 +0100 Subject: [PATCH 183/253] Add commens. Update README --- python/PiFinder/pointing_model/README.md | 8 +++++++- python/PiFinder/pointing_model/astro_coords.py | 4 ++-- 2 files changed, 9 insertions(+), 3 deletions(-) diff --git a/python/PiFinder/pointing_model/README.md b/python/PiFinder/pointing_model/README.md index 7adfcf123..ee85800d0 100644 --- a/python/PiFinder/pointing_model/README.md +++ b/python/PiFinder/pointing_model/README.md @@ -1,7 +1,7 @@ README: IMU support prototyping =============================== -> This README is temporary during the prototyping phase of the IMU support. +> The first part of this README is temporary for the prototyping phase of the IMU support. # TODO @@ -33,6 +33,12 @@ Done: >Remove this before release! +## 20250831: af358e (tested 5/6 Aug) + +* Tested on altaz mount in altaz mode. +* Seemed ok. Didn't check chart display. +* Changes have mainly been refactoring & linting. + ## 20250819: 700f77c (tested 19/20 Aug) * Tested on altaz mount in altaz & eq mode diff --git a/python/PiFinder/pointing_model/astro_coords.py b/python/PiFinder/pointing_model/astro_coords.py index 515b0f0c7..cffc5f9e2 100644 --- a/python/PiFinder/pointing_model/astro_coords.py +++ b/python/PiFinder/pointing_model/astro_coords.py @@ -7,14 +7,14 @@ import quaternion from typing import Union # When updated to Python 3.10+, remove and use new type hints -import PiFinder.pointing_model.quaternion_transforms as qt +import PiFinder.pointing_model.quaternion_transforms as qt # TODO: Remove dependence on qt @dataclass class RaDecRoll: """ Data class for equatorial coordinates defined by (RA, Dec, Roll). This - makes it easier to convert between radians and degrees. + makes it easier for interfacing and convert between radians and degrees. The set methods allow values to be float or None but internally, None will be stored as np.nan so that the type is consistent. the get methods will From b831815379203858da0142a9e80b27dce2742b3f Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Sat, 6 Sep 2025 18:03:26 +0200 Subject: [PATCH 184/253] astro_coords: Remove dependence on quaternion_transforms --- .../PiFinder/pointing_model/astro_coords.py | 25 ++++++++++++++++--- 1 file changed, 21 insertions(+), 4 deletions(-) diff --git a/python/PiFinder/pointing_model/astro_coords.py b/python/PiFinder/pointing_model/astro_coords.py index cffc5f9e2..0f1a31654 100644 --- a/python/PiFinder/pointing_model/astro_coords.py +++ b/python/PiFinder/pointing_model/astro_coords.py @@ -7,8 +7,6 @@ import quaternion from typing import Union # When updated to Python 3.10+, remove and use new type hints -import PiFinder.pointing_model.quaternion_transforms as qt # TODO: Remove dependence on qt - @dataclass class RaDecRoll: @@ -60,8 +58,27 @@ def set_from_deg( self.set(ra, dec, roll) def set_from_quaternion(self, q_eq: quaternion.quaternion): - """Set from a quaternion rotation relative to the Equatorial frame""" - ra, dec, roll = qt.get_radec_of_q_eq(q_eq) + """ + Set from a quaternion rotation relative to the Equatorial frame. + Re-using code from quaternion_transforms.get_radec_of_q_eq. + """ + # Pure quaternion along camera boresight + pz_frame = q_eq * quaternion.quaternion(0, 0, 0, 1) * q_eq.conj() + + # Calculate RA, Dec from the camera boresight: + dec = np.arcsin(pz_frame.z) + ra = np.arctan2(pz_frame.y, pz_frame.x) + + # Calcualte Roll: + # Pure quaternion along y_cam which points to NCP when roll = 0 + py_cam = q_eq * quaternion.quaternion(0, 0, 1, 0) * q_eq.conj() + # Local East and North vectors (roll is the angle between py_cam and the north vector) + vec_east = np.array([-np.sin(ra), np.cos(ra), 0]) + vec_north = np.array( + [-np.sin(dec) * np.cos(ra), -np.sin(dec) * np.sin(ra), np.cos(dec)] + ) + roll = -np.arctan2(np.dot(py_cam.vec, vec_east), np.dot(py_cam.vec, vec_north)) + self.set(ra, dec, roll) def get( From ffb98838ba2a01cb550f37ff65bc744f738627d5 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Sat, 6 Sep 2025 18:09:18 +0200 Subject: [PATCH 185/253] Rename func --> get_q_eq() --- .../PiFinder/pointing_model/imu_dead_reckoning.py | 6 +++--- .../pointing_model/quaternion_transforms.py | 15 +++++++-------- 2 files changed, 10 insertions(+), 11 deletions(-) diff --git a/python/PiFinder/pointing_model/imu_dead_reckoning.py b/python/PiFinder/pointing_model/imu_dead_reckoning.py index 3098fccbb..ca3ec1930 100644 --- a/python/PiFinder/pointing_model/imu_dead_reckoning.py +++ b/python/PiFinder/pointing_model/imu_dead_reckoning.py @@ -82,8 +82,8 @@ def set_alignment( q_scope2cam: Quaternion that rotates the scope frame to the camera frame. """ # Calculate q_scope2cam (alignment) - q_eq2cam = qt.get_q_eq2cam(solved_cam.ra, solved_cam.dec, solved_cam.roll) - q_eq2scope = qt.get_q_eq2cam(solved_scope.ra, solved_scope.dec, solved_scope.roll) + q_eq2cam = qt.get_q_eq(solved_cam.ra, solved_cam.dec, solved_cam.roll) + q_eq2scope = qt.get_q_eq(solved_scope.ra, solved_scope.dec, solved_scope.roll) q_scope2cam = q_eq2scope.conjugate() * q_eq2cam # TODO: Use qt.get_q_scope2cam(target_eq, cam_eq) @@ -113,7 +113,7 @@ def update_plate_solve_and_imu( # Update plate-solved coord: Camera frame relative to the Equatorial # frame where the +y camera frame (i.e. "up") points to the North # Celestial Pole (NCP) -- i.e. zero roll offset: - self.q_eq2cam = qt.get_q_eq2cam(solved_cam.ra, solved_cam.dec, solved_cam.roll) + self.q_eq2cam = qt.get_q_eq(solved_cam.ra, solved_cam.dec, solved_cam.roll) self.dead_reckoning = False # Using plate solve, no dead_reckoning # Update IMU: Calculate the IMU's unknown reference frame X using the diff --git a/python/PiFinder/pointing_model/quaternion_transforms.py b/python/PiFinder/pointing_model/quaternion_transforms.py index cf53c32e5..ebe259721 100644 --- a/python/PiFinder/pointing_model/quaternion_transforms.py +++ b/python/PiFinder/pointing_model/quaternion_transforms.py @@ -62,13 +62,12 @@ def get_quat_angular_diff( # ========== Equatorial frame functions ============================ -# TODO: Rename to get_q_eq2frame? -def get_q_eq2cam( +def get_q_eq( ra_rad: float, dec_rad: float, roll_rad: float ) -> quaternion.quaternion: # TODO: Rename to q_eq2frame? """ - Express the coordinates of a camera pointing at RA, Dec, Roll (in radians) - in the relative to the Equatorial frame. + Express the equatorial coordinates (RA, Dec, Roll) in radians + in a quaternion rotation the relative to the Equatorial frame. """ # Intrinsic rotation of q_ra followed by q_dec gives a quaternion rotation # that points +z towards the boresight of the camera. +y to the left and @@ -83,8 +82,8 @@ def get_q_eq2cam( q_roll = axis_angle2quat([0, 0, 1], np.pi / 2 + roll_rad) # Intrinsic rotation: - q_eq2cam = (q_ra * q_dec * q_roll).normalized() - return q_eq2cam + q_eq = (q_ra * q_dec * q_roll).normalized() + return q_eq def get_radec_of_q_eq(q_eq2frame: quaternion.quaternion) -> tuple[float, float, float]: @@ -116,8 +115,8 @@ def get_q_scope2cam(target_eq: RaDecRoll, cam_eq: RaDecRoll) -> quaternion.quate #TODO: Update? # TODO: Cannot use RaDecRoll here because it'll cause a circular import - q_eq2cam = get_q_eq2cam(cam_eq.ra, cam_eq.dec, cam_eq.roll) - q_eq2scope = get_q_eq2cam( + q_eq2cam = get_q_eq(cam_eq.ra, cam_eq.dec, cam_eq.roll) + q_eq2scope = get_q_eq( target_eq.ra, target_eq.dec, target_eq.roll ) # This assumes an EQ mount - We don't know the roll of the scope frame q_scope2cam = q_eq2scope.conj() * q_eq2cam From 842c7278720dce49414c3de2e6420cbb3388e8e3 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Sat, 6 Sep 2025 18:16:10 +0200 Subject: [PATCH 186/253] Remove commented out code block --- .../pointing_model/imu_dead_reckoning.py | 2 +- .../pointing_model/quaternion_transforms.py | 17 ----------------- 2 files changed, 1 insertion(+), 18 deletions(-) diff --git a/python/PiFinder/pointing_model/imu_dead_reckoning.py b/python/PiFinder/pointing_model/imu_dead_reckoning.py index ca3ec1930..a1952063b 100644 --- a/python/PiFinder/pointing_model/imu_dead_reckoning.py +++ b/python/PiFinder/pointing_model/imu_dead_reckoning.py @@ -86,7 +86,7 @@ def set_alignment( q_eq2scope = qt.get_q_eq(solved_scope.ra, solved_scope.dec, solved_scope.roll) q_scope2cam = q_eq2scope.conjugate() * q_eq2cam - # TODO: Use qt.get_q_scope2cam(target_eq, cam_eq) + # Set the alignmen attributes: self.q_scope2cam = q_scope2cam.normalized() self.q_cam2scope = self.q_scope2cam.conj() self.q_imu2scope = self.q_imu2cam * self.q_cam2scope diff --git a/python/PiFinder/pointing_model/quaternion_transforms.py b/python/PiFinder/pointing_model/quaternion_transforms.py index ebe259721..7a84f700f 100644 --- a/python/PiFinder/pointing_model/quaternion_transforms.py +++ b/python/PiFinder/pointing_model/quaternion_transforms.py @@ -107,20 +107,3 @@ def get_radec_of_q_eq(q_eq2frame: quaternion.quaternion) -> tuple[float, float, roll = -np.arctan2(np.dot(py_cam.vec, vec_east), np.dot(py_cam.vec, vec_north)) return ra, dec, roll # In radians - - -""" -def get_q_scope2cam(target_eq: RaDecRoll, cam_eq: RaDecRoll) -> quaternion.quaternion: - #Returns the quaternion that rotates from the scope frame to the camera frame. - #TODO: Update? - # TODO: Cannot use RaDecRoll here because it'll cause a circular import - - q_eq2cam = get_q_eq(cam_eq.ra, cam_eq.dec, cam_eq.roll) - q_eq2scope = get_q_eq( - target_eq.ra, target_eq.dec, target_eq.roll - ) # This assumes an EQ mount - We don't know the roll of the scope frame - q_scope2cam = q_eq2scope.conj() * q_eq2cam - NotImplementedError # TODO: Needs more work - - return q_scope2cam -""" From 264a24210a8351f49383b5de8326dd56fc755467 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Sun, 21 Sep 2025 14:27:58 +0200 Subject: [PATCH 187/253] Update README issues list --- python/PiFinder/pointing_model/README.md | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/python/PiFinder/pointing_model/README.md b/python/PiFinder/pointing_model/README.md index ee85800d0..09057fad2 100644 --- a/python/PiFinder/pointing_model/README.md +++ b/python/PiFinder/pointing_model/README.md @@ -7,17 +7,18 @@ README: IMU support prototyping >Remove this before release! +See Discord thread: https://discord.com/channels/1087556380724052059/1406599296002035895 + Issues: -* Doesn't run wih v3 Flat. Issue in main branch? -* Issue in requirements? Can't get it to work in a new env. +* Doesn't run wih v3 Flat. Issue in main branch? (reported by grimaldi: 20 Aug 2025 https://discord.com/channels/1087556380724052059/1406599296002035895/1407813498163167345) +* Issue in the default requirements? Error (not related to the IMU changes) when I try to create a new env using requirements.txt. Maybe I can't just create a new environment using pip? * Doesn't pass Nox * In EQ mode flickers between 0° and 359°. This is also in the main branch. TODO: -* Use RaDecRoll class --> Done. Need to test. * Use alignment rather than calculating every loop * Go through TODOs in code -* Discuss requirements.txt with Richard +* Discuss requirements.txt with Richard: It needs numpy quaternion. Can this just be added to the requirements.txt? Later: * Update imu_pi.py @@ -27,6 +28,7 @@ Done: * Adjust Roll depending on mount_type for charts * Lint * Type hints for integrator.py +* Use RaDecRoll class --> Done. Need to test. # Sky test log From b96626965c3fdd782c36b6cd4c2786f546dfe9c8 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 21 Sep 2025 14:36:03 +0100 Subject: [PATCH 188/253] Now shows RA difference to aim as -180 to +180 degrees rather than 0 to 360 degrees --- python/PiFinder/calc_utils.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/python/PiFinder/calc_utils.py b/python/PiFinder/calc_utils.py index 4d97b9907..aca232434 100644 --- a/python/PiFinder/calc_utils.py +++ b/python/PiFinder/calc_utils.py @@ -168,6 +168,8 @@ def aim_degrees(shared_state, mount_type, screen_direction, target): else: # EQ Mount type ra_diff = target.ra - solution["RA"] + ra_diff = (dec_diff + 180) % 360 - 180 # Convert to -180 to +180 + dec_diff = target.dec - solution["Dec"] dec_diff = (dec_diff + 180) % 360 - 180 return ra_diff, dec_diff From 4b91d20a80baf62e167647de9fda07c99ca088f0 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 21 Sep 2025 14:36:18 +0100 Subject: [PATCH 189/253] README - detail out TODO & issues --- python/PiFinder/pointing_model/README.md | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/python/PiFinder/pointing_model/README.md b/python/PiFinder/pointing_model/README.md index 09057fad2..fc3a9e1f2 100644 --- a/python/PiFinder/pointing_model/README.md +++ b/python/PiFinder/pointing_model/README.md @@ -16,9 +16,13 @@ Issues: * In EQ mode flickers between 0° and 359°. This is also in the main branch. TODO: -* Use alignment rather than calculating every loop +* Set alignment once at alignment rather than calculating it every loop + * Alignment is currently done in `integrator.py` where `set_alignment()` is + called every iteration of the loop. Would like to set the alignment onece + to pre-compute the `q_scope2cam` quaternion, etc. * Go through TODOs in code -* Discuss requirements.txt with Richard: It needs numpy quaternion. Can this just be added to the requirements.txt? +* Discuss requirements.txt with Richard + * It needs numpy quaternion. Can this just be added to the requirements.txt? Later: * Update imu_pi.py @@ -30,7 +34,6 @@ Done: * Type hints for integrator.py * Use RaDecRoll class --> Done. Need to test. - # Sky test log >Remove this before release! From 50952b83c000d66d75866dd9e0fda55bd2aafd7a Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 21 Sep 2025 14:57:35 +0100 Subject: [PATCH 190/253] Lint --- python/PiFinder/calc_utils.py | 1 + 1 file changed, 1 insertion(+) diff --git a/python/PiFinder/calc_utils.py b/python/PiFinder/calc_utils.py index aca232434..017c9be96 100644 --- a/python/PiFinder/calc_utils.py +++ b/python/PiFinder/calc_utils.py @@ -172,6 +172,7 @@ def aim_degrees(shared_state, mount_type, screen_direction, target): dec_diff = target.dec - solution["Dec"] dec_diff = (dec_diff + 180) % 360 - 180 + return ra_diff, dec_diff return None, None From 645c07207f2b3f33aab26c59828733e08ae39017 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 21 Sep 2025 22:22:09 +0100 Subject: [PATCH 191/253] Add quaternion to mypy.overrides to ignore type hints --- python/pyproject.toml | 1 + 1 file changed, 1 insertion(+) diff --git a/python/pyproject.toml b/python/pyproject.toml index 5617b6ec3..6f9340e7f 100644 --- a/python/pyproject.toml +++ b/python/pyproject.toml @@ -128,6 +128,7 @@ module = [ 'sklearn.*', 'PyHotKey.*', 'PiFinder.tetra3.*', + 'quaterion', 'tetra3.*', 'grpc', 'ceder_detect_pb2', From c3c30bf0d0922c34bcb39530d31a0b72f58d5b36 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Mon, 22 Sep 2025 07:31:49 +0100 Subject: [PATCH 192/253] Rename --> initialized_solved_dict --- python/PiFinder/integrator.py | 4 ++-- python/PiFinder/pointing_model/astro_coords.py | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 22f886711..287e8d1d7 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -19,7 +19,7 @@ from PiFinder import state_utils import PiFinder.calc_utils as calc_utils from PiFinder.multiproclogging import MultiprocLogging -from PiFinder.pointing_model.astro_coords import get_initialized_solved_dict, RaDecRoll +from PiFinder.pointing_model.astro_coords import initialized_solved_dict, RaDecRoll from PiFinder.pointing_model.imu_dead_reckoning import ImuDeadReckoning import PiFinder.pointing_model.quaternion_transforms as qt @@ -41,7 +41,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa try: # Dict of RA, Dec, etc. initialized to None: - solved = get_initialized_solved_dict() + solved = initialized_solved_dict() cfg = config.Config() mount_type = cfg.get_option("mount_type") diff --git a/python/PiFinder/pointing_model/astro_coords.py b/python/PiFinder/pointing_model/astro_coords.py index 0f1a31654..9fb98ebbb 100644 --- a/python/PiFinder/pointing_model/astro_coords.py +++ b/python/PiFinder/pointing_model/astro_coords.py @@ -118,7 +118,7 @@ def get_deg( return ra, dec, roll -def get_initialized_solved_dict() -> dict: +def initialized_solved_dict() -> dict: """ Returns an initialized 'solved' dictionary with cooridnate and other information. From eea1e35fd03cd3a14a7cc60e5bfbfcbe7112958d Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Mon, 22 Sep 2025 07:46:17 +0100 Subject: [PATCH 193/253] Fix bug in ra_diff calculation: Was causing a crash when catalogs selected in EQ mode --- python/PiFinder/calc_utils.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/python/PiFinder/calc_utils.py b/python/PiFinder/calc_utils.py index 017c9be96..e5b99ad60 100644 --- a/python/PiFinder/calc_utils.py +++ b/python/PiFinder/calc_utils.py @@ -168,7 +168,7 @@ def aim_degrees(shared_state, mount_type, screen_direction, target): else: # EQ Mount type ra_diff = target.ra - solution["RA"] - ra_diff = (dec_diff + 180) % 360 - 180 # Convert to -180 to +180 + ra_diff = (ra_diff + 180) % 360 - 180 # Convert to -180 to +180 dec_diff = target.dec - solution["Dec"] dec_diff = (dec_diff + 180) % 360 - 180 From 1a082d6ec36f81559892d2675375277856291db9 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Mon, 22 Sep 2025 07:51:48 +0100 Subject: [PATCH 194/253] Remove commented out code block --- python/PiFinder/camera_interface.py | 13 ++----------- 1 file changed, 2 insertions(+), 11 deletions(-) diff --git a/python/PiFinder/camera_interface.py b/python/PiFinder/camera_interface.py index b673988da..3fedd94f0 100644 --- a/python/PiFinder/camera_interface.py +++ b/python/PiFinder/camera_interface.py @@ -112,17 +112,6 @@ def get_image_loop( imu_end = shared_state.imu() # see if we moved during exposure - pointing_diff = 0.0 - - # TODO: REMOVE - # if imu_start and imu_end: - # pointing_diff = ( - # abs(imu_start["pos"][0] - imu_end["pos"][0]) - # + abs(imu_start["pos"][1] - imu_end["pos"][1]) - # + abs(imu_start["pos"][2] - imu_end["pos"][2]) - # ) - - # # Quaternion version if imu_start and imu_end: # Returns the pointing difference between successive IMU quaternions as # an angle (radians). Note that this also accounts for rotation around the @@ -130,6 +119,8 @@ def get_image_loop( pointing_diff = qt.get_quat_angular_diff( imu_start["quat"], imu_end["quat"] ) + else: + pointing_diff = 0.0 camera_image.paste(base_image) shared_state.set_last_image_metadata( From d0146da377dd724760b0c042dc55d76face80478 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Mon, 22 Sep 2025 07:58:47 +0100 Subject: [PATCH 195/253] Remove unused IMU data: "pos", "imu_pos", etc. which stored Euler angles that are no longer used --- python/PiFinder/imu_pi.py | 9 --------- python/PiFinder/pointing_model/astro_coords.py | 1 - python/PiFinder/pointing_model/imu_print_measurements.py | 4 ---- python/PiFinder/solver.py | 3 --- 4 files changed, 17 deletions(-) diff --git a/python/PiFinder/imu_pi.py b/python/PiFinder/imu_pi.py index 0e11933f3..528580ec4 100644 --- a/python/PiFinder/imu_pi.py +++ b/python/PiFinder/imu_pi.py @@ -163,11 +163,6 @@ def imu_monitor(shared_state, console_queue, log_queue): "moving": False, "move_start": None, "move_end": None, - "pos": [ - 0, - 0, - 0, - ], # Corresponds to [Az, related_to_roll, Alt] --> **TO REMOVE LATER "quat": np.quaternion( 0, 0, 0, 0 ), # Scalar-first numpy quaternion(w, x, y, z) - Init to invalid quaternion @@ -184,10 +179,8 @@ def imu_monitor(shared_state, console_queue, log_queue): if not imu_data["moving"]: logger.debug("IMU: move start") imu_data["moving"] = True - imu_data["start_pos"] = imu_data["pos"] imu_data["move_start"] = time.time() # DISABLE old method - # imu_data["pos"] = imu.get_euler() # TODO: Remove this later. Was used to store Euler angles imu_data["quat"] = quaternion.from_float_array( imu.avg_quat ) # Scalar-first (w, x, y, z) @@ -197,8 +190,6 @@ def imu_monitor(shared_state, console_queue, log_queue): logger.debug("IMU: move end") imu_data["moving"] = False imu_data["move_end"] = time.time() - # DISABLE old method - # imu_data["pos"] = imu.get_euler() imu_data["quat"] = quaternion.from_float_array( imu.avg_quat ) # Scalar-first (w, x, y, z) diff --git a/python/PiFinder/pointing_model/astro_coords.py b/python/PiFinder/pointing_model/astro_coords.py index 9fb98ebbb..37dc63c0b 100644 --- a/python/PiFinder/pointing_model/astro_coords.py +++ b/python/PiFinder/pointing_model/astro_coords.py @@ -145,7 +145,6 @@ def initialized_solved_dict() -> dict: "Roll": None, }, "Roll_offset": 0, # May/may not be needed - for experimentation - "imu_pos": None, "imu_quat": None, # IMU quaternion as numpy quaternion (scalar-first) - TODO: Move to "imu" "Alt": None, # Alt of scope "Az": None, diff --git a/python/PiFinder/pointing_model/imu_print_measurements.py b/python/PiFinder/pointing_model/imu_print_measurements.py index 23b47379b..c51b7c23f 100644 --- a/python/PiFinder/pointing_model/imu_print_measurements.py +++ b/python/PiFinder/pointing_model/imu_print_measurements.py @@ -149,7 +149,6 @@ def imu_monitor(): "moving": False, "move_start": None, "move_end": None, - "pos": [0, 0, 0], # Corresponds to [Az, related_to_roll, Alt] "quat": [0, 0, 0, 0], # Scalar-first quaternion (w, x, y, z) "start_pos": [0, 0, 0], "status": 0, @@ -162,9 +161,7 @@ def imu_monitor(): if not imu_data["moving"]: # logger.debug("IMU: move start") imu_data["moving"] = True - imu_data["start_pos"] = imu_data["pos"] imu_data["move_start"] = time.time() - imu_data["pos"] = imu.get_euler() imu_data["quat"] = imu.avg_quat print(imu_data["quat"]) @@ -174,7 +171,6 @@ def imu_monitor(): # If we were moving and we now stopped # logger.debug("IMU: move end") imu_data["moving"] = False - imu_data["pos"] = imu.get_euler() imu_data["quat"] = imu.avg_quat imu_data["move_end"] = time.time() diff --git a/python/PiFinder/solver.py b/python/PiFinder/solver.py index c09f1fb2b..e6022b257 100644 --- a/python/PiFinder/solver.py +++ b/python/PiFinder/solver.py @@ -69,7 +69,6 @@ def solver( "RA": None, "Dec": None, "Roll": None, - "imu_pos": None, "solve_time": None, "cam_solve_time": 0, } @@ -204,10 +203,8 @@ def solver( solved["RA"] = solved["RA_target"] solved["Dec"] = solved["Dec_target"] if last_image_metadata["imu"]: - solved["imu_pos"] = last_image_metadata["imu"]["pos"] solved["imu_quat"] = last_image_metadata["imu"]["quat"] else: - solved["imu_pos"] = None solved["imu_quat"] = None solved["solve_time"] = time.time() solved["cam_solve_time"] = solved["solve_time"] From 79f00a7dda101139b1a8ef68fef081506b6a0920 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Mon, 22 Sep 2025 17:40:58 +0100 Subject: [PATCH 196/253] Remove "imu_pos", "pos" etc. for Euler angles --- docs/source/dev_arch.rst | 6 +++--- python/PiFinder/imu_pi.py | 3 +-- python/PiFinder/pointing_model/imu_print_measurements.py | 1 - python/PiFinder/state.py | 6 +++--- 4 files changed, 7 insertions(+), 9 deletions(-) diff --git a/docs/source/dev_arch.rst b/docs/source/dev_arch.rst index 1f512ddc7..969ea6cef 100644 --- a/docs/source/dev_arch.rst +++ b/docs/source/dev_arch.rst @@ -219,12 +219,12 @@ There are three types of shared state in PiFinder SharedStateObj( power_state=1, solve_state=True, - solution={'RA': 22.86683471463411, 'Dec': 15.347716050003328, 'imu_pos': [171.39798541261814, 202.7646132036331, 358.2794741322842], + solution={'RA': 22.86683471463411, 'Dec': 15.347716050003328, 'solve_time': 1695297930.5532792, 'cam_solve_time': 1695297930.5532837, 'Roll': 306.2951794424281, 'FOV': 10.200729425086111, RMSE': 21.995567413046142, 'Matches': 12, 'Prob': 6.987725483613384e-13, 'T_solve': 15.00384000246413, 'RA_target': 22.86683471463411, 'Dec_target': 15.347716050003328, 'T_extract': 75.79255499877036, 'Alt': None, 'Az': None, 'solve_source': 'CAM', 'constellation': 'Psc'}, - imu={'moving': False, 'move_start': 1695297928.69749, 'move_end': 1695297928.764207, 'pos': [171.39798541261814, 202.7646132036331, 358.2794741322842], - 'start_pos': [171.4009455613444, 202.76321535004726, 358.2587208386012], 'status': 3}, + imu={'moving': False, 'move_start': 1695297928.69749, 'move_end': 1695297928.764207, + 'status': 3}, location={'lat': 59.05139745, 'lon': 7.987654, 'altitude': 151.4, 'gps_lock': False, 'timezone': 'Europe/Stockholm', 'last_gps_lock': None}, datetime=None, screen=, diff --git a/python/PiFinder/imu_pi.py b/python/PiFinder/imu_pi.py index 528580ec4..cbaedc15c 100644 --- a/python/PiFinder/imu_pi.py +++ b/python/PiFinder/imu_pi.py @@ -158,7 +158,7 @@ def imu_monitor(shared_state, console_queue, log_queue): MultiprocLogging.configurer(log_queue) imu = Imu() imu_calibrated = False - # TODO: Remove start_pos, move_start, move_end + # TODO: Remove move_start, move_end imu_data = { "moving": False, "move_start": None, @@ -166,7 +166,6 @@ def imu_monitor(shared_state, console_queue, log_queue): "quat": np.quaternion( 0, 0, 0, 0 ), # Scalar-first numpy quaternion(w, x, y, z) - Init to invalid quaternion - "start_pos": [0, 0, 0], "status": 0, } diff --git a/python/PiFinder/pointing_model/imu_print_measurements.py b/python/PiFinder/pointing_model/imu_print_measurements.py index c51b7c23f..791d974ec 100644 --- a/python/PiFinder/pointing_model/imu_print_measurements.py +++ b/python/PiFinder/pointing_model/imu_print_measurements.py @@ -150,7 +150,6 @@ def imu_monitor(): "move_start": None, "move_end": None, "quat": [0, 0, 0, 0], # Scalar-first quaternion (w, x, y, z) - "start_pos": [0, 0, 0], "status": 0, } diff --git a/python/PiFinder/state.py b/python/PiFinder/state.py index ea75ffba0..934447b39 100644 --- a/python/PiFinder/state.py +++ b/python/PiFinder/state.py @@ -126,12 +126,12 @@ def __repr__(self): SharedStateObj( power_state=1, solve_state=True, - solution={'RA': 22.86683471463411, 'Dec': 15.347716050003328, 'imu_pos': [171.39798541261814, 202.7646132036331, 358.2794741322842], + solution={'RA': 22.86683471463411, 'Dec': 15.347716050003328, 'solve_time': 1695297930.5532792, 'cam_solve_time': 1695297930.5532837, 'Roll': 306.2951794424281, 'FOV': 10.200729425086111, 'RMSE': 21.995567413046142, 'Matches': 12, 'Prob': 6.987725483613384e-13, 'T_solve': 15.00384000246413, 'RA_target': 22.86683471463411, 'Dec_target': 15.347716050003328, 'T_extract': 75.79255499877036, 'Alt': None, 'Az': None, 'solve_source': 'CAM', 'constellation': 'Psc'}, - imu={'moving': False, 'move_start': 1695297928.69749, 'move_end': 1695297928.764207, 'pos': [171.39798541261814, 202.7646132036331, 358.2794741322842], - 'start_pos': [171.4009455613444, 202.76321535004726, 358.2587208386012], 'status': 3}, + imu={'moving': False, 'move_start': 1695297928.69749, 'move_end': 1695297928.764207, + 'status': 3}, location={'lat': 59.05139745, 'lon': 7.987654, 'altitude': 151.4, 'source': 'GPS', gps_lock': False, 'timezone': 'Europe/Stockholm', 'last_gps_lock': None}, datetime=None, screen=, From 7ce868cdac05dade479b4209306e229a1ff1a32b Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Mon, 22 Sep 2025 17:47:22 +0100 Subject: [PATCH 197/253] Remove unused Euler angle functions/methods quat_to_euler() and get_euler() --- python/PiFinder/imu_pi.py | 14 -------------- .../pointing_model/imu_print_measurements.py | 5 ----- 2 files changed, 19 deletions(-) diff --git a/python/PiFinder/imu_pi.py b/python/PiFinder/imu_pi.py index cbaedc15c..23e816da3 100644 --- a/python/PiFinder/imu_pi.py +++ b/python/PiFinder/imu_pi.py @@ -50,17 +50,6 @@ def __init__(self): # to stop moving. self.__moving_threshold = (0.0005, 0.0003) - def quat_to_euler(self, quat): - if quat[0] + quat[1] + quat[2] + quat[3] == 0: - return 0, 0, 0 - rot = Rotation.from_quat(quat) - rot_euler = rot.as_euler("xyz", degrees=True) - # convert from -180/180 to 0/360 - rot_euler[0] += 180 - rot_euler[1] += 180 - rot_euler[2] += 180 - return rot_euler - def moving(self): """ Compares most recent reading @@ -136,9 +125,6 @@ def update(self): if self.__reading_diff > self.__moving_threshold[0]: self.__moving = True - def get_euler(self): - return list(self.quat_to_euler(self.avg_quat)) - def __str__(self): return ( f"IMU Information:\n" diff --git a/python/PiFinder/pointing_model/imu_print_measurements.py b/python/PiFinder/pointing_model/imu_print_measurements.py index 791d974ec..756fcf032 100644 --- a/python/PiFinder/pointing_model/imu_print_measurements.py +++ b/python/PiFinder/pointing_model/imu_print_measurements.py @@ -135,11 +135,6 @@ def update(self): if self.__reading_diff > self.__moving_threshold[0]: self.__moving = True - def get_euler(self): - return list( - self.quat_to_euler(self.avg_quat) - ) # !! Expect scalar-last but avg_quat is scalar-first?? - def imu_monitor(): # MultiprocLogging.configurer(log_queue) From d6b24bfb43072f199373b7d7add8d53e16bec1d3 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Mon, 22 Sep 2025 20:58:15 +0200 Subject: [PATCH 198/253] Address TODO items --- python/PiFinder/imu_pi.py | 1 - python/PiFinder/integrator.py | 12 ++++++------ python/PiFinder/pointing_model/astro_coords.py | 3 +-- python/PiFinder/pointing_model/imu_dead_reckoning.py | 10 ++++------ .../PiFinder/pointing_model/quaternion_transforms.py | 4 +--- python/PiFinder/solver.py | 5 ++--- 6 files changed, 14 insertions(+), 21 deletions(-) diff --git a/python/PiFinder/imu_pi.py b/python/PiFinder/imu_pi.py index 23e816da3..76c060b00 100644 --- a/python/PiFinder/imu_pi.py +++ b/python/PiFinder/imu_pi.py @@ -17,7 +17,6 @@ logger = logging.getLogger("IMU.pi") QUEUE_LEN = 10 -MOVE_CHECK_LEN = 2 # TODO: Doesn't seem to be used? class Imu: diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 287e8d1d7..d16173d2c 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -34,7 +34,6 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=False): MultiprocLogging.configurer(log_queue) """ """ - is_debug = True # TODO: For development. Remove later. if is_debug: logger.setLevel(logging.DEBUG) logger.debug("Starting Integrator") @@ -49,7 +48,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa # Set up dead-reckoning tracking by the IMU: imu_dead_reckoning = ImuDeadReckoning(cfg.get_option("screen_direction")) - # imu_dead_reckoning.set_alignment(q_scope2cam) # TODO: Enable when q_scope2cam is available + # imu_dead_reckoning.set_alignment(q_scope2cam) # TODO: Enable when q_scope2cam is available from alignment # This holds the last image solve position info # so we can delta for IMU updates @@ -88,8 +87,10 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa # Try to set date and time location = shared_state.location() dt = shared_state.datetime() - # Set location for roll and altaz calculations. TODO: Is it necessary to set location? - # TODO: Altaz doesn't seem to be required for catalogs when in EQ mode? Could be disabled in future when in EQ mode? + # Set location for roll and altaz calculations. + # TODO: Is itnecessary to set location? + # TODO: Altaz doesn't seem to be required for catalogs when in + # EQ mode? Could be disabled in future when in EQ mode? calc_utils.sf_utils.set_location( location.lat, location.lon, location.altitude ) @@ -136,7 +137,6 @@ def update_plate_solve_and_imu(imu_dead_reckoning: ImuDeadReckoning, solved: dic else: # Successfully plate solved & camera pointing exists if solved["imu_quat"] is None: - # TODO: This Do not run the rest of the code? q_x2imu = quaternion.quaternion(np.nan) else: q_x2imu = solved["imu_quat"] # IMU measurement at the time of plate solving @@ -168,7 +168,7 @@ def set_alignment(imu_dead_reckoning: ImuDeadReckoning, solved: dict): ) # RA, Dec of target (where scope is pointing): - solved["Roll"] = 0 # TODO: Target roll isn't calculated by Tetra3. Set to zero here + solved["Roll"] = 0 # Target roll isn't calculated by Tetra3. Set to zero here solved_scope = RaDecRoll() solved_scope.set_from_deg(solved["RA"], solved["Dec"], solved["Roll"]) diff --git a/python/PiFinder/pointing_model/astro_coords.py b/python/PiFinder/pointing_model/astro_coords.py index 37dc63c0b..07f7f027d 100644 --- a/python/PiFinder/pointing_model/astro_coords.py +++ b/python/PiFinder/pointing_model/astro_coords.py @@ -18,8 +18,6 @@ class RaDecRoll: be stored as np.nan so that the type is consistent. the get methods will return None if the value is np.nan. - TODO: Migrate to something like this from the current "solved" dict? - NOTE: All angles are in radians. """ @@ -125,6 +123,7 @@ def initialized_solved_dict() -> dict: TODO: The solved dict is used by other components. Move this func and use this elsewhere (e.g. solver.py) to enforce consistency. + TODO: use RaDecRoll class for the RA, Dec, Roll coordinates here? """ # TODO: This dict is duplicated in solver.py - Refactor? # "Alt" and "Az" could be removed once we move to Eq-based dead-reckoning diff --git a/python/PiFinder/pointing_model/imu_dead_reckoning.py b/python/PiFinder/pointing_model/imu_dead_reckoning.py index a1952063b..88b77d3ef 100644 --- a/python/PiFinder/pointing_model/imu_dead_reckoning.py +++ b/python/PiFinder/pointing_model/imu_dead_reckoning.py @@ -29,13 +29,13 @@ class ImuDeadReckoning: All angles are in radians. None is not allowed as inputs (use np.nan). - EXAMPLE: TODO: Update + EXAMPLE: # Set up: imu_dead_reckoning = ImuDeadReckoning('flat') - imu_dead_reckoning.set_alignment(q_scope2cam) + imu_dead_reckoning.set_alignment(solved_cam, solved_scope) # Update with plate solved and IMU data: - imu_dead_reckoning.update_plate_solve_and_imu(solved_cam_ra, solved_cam_dec, solved_cam_roll, q_x2imu) + imu_dead_reckoning.update_plate_solve_and_imu(solved_cam, q_x2imu) # Dead-reckoning using IMU imu_dead_reckoning.update_imu(q_x2imu) @@ -76,8 +76,6 @@ def set_alignment( Set the alignment between the PiFinder camera center and the scope pointing. - TODO: Setting cam2scope might be more natural? - INPUTS: q_scope2cam: Quaternion that rotates the scope frame to the camera frame. """ @@ -230,7 +228,7 @@ def get_screen_direction_q_imu2cam(screen_direction: str) -> quaternion.quaterni # Rotate -90° around z_imu' to align with the camera cooridnates q2 = qt.axis_angle2quat([0, 0, 1], -np.pi / 2) q_imu2cam = (q1 * q2).normalized() - elif screen_direction == "as_dream": # TODO: Propose o rename to "back"? + elif screen_direction == "as_dream": # TODO: Propose to rename to "back"? # As Dream: # Camera points back up from the screen # NOTE: Need to check if the orientation of the camera is correct diff --git a/python/PiFinder/pointing_model/quaternion_transforms.py b/python/PiFinder/pointing_model/quaternion_transforms.py index 7a84f700f..898b4d8bb 100644 --- a/python/PiFinder/pointing_model/quaternion_transforms.py +++ b/python/PiFinder/pointing_model/quaternion_transforms.py @@ -62,9 +62,7 @@ def get_quat_angular_diff( # ========== Equatorial frame functions ============================ -def get_q_eq( - ra_rad: float, dec_rad: float, roll_rad: float -) -> quaternion.quaternion: # TODO: Rename to q_eq2frame? +def get_q_eq(ra_rad: float, dec_rad: float, roll_rad: float) -> quaternion.quaternion: """ Express the equatorial coordinates (RA, Dec, Roll) in radians in a quaternion rotation the relative to the Equatorial frame. diff --git a/python/PiFinder/solver.py b/python/PiFinder/solver.py index e6022b257..df0f9d8cd 100644 --- a/python/PiFinder/solver.py +++ b/python/PiFinder/solver.py @@ -50,7 +50,7 @@ def solver( # TODO: This dictionary is duplicated in integrator.py. Need to rationalize? solved = { # RA, Dec, Roll solved at the center of the camera FoV - # update by integrator + # update by the IMU in the integrator "camera_center": { "RA": None, "Dec": None, @@ -58,8 +58,7 @@ def solver( "Alt": None, "Az": None, }, - # RA, Dec, Roll from the camera, not - # affected by IMU in integrator + # RA, Dec, Roll from the camera, not affected by IMU in integrator "camera_solve": { "RA": None, "Dec": None, From f5340011b5e94147f21d25928cff817208795786 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Mon, 22 Sep 2025 21:12:17 +0200 Subject: [PATCH 199/253] ToDo items: Remove unused variables --- python/PiFinder/camera_interface.py | 2 +- python/PiFinder/pointing_model/astro_coords.py | 3 +-- python/PiFinder/pointing_model/imu_dead_reckoning.py | 7 +++---- 3 files changed, 5 insertions(+), 7 deletions(-) diff --git a/python/PiFinder/camera_interface.py b/python/PiFinder/camera_interface.py index 3fedd94f0..96a108b9d 100644 --- a/python/PiFinder/camera_interface.py +++ b/python/PiFinder/camera_interface.py @@ -128,7 +128,7 @@ def get_image_loop( "exposure_start": image_start_time, "exposure_end": image_end_time, "imu": imu_end, - "imu_delta": np.rad2deg(pointing_diff), # TODO: Rename this + "imu_delta": np.rad2deg(pointing_diff), # Pointing chiange during exposure in degrees } ) diff --git a/python/PiFinder/pointing_model/astro_coords.py b/python/PiFinder/pointing_model/astro_coords.py index 07f7f027d..b42fce284 100644 --- a/python/PiFinder/pointing_model/astro_coords.py +++ b/python/PiFinder/pointing_model/astro_coords.py @@ -143,8 +143,7 @@ def initialized_solved_dict() -> dict: "Dec": None, "Roll": None, }, - "Roll_offset": 0, # May/may not be needed - for experimentation - "imu_quat": None, # IMU quaternion as numpy quaternion (scalar-first) - TODO: Move to "imu" + "imu_quat": None, # IMU quaternion as numpy quaternion (scalar-first) "Alt": None, # Alt of scope "Az": None, "solve_source": None, diff --git a/python/PiFinder/pointing_model/imu_dead_reckoning.py b/python/PiFinder/pointing_model/imu_dead_reckoning.py index 88b77d3ef..3d082c001 100644 --- a/python/PiFinder/pointing_model/imu_dead_reckoning.py +++ b/python/PiFinder/pointing_model/imu_dead_reckoning.py @@ -42,7 +42,6 @@ class ImuDeadReckoning: """ # Alignment: - q_scope2cam: quaternion.quaternion # TODO: Do we need this?? q_cam2scope: quaternion.quaternion # IMU orientation: q_imu2cam: quaternion.quaternion @@ -77,7 +76,8 @@ def set_alignment( pointing. INPUTS: - q_scope2cam: Quaternion that rotates the scope frame to the camera frame. + solved_cam: Equatorial coordinate of the camera center at alignment. + solved_scope: Equatorial coordinate of the scope center at alignement. """ # Calculate q_scope2cam (alignment) q_eq2cam = qt.get_q_eq(solved_cam.ra, solved_cam.dec, solved_cam.roll) @@ -85,8 +85,7 @@ def set_alignment( q_scope2cam = q_eq2scope.conjugate() * q_eq2cam # Set the alignmen attributes: - self.q_scope2cam = q_scope2cam.normalized() - self.q_cam2scope = self.q_scope2cam.conj() + self.q_cam2scope = q_scope2cam.normalized().conj() self.q_imu2scope = self.q_imu2cam * self.q_cam2scope def update_plate_solve_and_imu( From 944a6a85e304dfbac9313631779bf1eaff8e9f90 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Mon, 22 Sep 2025 21:20:42 +0200 Subject: [PATCH 200/253] Use solve dict from astro_coords --- .../PiFinder/pointing_model/astro_coords.py | 8 ++++-- python/PiFinder/solver.py | 27 +++---------------- 2 files changed, 9 insertions(+), 26 deletions(-) diff --git a/python/PiFinder/pointing_model/astro_coords.py b/python/PiFinder/pointing_model/astro_coords.py index b42fce284..da6720e8f 100644 --- a/python/PiFinder/pointing_model/astro_coords.py +++ b/python/PiFinder/pointing_model/astro_coords.py @@ -128,9 +128,12 @@ def initialized_solved_dict() -> dict: # TODO: This dict is duplicated in solver.py - Refactor? # "Alt" and "Az" could be removed once we move to Eq-based dead-reckoning solved = { - "RA": None, # RA of scope + # RA, Dec, Roll of the scope at the target pixel + "RA": None, "Dec": None, "Roll": None, + # RA, Dec, Roll solved at the center of the camera FoV + # update by the IMU in the integrator "camera_center": { "RA": None, "Dec": None, @@ -138,7 +141,8 @@ def initialized_solved_dict() -> dict: "Alt": None, # NOTE: Altaz needed by catalogs for altaz mounts "Az": None, }, - "camera_solve": { # camera_solve is NOT updated by IMU dead-reckoning + # RA, Dec, Roll from the camera, not updated by IMU in integrator + "camera_solve": { "RA": None, "Dec": None, "Roll": None, diff --git a/python/PiFinder/solver.py b/python/PiFinder/solver.py index df0f9d8cd..026ccb8f7 100644 --- a/python/PiFinder/solver.py +++ b/python/PiFinder/solver.py @@ -20,6 +20,7 @@ from PiFinder import state_utils from PiFinder import utils +from PiFinder.pointing_model.astro_coords import initialized_solved_dict sys.path.append(str(utils.tetra3_dir)) import tetra3 @@ -47,30 +48,8 @@ def solver( last_solve_time = 0 align_ra = 0 align_dec = 0 - # TODO: This dictionary is duplicated in integrator.py. Need to rationalize? - solved = { - # RA, Dec, Roll solved at the center of the camera FoV - # update by the IMU in the integrator - "camera_center": { - "RA": None, - "Dec": None, - "Roll": None, - "Alt": None, - "Az": None, - }, - # RA, Dec, Roll from the camera, not affected by IMU in integrator - "camera_solve": { - "RA": None, - "Dec": None, - "Roll": None, - }, - # RA, Dec, Roll at the target pixel - "RA": None, - "Dec": None, - "Roll": None, - "solve_time": None, - "cam_solve_time": 0, - } + # Dict of RA, Dec, etc. initialized to None: + solved = initialized_solved_dict() centroids = [] log_no_stars_found = True From 70717e73259c914b5a5bb72e1888a813bee81f6e Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Mon, 22 Sep 2025 21:20:55 +0200 Subject: [PATCH 201/253] Update README --- python/PiFinder/pointing_model/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/python/PiFinder/pointing_model/README.md b/python/PiFinder/pointing_model/README.md index fc3a9e1f2..b7522ab94 100644 --- a/python/PiFinder/pointing_model/README.md +++ b/python/PiFinder/pointing_model/README.md @@ -20,7 +20,6 @@ TODO: * Alignment is currently done in `integrator.py` where `set_alignment()` is called every iteration of the loop. Would like to set the alignment onece to pre-compute the `q_scope2cam` quaternion, etc. -* Go through TODOs in code * Discuss requirements.txt with Richard * It needs numpy quaternion. Can this just be added to the requirements.txt? @@ -33,6 +32,7 @@ Done: * Lint * Type hints for integrator.py * Use RaDecRoll class --> Done. Need to test. +* Go through TODOs in code # Sky test log From 03fc2e3219ac7b3db4336393df7c47108b960e92 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Mon, 22 Sep 2025 20:22:54 +0100 Subject: [PATCH 202/253] Update README --- python/PiFinder/pointing_model/README.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/python/PiFinder/pointing_model/README.md b/python/PiFinder/pointing_model/README.md index b7522ab94..ffa187ea8 100644 --- a/python/PiFinder/pointing_model/README.md +++ b/python/PiFinder/pointing_model/README.md @@ -10,10 +10,8 @@ README: IMU support prototyping See Discord thread: https://discord.com/channels/1087556380724052059/1406599296002035895 Issues: -* Doesn't run wih v3 Flat. Issue in main branch? (reported by grimaldi: 20 Aug 2025 https://discord.com/channels/1087556380724052059/1406599296002035895/1407813498163167345) * Issue in the default requirements? Error (not related to the IMU changes) when I try to create a new env using requirements.txt. Maybe I can't just create a new environment using pip? -* Doesn't pass Nox -* In EQ mode flickers between 0° and 359°. This is also in the main branch. +* In EQ mode flickers between 0° and 359°. This is also in the main branch. --> Test implementation TODO: * Set alignment once at alignment rather than calculating it every loop @@ -33,6 +31,8 @@ Done: * Type hints for integrator.py * Use RaDecRoll class --> Done. Need to test. * Go through TODOs in code +* Doesn't pass Nox +* Doesn't run wih v3 Flat. Issue in main branch? (reported by grimaldi: 20 Aug 2025 https://discord.com/channels/1087556380724052059/1406599296002035895/1407813498163167345) # Sky test log From 04465a22544531f34d97b8fe143da59461ba3627 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Mon, 22 Sep 2025 20:27:15 +0100 Subject: [PATCH 203/253] Update README --- python/PiFinder/pointing_model/README.md | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/python/PiFinder/pointing_model/README.md b/python/PiFinder/pointing_model/README.md index ffa187ea8..8909e0a44 100644 --- a/python/PiFinder/pointing_model/README.md +++ b/python/PiFinder/pointing_model/README.md @@ -10,8 +10,9 @@ README: IMU support prototyping See Discord thread: https://discord.com/channels/1087556380724052059/1406599296002035895 Issues: -* Issue in the default requirements? Error (not related to the IMU changes) when I try to create a new env using requirements.txt. Maybe I can't just create a new environment using pip? -* In EQ mode flickers between 0° and 359°. This is also in the main branch. --> Test implementation +* Issue in the default requirements? Error (not related to the IMU changes) + when I try to create a new env using requirements.txt. Maybe I can't just + create a new environment using pip? TODO: * Set alignment once at alignment rather than calculating it every loop @@ -33,6 +34,7 @@ Done: * Go through TODOs in code * Doesn't pass Nox * Doesn't run wih v3 Flat. Issue in main branch? (reported by grimaldi: 20 Aug 2025 https://discord.com/channels/1087556380724052059/1406599296002035895/1407813498163167345) +* In EQ mode flickers between 0° and 359°. This is also in the main branch. # Sky test log From 5f1e1cc969fb1351f11875f67ceb312a9e541f2b Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Mon, 22 Sep 2025 20:46:13 +0100 Subject: [PATCH 204/253] Remove scipy spatial rotation package import - no longer needed for Euler angles --- python/PiFinder/imu_pi.py | 1 - 1 file changed, 1 deletion(-) diff --git a/python/PiFinder/imu_pi.py b/python/PiFinder/imu_pi.py index 76c060b00..8385ca752 100644 --- a/python/PiFinder/imu_pi.py +++ b/python/PiFinder/imu_pi.py @@ -12,7 +12,6 @@ import logging import numpy as np import quaternion # Numpy quaternion -from scipy.spatial.transform import Rotation logger = logging.getLogger("IMU.pi") From dba10b1b333fe6ba2c70617c13636118c056ff46 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Mon, 22 Sep 2025 20:48:42 +0100 Subject: [PATCH 205/253] Nox format --- python/PiFinder/calc_utils.py | 2 +- python/PiFinder/camera_interface.py | 4 +- python/PiFinder/camera_pi.py | 25 ++++++------ python/PiFinder/integrator.py | 39 +++++++++++++------ .../PiFinder/pointing_model/astro_coords.py | 6 +-- 5 files changed, 46 insertions(+), 30 deletions(-) diff --git a/python/PiFinder/calc_utils.py b/python/PiFinder/calc_utils.py index e5b99ad60..b6df6b3b0 100644 --- a/python/PiFinder/calc_utils.py +++ b/python/PiFinder/calc_utils.py @@ -172,7 +172,7 @@ def aim_degrees(shared_state, mount_type, screen_direction, target): dec_diff = target.dec - solution["Dec"] dec_diff = (dec_diff + 180) % 360 - 180 - + return ra_diff, dec_diff return None, None diff --git a/python/PiFinder/camera_interface.py b/python/PiFinder/camera_interface.py index 96a108b9d..b2e0e840b 100644 --- a/python/PiFinder/camera_interface.py +++ b/python/PiFinder/camera_interface.py @@ -128,7 +128,9 @@ def get_image_loop( "exposure_start": image_start_time, "exposure_end": image_end_time, "imu": imu_end, - "imu_delta": np.rad2deg(pointing_diff), # Pointing chiange during exposure in degrees + "imu_delta": np.rad2deg( + pointing_diff + ), # Pointing chiange during exposure in degrees } ) diff --git a/python/PiFinder/camera_pi.py b/python/PiFinder/camera_pi.py index 855362e1d..37ef23e89 100644 --- a/python/PiFinder/camera_pi.py +++ b/python/PiFinder/camera_pi.py @@ -31,8 +31,8 @@ def __init__(self, exposure_time) -> None: self.exposure_time = exposure_time self.format = "SRGGB12" self.bit_depth = 12 - self.digital_gain = 1.0 # TODO: find optimum value for imx296 and imx290 - self.offset = 0 # TODO: measure offset for imx296 and imx290 + self.digital_gain = 1.0 # TODO: find optimum value for imx296 and imx290 + self.offset = 0 # TODO: measure offset for imx296 and imx290 # Figure out camera type, hq or imx296 (global shutter) if "imx296" in self.camera.camera.id: @@ -52,9 +52,13 @@ def __init__(self, exposure_time) -> None: self.camera_type = "hq" # using this smaller scale auto-selects binning on the sensor self.raw_size = (2028, 1520) - self.gain = 22 # cedar uses this value - self.digital_gain = 13.0 # initial tests show that higher values don't help much - self.offset = 256 # measured with lens cap on, matches what the internet says + self.gain = 22 # cedar uses this value + self.digital_gain = ( + 13.0 # initial tests show that higher values don't help much + ) + self.offset = ( + 256 # measured with lens cap on, matches what the internet says + ) else: raise Exception(f"Unknown camera type: {self.camera.camera.id}") @@ -65,13 +69,8 @@ def initialize(self) -> None: """Initializes the camera and set the needed control parameters""" self.stop_camera() cam_config = self.camera.create_still_configuration( - { - "size": (512, 512) - }, - raw={ - "size": self.raw_size, - "format": self.format - }, + {"size": (512, 512)}, + raw={"size": self.raw_size, "format": self.format}, ) self.camera.configure(cam_config) self.camera.set_controls({"AeEnable": False}) @@ -98,7 +97,7 @@ def capture(self) -> Image.Image: raw_capture = _request.make_array("raw").copy().view(np.uint16) # tmp_image = _request.make_image("main") _request.release() - # crop to square + # crop to square if self.camera_type == "imx296": raw_capture = raw_capture[:, 184:-184] # Sensor orientation is different diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index d16173d2c..ef79f4f07 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -87,9 +87,9 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa # Try to set date and time location = shared_state.location() dt = shared_state.datetime() - # Set location for roll and altaz calculations. - # TODO: Is itnecessary to set location? - # TODO: Altaz doesn't seem to be required for catalogs when in + # Set location for roll and altaz calculations. + # TODO: Is itnecessary to set location? + # TODO: Altaz doesn't seem to be required for catalogs when in # EQ mode? Could be disabled in future when in EQ mode? calc_utils.sf_utils.set_location( location.lat, location.lon, location.altitude @@ -201,17 +201,25 @@ def update_imu( logger.debug( "Track using IMU: Angle moved since last_image_solve = " "{:}(> threshold = {:}) | IMU quat = ({:}, {:}, {:}, {:})".format( - np.rad2deg(angle_moved), np.rad2deg(IMU_MOVED_ANG_THRESHOLD), - q_x2imu.w, q_x2imu.x, q_x2imu.y, q_x2imu.z) + np.rad2deg(angle_moved), + np.rad2deg(IMU_MOVED_ANG_THRESHOLD), + q_x2imu.w, + q_x2imu.x, + q_x2imu.y, + q_x2imu.z, ) + ) # Dead-reckoning using IMU imu_dead_reckoning.update_imu(q_x2imu) # Latest IMU measurement # Store current camera pointing estimate: cam_eq = imu_dead_reckoning.get_cam_radec() - (solved["camera_center"]["RA"], solved["camera_center"]["Dec"], - solved["camera_center"]["Roll"]) = cam_eq.get_deg(use_none=True) + ( + solved["camera_center"]["RA"], + solved["camera_center"]["Dec"], + solved["camera_center"]["Roll"], + ) = cam_eq.get_deg(use_none=True) # Store the current scope pointing estimate scope_eq = imu_dead_reckoning.get_scope_radec() @@ -221,11 +229,18 @@ def update_imu( solved["solve_source"] = "IMU" # Logging for states updated in solved: - logger.debug("IMU update: scope: RA: {:}, Dec: {:}, Roll: {:}".format( - solved["RA"], solved["Dec"], solved["Roll"])) - logger.debug("IMU update: camera_center: RA: {:}, Dec: {:}, Roll: {:}".format( - solved["camera_center"]["RA"], solved["camera_center"]["Dec"], - solved["camera_center"]["Roll"])) + logger.debug( + "IMU update: scope: RA: {:}, Dec: {:}, Roll: {:}".format( + solved["RA"], solved["Dec"], solved["Roll"] + ) + ) + logger.debug( + "IMU update: camera_center: RA: {:}, Dec: {:}, Roll: {:}".format( + solved["camera_center"]["RA"], + solved["camera_center"]["Dec"], + solved["camera_center"]["Roll"], + ) + ) def get_roll_by_mount_type( diff --git a/python/PiFinder/pointing_model/astro_coords.py b/python/PiFinder/pointing_model/astro_coords.py index da6720e8f..c2fb8997a 100644 --- a/python/PiFinder/pointing_model/astro_coords.py +++ b/python/PiFinder/pointing_model/astro_coords.py @@ -62,7 +62,7 @@ def set_from_quaternion(self, q_eq: quaternion.quaternion): """ # Pure quaternion along camera boresight pz_frame = q_eq * quaternion.quaternion(0, 0, 0, 1) * q_eq.conj() - + # Calculate RA, Dec from the camera boresight: dec = np.arcsin(pz_frame.z) ra = np.arctan2(pz_frame.y, pz_frame.x) @@ -129,7 +129,7 @@ def initialized_solved_dict() -> dict: # "Alt" and "Az" could be removed once we move to Eq-based dead-reckoning solved = { # RA, Dec, Roll of the scope at the target pixel - "RA": None, + "RA": None, "Dec": None, "Roll": None, # RA, Dec, Roll solved at the center of the camera FoV @@ -142,7 +142,7 @@ def initialized_solved_dict() -> dict: "Az": None, }, # RA, Dec, Roll from the camera, not updated by IMU in integrator - "camera_solve": { + "camera_solve": { "RA": None, "Dec": None, "Roll": None, From 4ad6f5bdecdb10c1a2f298a99bcabbf2b42b329a Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Mon, 22 Sep 2025 20:48:55 +0100 Subject: [PATCH 206/253] Nox format for changes merged from main --- python/PiFinder/keyboard_local.py | 15 ++++++++------- 1 file changed, 8 insertions(+), 7 deletions(-) diff --git a/python/PiFinder/keyboard_local.py b/python/PiFinder/keyboard_local.py index 81c08a5f3..1a418501d 100644 --- a/python/PiFinder/keyboard_local.py +++ b/python/PiFinder/keyboard_local.py @@ -7,26 +7,27 @@ class KeyboardLocal(KeyboardInterface): - '''' + """' Keyboard used with `python -m PiFinder.main -k local` - PyHotKey does not support key combinations, so we map single keys to combination of button presses here. + PyHotKey does not support key combinations, so we map single keys to combination of button presses here. In addition to the arrow keys (LEFT, UP, DOWN, RIGHT), the following keys are mapped on an english keyboard layout: (Note that in other locales, the position of the keys may differ, but the meaning is the same) - + 0 1 2 3 4 5 6 7 8 9 <-- number keys q w e r . . . i . . - a s d f g . j k l + a s d f g . j k l z . . . . . m . . . ^ ^ ^^^^^^^^ ^ ^^^^^^- j=LNG_LEFT, i=LNG_UP, k=LNG_DOWN, l=LNG_RIGHT | | | + m = LNG_SQUARE - | | + e = ALT+0; d=ALT+LEFT, r=ALT+UP, f=ALT+DOWN, g=ALT+RIGHT + | | + e = ALT+0; d=ALT+LEFT, r=ALT+UP, f=ALT+DOWN, g=ALT+RIGHT | + w=ALT+PLUS, s=ALT+MINUS + q=PLUS, a=MINUS, z=SQUARE - Note: ALT_ means that SQUARE+ is pressed. - ''' + Note: ALT_ means that SQUARE+ is pressed. + """ + def __init__(self, q): try: from PyHotKey import Key, keyboard From cc7b008ea9ffd65409d510f6ac7983661a63e89c Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Mon, 22 Sep 2025 20:54:41 +0100 Subject: [PATCH 207/253] Nox format --- python/PiFinder/pointing_model/imu_dead_reckoning.py | 5 +---- 1 file changed, 1 insertion(+), 4 deletions(-) diff --git a/python/PiFinder/pointing_model/imu_dead_reckoning.py b/python/PiFinder/pointing_model/imu_dead_reckoning.py index 3d082c001..30e3ced26 100644 --- a/python/PiFinder/pointing_model/imu_dead_reckoning.py +++ b/python/PiFinder/pointing_model/imu_dead_reckoning.py @@ -67,10 +67,7 @@ def __init__(self, screen_direction: str): # IMU-to-camera orientation. Fixed by PiFinder type self._set_screen_direction(screen_direction) - def set_alignment( - self, - solved_cam: RaDecRoll, - solved_scope: RaDecRoll): + def set_alignment(self, solved_cam: RaDecRoll, solved_scope: RaDecRoll): """ Set the alignment between the PiFinder camera center and the scope pointing. From 76adc31e6d26ca2b10eb1e3df031c3e7f8656255 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 28 Sep 2025 00:18:21 +0100 Subject: [PATCH 208/253] Change requirements.txt numpy=1.26.2 --> numpy=1.26.4 preferred by numpy-quaternion --- python/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/python/requirements.txt b/python/requirements.txt index c4aace437..2fa71abcf 100644 --- a/python/requirements.txt +++ b/python/requirements.txt @@ -9,7 +9,7 @@ json5==0.9.25 luma.oled==3.12.0 luma.lcd==2.11.0 pillow==10.4.0 -numpy==1.26.2 +numpy==1.26.4 numpy-quaternion==2023.0.4 pandas==1.5.3 pydeepskylog==1.3.2 From 1cdf87bfc06e3b98d72703d3957ed34e836706fd Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 28 Sep 2025 16:18:50 +0100 Subject: [PATCH 209/253] Update README - remove parts that are no longer relevant (virtual env, horiz frame, etc) --- python/PiFinder/pointing_model/README.md | 202 +++++++++-------------- 1 file changed, 74 insertions(+), 128 deletions(-) diff --git a/python/PiFinder/pointing_model/README.md b/python/PiFinder/pointing_model/README.md index 8909e0a44..fc3435fde 100644 --- a/python/PiFinder/pointing_model/README.md +++ b/python/PiFinder/pointing_model/README.md @@ -10,20 +10,17 @@ README: IMU support prototyping See Discord thread: https://discord.com/channels/1087556380724052059/1406599296002035895 Issues: -* Issue in the default requirements? Error (not related to the IMU changes) - when I try to create a new env using requirements.txt. Maybe I can't just - create a new environment using pip? +* Fails nox TODO: +* Sky test + +For future: +* Update imu_pi.py * Set alignment once at alignment rather than calculating it every loop * Alignment is currently done in `integrator.py` where `set_alignment()` is called every iteration of the loop. Would like to set the alignment onece to pre-compute the `q_scope2cam` quaternion, etc. -* Discuss requirements.txt with Richard - * It needs numpy quaternion. Can this just be added to the requirements.txt? - -Later: -* Update imu_pi.py Done: * Support other PiFinder types @@ -35,6 +32,12 @@ Done: * Doesn't pass Nox * Doesn't run wih v3 Flat. Issue in main branch? (reported by grimaldi: 20 Aug 2025 https://discord.com/channels/1087556380724052059/1406599296002035895/1407813498163167345) * In EQ mode flickers between 0° and 359°. This is also in the main branch. +* Issue in the default requirements? Error (not related to the IMU changes) + when I try to create a new env using requirements.txt. Maybe I can't just + create a new environment using pip? +* Clean up README + * Remove instruction on venv + * Remove descriptions of frames # Sky test log @@ -73,63 +76,14 @@ Done: ## Install additional packages -This branch needs the `numpy.quaternion` package. For desktop-testing, you -could install it in a virtual environment. For field-testing, it's more -practical to install it as default. - -### Create a virtual environment - -Skip this section if you want to install the packages as default. +This branch needs the `numpy.quaternion` package. To do this, run +`pifinder_post_update.sh`, which will install the new package and updage +`numpy`. -This step creates a virtual environment using `venv`. Connect to the PiFinder using `ssh` and install venv to create a virtual environment: - -```bash -sudo apt-get install python3-venv -``` - -Still on the PiFinder, create a virtual environment called `.venv_imu`. Note -that the virtual environment is created in the home directory because `venv` -creates the environment folder `.venv_imu\` where you run this command. - -```bash -cd ~ -python3 -m venv .venv_imu -``` - -Type this to activate the environment: - -```bash -source .venv_imu/bin/activate -``` - -Follow the next step to install the packages in the virtual environmnet. - -At the end, it can be de-activated by typing: - -```bash -deactivate -``` - -### Install the packages - -Update `pip`: - -```bash -pip install --upgrade pip -``` - -Ensure that you're in new virtual environment and install the Python packages using `pip`. - -```bash -cd PiFinder/python -pip install -r requirements.txt -pip install -r requirements_dev.txt -``` - -The last line installs the additional packages required (just `numpy-quaternion`). PiFinder can be -run from the command line as usual: +PiFinder can be run from the command line as usual: ```bash +cd ~/PiFinder/python python3 -m PiFinder.main ``` @@ -192,17 +146,10 @@ $$q_{new} = q_1 q_0$$ ## Coordinate frames -### Home positions - -For an altaz mount, we define the *home position* as az=0°, alt=0°. i.e. the -scope points due North and is horizontal. The $z_{mnt}$ axis of the mount frame -corresponds to the axis of the scope in the *home* position in the ideal case. - ### Coordinate frame definitions We define the following reference frames: - #### Equatorial coordinate system * Centered around the center of the Earth with the $xy$ plane running through the Earths' equator. $+z$ points to the north pole and $+x$ to the Vernal @@ -212,25 +159,10 @@ We define the following reference frames: * Centred around the observer. We will use the convention: * $x$ points South, $y$ to East and $z$ to the zenith. -#### Mount frame (altaz) -* $y$ is defined as the axis of the azimuthal gimbal rotation. $z$ is the cross - product between the altitude and azimuthal gimbal axes and $x = y \times z$. -* For a perfect mount where $y$ points to the zenith and the gimbal axes are - orthogonal, $x$ is the altitude gimbal axis when in the *home position*. -* A perfect system in the *home position*, $x$ points West and $z$ points due - North and horizontal. -* Non-orthogonality between the axes are allowed by for now, we will assume the - orthogonal case for simplicity. - -#### Gimbal frame -* The mount frame rotated around the mount's azimuthal gimbal axes by - $\theta_{az}$ followed by a rotation around the mount's altitude axis by - $\theta_{alt}$. - #### Scope frame * +z is boresight. -* On an altaz mount, we define +y as the vertical direction of the scope and +x as the - horizontal direction to the left when looking along the boresight. +* On an altaz mount, we define +y as the vertical direction of the scope and +x + as the horizontal direction to the left when looking along the boresight. * In the ideal case, the Scope frame is assumed to be the same as the Gimbal frame. In reality, there may be errors due to mounting or gravity. @@ -242,7 +174,8 @@ We define the following reference frames: #### IMU frame * The IMU frame is the local coordinates that the IMU outputs the data in. -* The diagram below illustrates the IMU coordinate frame for the v2 PiFinder with the Adafruit BNO055 IMU. +* The diagram below illustrates the IMU coordinate frame for the v2 PiFinder + with the Adafruit BNO055 IMU. ### IMU and camera coordinate frames @@ -265,26 +198,19 @@ tracking error between the plate solved coordinates and the IMU dead-reckoning. The roll (as given by Tetra3) is defined as the rotation of the north pole relative to the camera image's "up" direction ($+y$). A positive roll angle means that the pole is counter-clockwise from image "up" (i.e. towards West). -The roll offset is defined as - -``` -roll_offset = camera_roll - expected_camera_roll -``` - -The `expected_camera_roll` is the roll at the camera center given its -plate-solved RA and Dec for a camera on a perfect horizontal mount (i.e. the -"up" $+y$ direction of the camera always points to the zenith). The camera pose -is rotated by the angle `roll_offset` around its boresight. ### Telescope coordinate transformations -We can use quaternions to rotate between the coordinate frames. -For example, the quaternion `q_horiz2mnt` rotates the Horizontal frame to the -Mount frame. The quaternions can be multiplied to apply successive *intrinsic* -rotation from the Horizontal frame to the Camera frame; +We will use quaternions to describe rotations. In our convention, the +orientation of the camera frame in equatorial frame is written as `q_eq2cam`. +This is the rotation from the EQ frame's origin to the camera frame. We can +also write the rotation from the camera frame to the scope frame as +`q_cam2scope`. The two quaternions can be multiplied to describe the equitorial +coordinates of the scope pointing by + ```python -q_horiz2camera = q_horiz2mnt * q_mnt2gimb * q_gimb2scope * q_scope2camera +q_eq2cam * q_cam2scope = q_eq2scope ``` Note that this convention makes it clear when applying intrinsic rotations (right-multiply). @@ -296,42 +222,59 @@ control to move the scope. ## Coordinate frame transformation -We will use the equatorial frame as the reference frame. The goal is determine the scope pointing in RA and Dec. The pointing of the scope relative to the equatorial frame can be described by quaternion $q_{eq2scope}$. +We will use the equatorial frame as the reference frame. The goal is determine +the scope pointing in RA and Dec. The pointing of the scope relative to the +equatorial frame can be described by quaternion $q_{eq2scope}$. -The PiFinder uses the coordinates from plate-solving but this is at a low rate and plate-solving may not succeed when the scope is moving so the IMU measurements can be used to infer the pointing between plate-solving by dead-reckoning. +The PiFinder uses the coordinates from plate-solving but this is at a low rate +and plate-solving may not succeed when the scope is moving so the IMU +measurements can be used to infer the pointing between plate-solving by +dead-reckoning. ### Plate solving -Plate-solving returns the pointing of the PiFinder camera in (RA, Dec, Roll) coordinates. The quaternion rotation of the camera pointing relative to the equatorial frame for time step $k$ is given by $q_{eq2cam}(k)$ and the scope pointing is give by, +Plate-solving returns the pointing of the PiFinder camera in (RA, Dec, Roll) +coordinates. The quaternion rotation of the camera pointing relative to the +equatorial frame for time step $k$ is given by $q_{eq2cam}(k)$ and the scope +pointing is give by, -$$q_{hor2scope}(k) = q_{hor2cam}(k) \; q_{cam2scope}$$ +$$q_{eq2scope}(k) = q_{eq2cam}(k) \; q_{cam2scope}$$ -We use the PiFinder's camera frame as the reference because plate solving is done relative to the -camera frame. $q_{cam2scope}$ is the quaternion that represents the alignment offset between the -PiFinder camera frame and the scope frame +We use the PiFinder's camera frame as the reference because plate solving is +done relative to the camera frame. $q_{cam2scope}$ is the quaternion that +represents the alignment offset between the PiFinder camera frame and the scope +frame ### Alignment -The alignment offset between the PiFinder camera frame and the -scope frame is determined during alignment of the PiFinder with the scope and is assumed to be fixed. The goal of alignment is to determine the quaternion $q_{cam2scope}$. +The alignment offset between the PiFinder camera frame and the scope frame is +determined during alignment of the PiFinder with the scope and is assumed to be +fixed. The goal of alignment is to determine the quaternion $q_{cam2scope}$. -During alignment, the user user selects the target seen in the center the scope, which gives the (RA, Dec) of the scope pointing but not the roll. We can assume some arbitrary roll value (say roll = 0) and get $q_{eq2scope}$. At the same time, plate solving measures the (RA, Dec, Roll) at the camera center or $q_{eq2cam}$. We can express the relation by, +During alignment, the user user selects the target seen in the center the +scope, which gives the (RA, Dec) of the scope pointing but not the roll. We can +assume some arbitrary roll value (say roll = 0) and get $q_{eq2scope}$. At the +same time, plate solving measures the (RA, Dec, Roll) at the camera center or +$q_{eq2cam}$. We can express the relation by, $$q_{eq2scope} = q_{eq2cam} \; q_{cam2scope}$$ Rearranging this gives, -$$q_{cam2scope} = q_{hor2cam}^{-1} \; q_{hor2scope}$$ +$$q_{cam2scope} = q_{eq2cam}^{-1} \; q_{eq2scope}$$ Note that for unit quaternions, we can also use the conjugate $q^*$ instead of $q^{-1}$, because the conjugate is slightly faster to compute. -Roll returned by plate-solving is not relevant for pointing and it can be arbitrary but it is needed for full three degrees-of-freedom dead-reckoning by the IMU. +Roll returned by plate-solving is not relevant for pointing and it can be +arbitrary but it is needed for full three degrees-of-freedom dead-reckoning by +the IMU. ### Dead-reckoning -Between plate solving, the IMU extrapolates the scope orientation by dead reckoning. Suppose that we -want to use the IMU measurement at time step $k$ to estimate the scope pointing; +Between plate solving, the IMU extrapolates the scope orientation by dead +reckoning. Suppose that we want to use the IMU measurement at time step $k$ to +estimate the scope pointing; ```python q_eq2scope(k) = q_eq2cam(k-m) * q_cam2imu * q_x2imu(k-m).conj() * q_x2imu(k) * q_imu2cam * q_cam2scope @@ -345,9 +288,10 @@ Where 3. Note that the quaternion `q_x2imu(k-m).conj() * q_x2imu(k)` rotates the IMU body from the orientation in the last solve (at time step `k-m`) to to the current orientation (at time step `k`). -4. `q_cam2imu = q_imu2cam.conj()` is the alignment of the IMU to the camera and depends on the -PiFinder configuration. There will be some error due to mechanical tolerances which will propagate -to the pointing error when using the IMU. +4. `q_cam2imu = q_imu2cam.conj()` is the alignment of the IMU to the camera and +depends on the PiFinder configuration. There will be some error due to +mechanical tolerances which will propagate to the pointing error when using the +IMU. We can pre-compute the first three terms after plate solving at time step `k-m`, which corresponds to the quaternion rotation from the `eq` frame to the @@ -359,17 +303,18 @@ q_eq2x(k-m) = q_eq2cam(k-m) * q_cam2imu * q_x2imu(k-m).conj() ## Potential future improvements -A potential next step could be to use a Kalman filter framework to estimate the pointing. Some of -the benefits are: +A potential next step could be to use a Kalman filter framework to estimate the +pointing. Some of the benefits are: * Smoother, filtered pointing estimate. -* Improves the accuracy of the pointing estimate. Accuracy may be more beneficial when using the - PiFinder estimate to control driven mounts. +* Improves the accuracy of the pointing estimate. Accuracy may be more + beneficial when using the PiFinder estimate to control driven mounts. * Potentially enable any generic IMU (with gyro and accelerometer) to be used without internal fusion FW, which tends to add to the BOM cost. -* If required, could take fewer plate-solving frames by only triggering a plate solve when the -uncertainty of the Kalman filter estimate based on IMU dead-reckoning exceeds some limit. This can -reduce power consumption and allow for a cheaper, less powerful computing platform to be used. +* If required, could take fewer plate-solving frames by only triggering a plate +solve when the uncertainty of the Kalman filter estimate based on IMU +dead-reckoning exceeds some limit. This can reduce power consumption and allow +for a cheaper, less powerful computing platform to be used. The accuracy improvement will likely come from the following sources: @@ -378,5 +323,6 @@ The accuracy improvement will likely come from the following sources: calibration will be done in conjunction with the plate-solved measurements so it will be better than an IMU-only calibration. * The orientation of the IMU to the camera frame, $q_{imu2cam}$, has errors -because of mechanical tolerances. The Kalman filter will calibrate for this online. -This will improve the accuracy and enable other non-standard form-factors. +because of mechanical tolerances. The Kalman filter will calibrate for this +online. This will improve the accuracy and enable other non-standard +form-factors. From 82299455ae8ff3d86b20646a743c0afff587a60b Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Wed, 1 Oct 2025 08:13:53 +0100 Subject: [PATCH 210/253] Change np.quaternion --> quaternion.quaternion so that it passes Nox type checking --- python/PiFinder/imu_pi.py | 2 +- python/PiFinder/pointing_model/README.md | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/python/PiFinder/imu_pi.py b/python/PiFinder/imu_pi.py index 8385ca752..53cb673ff 100644 --- a/python/PiFinder/imu_pi.py +++ b/python/PiFinder/imu_pi.py @@ -147,7 +147,7 @@ def imu_monitor(shared_state, console_queue, log_queue): "moving": False, "move_start": None, "move_end": None, - "quat": np.quaternion( + "quat": quaternion.quaternion( 0, 0, 0, 0 ), # Scalar-first numpy quaternion(w, x, y, z) - Init to invalid quaternion "status": 0, diff --git a/python/PiFinder/pointing_model/README.md b/python/PiFinder/pointing_model/README.md index fc3435fde..38c11cab2 100644 --- a/python/PiFinder/pointing_model/README.md +++ b/python/PiFinder/pointing_model/README.md @@ -125,7 +125,7 @@ $\mathbf{p^\prime} = \mathbf{qpq}^{-1}$ In Numpy Quaternion, we can create a quaternion using ```python -q = np.quaternion(w, x, y, z) +q = quaternion.quaternion(w, x, y, z) ``` Quaternion multiplications are simply `q1 * q2`. From c6422247a2a3f0755f4e48c1c24e4af279664e91 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Wed, 1 Oct 2025 12:04:37 +0200 Subject: [PATCH 211/253] Remove imu_print_measurements.py -- used for debugging --- .../pointing_model/imu_print_measurements.py | 178 ------------------ 1 file changed, 178 deletions(-) delete mode 100644 python/PiFinder/pointing_model/imu_print_measurements.py diff --git a/python/PiFinder/pointing_model/imu_print_measurements.py b/python/PiFinder/pointing_model/imu_print_measurements.py deleted file mode 100644 index 756fcf032..000000000 --- a/python/PiFinder/pointing_model/imu_print_measurements.py +++ /dev/null @@ -1,178 +0,0 @@ -#!/usr/bin/python -# -*- coding:utf-8 -*- -""" -For testing the IMU: Not for use by PiFinder main loop. -Prints the IMU measurements (based on imu_pi.py) - -TODO: Remove this in the future. -""" - -import time -import board -import adafruit_bno055 -# import logging - -from scipy.spatial.transform import Rotation - -# from PiFinder import config - -# logger = logging.getLogger("IMU.pi") - -QUEUE_LEN = 10 -MOVE_CHECK_LEN = 2 - - -class ImuSimple: - def __init__(self): - i2c = board.I2C() - self.sensor = adafruit_bno055.BNO055_I2C(i2c) - self.sensor.mode = adafruit_bno055.IMUPLUS_MODE - # self.sensor.mode = adafruit_bno055.NDOF_MODE - - # Unlike Imu(), we use the IMU's native orientation - self.quat_history = [(0, 0, 0, 0)] * QUEUE_LEN - self._flip_count = 0 - self.calibration = 0 - self.avg_quat = (0, 0, 0, 0) - self.__moving = False - - self.last_sample_time = time.time() - - # Calibration settings - self.imu_sample_frequency = 1 / 30 - - # First value is delta to exceed between samples - # to start moving, second is threshold to fall below - # to stop moving. - self.__moving_threshold = (0.0005, 0.0003) - - def quat_to_euler(self, quat): - """ - INPUTS: - quat: Scalar last quaternion (x, y, z, w) - - OUTPUTS: - rot_euler: [Az, related_to_roll, Alt] - """ - if quat[0] + quat[1] + quat[2] + quat[3] == 0: - return 0, 0, 0 - rot = Rotation.from_quat(quat) # Expects scalar-last quaternion - # Lowercase 'xyz' indicate extrinsic rotation: - rot_euler = rot.as_euler("xyz", degrees=True) - # convert from -180/180 to 0/360 - rot_euler[0] += 180 - rot_euler[1] += 180 - rot_euler[2] += 180 - return rot_euler - - def moving(self): - """ - Compares most recent reading - with past readings - """ - return self.__moving - - def update(self): - # check for update frequency - if time.time() - self.last_sample_time < self.imu_sample_frequency: - return - - self.last_sample_time = time.time() - - # Throw out non-calibrated data - self.calibration = self.sensor.calibration_status[1] - if self.calibration == 0: - # logger.warning("NOIMU CAL") - return True - # adafruit_bno055 gives quaternion convention (w, x, y, z) - quat = self.sensor.quaternion - if quat[0] is None: - # logger.warning("IMU: Failed to get sensor values") - return - - _quat_diff = [] - for i in range(4): - _quat_diff.append(abs(quat[i] - self.quat_history[-1][i])) - - self.__reading_diff = sum(_quat_diff) - - # This seems to be some sort of defect / side effect - # of the integration system in the BNO055 - # When not moving quat output will vaccilate - # by exactly this amount... so filter this out - if self.__reading_diff == 0.0078125: - self.__reading_diff = 0 - return - - # Sometimes the quat output will 'flip' and change by 2.0+ - # from one reading to another. This is clearly noise or an - # artifact, so filter them out - if self.__reading_diff > 1.5: - self._flip_count += 1 - if self._flip_count > 10: - # with the history initialized to 0,0,0,0 the unit - # can get stuck seeing flips if the IMU starts - # returning data. This count will reset history - # to the current state if it exceeds 10 - self.quat_history = [quat] * QUEUE_LEN - self.__reading_diff = 0 - else: - self.__reading_diff = 0 - return - else: - # no flip - self._flip_count = 0 - - self.avg_quat = quat - if len(self.quat_history) == QUEUE_LEN: - self.quat_history = self.quat_history[1:] - self.quat_history.append(quat) - - if self.__moving: - if self.__reading_diff < self.__moving_threshold[1]: - self.__moving = False - else: - if self.__reading_diff > self.__moving_threshold[0]: - self.__moving = True - - -def imu_monitor(): - # MultiprocLogging.configurer(log_queue) - imu = ImuSimple() - imu_calibrated = False - imu_data = { - "moving": False, - "move_start": None, - "move_end": None, - "quat": [0, 0, 0, 0], # Scalar-first quaternion (w, x, y, z) - "status": 0, - } - - while True: - imu.update() - imu_data["status"] = imu.calibration - if imu.moving(): - if not imu_data["moving"]: - # logger.debug("IMU: move start") - imu_data["moving"] = True - imu_data["move_start"] = time.time() - imu_data["quat"] = imu.avg_quat - - print(imu_data["quat"]) - - else: - if imu_data["moving"]: - # If we were moving and we now stopped - # logger.debug("IMU: move end") - imu_data["moving"] = False - imu_data["quat"] = imu.avg_quat - imu_data["move_end"] = time.time() - - if not imu_calibrated: - if imu_data["status"] == 3: - imu_calibrated = True - # console_queue.put("IMU: NDOF Calibrated!") - - -if __name__ == "__main__": - imu_monitor() From 761653ec6ec1862c03da2f1c67d22822c48b72ac Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Sun, 5 Oct 2025 21:25:29 +0200 Subject: [PATCH 212/253] Sky-tested. Wrote notes in README. --- python/PiFinder/pointing_model/README.md | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/python/PiFinder/pointing_model/README.md b/python/PiFinder/pointing_model/README.md index 38c11cab2..cdb9a1e96 100644 --- a/python/PiFinder/pointing_model/README.md +++ b/python/PiFinder/pointing_model/README.md @@ -43,6 +43,18 @@ Done: >Remove this before release! +## 20251001: c6422 (tested 5 Oct) + +* v2 Flat. Exposure 0.4s. +* Tested in altaz mode. +* 97% full moon. Zenity NELM 3. +* Worked fine. When moved quickly to a target, the IMU mode got it to within +1-2° and then it snapped to the pointing from the plate solve and stayed there. +I didn't see any jiggling of the SkySafari cursor when zoomed in at a scale of +5° FOV. +* Changes since last test: Cleaning up & refactoring. EQ mode angle changed to + +/-. Numpy version updated. + ## 20250831: af358e (tested 5/6 Aug) * Tested on altaz mount in altaz mode. From 040bbd93682ea179fc60a51bf2cb7530fe8d149c Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 5 Oct 2025 21:18:49 +0100 Subject: [PATCH 213/253] Add issue to README --- python/PiFinder/pointing_model/README.md | 3 +++ 1 file changed, 3 insertions(+) diff --git a/python/PiFinder/pointing_model/README.md b/python/PiFinder/pointing_model/README.md index cdb9a1e96..c1b35a33e 100644 --- a/python/PiFinder/pointing_model/README.md +++ b/python/PiFinder/pointing_model/README.md @@ -11,6 +11,9 @@ See Discord thread: https://discord.com/channels/1087556380724052059/14065992960 Issues: * Fails nox +* When in "Chart Mode", alt/az seems to be swapped round. OK in Align mode. Is +it the way the fake IMU is generated? Does it try to account for the IMU +orientation which is removed in imu_pi.py? TODO: * Sky test From 084bc4a053dbef63a44355968b4a62e2b6fab512 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 5 Oct 2025 21:20:37 +0100 Subject: [PATCH 214/253] Fix typo in pyproject.toml --> Should pass nox --- python/pyproject.toml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/python/pyproject.toml b/python/pyproject.toml index 6f9340e7f..fe871ce19 100644 --- a/python/pyproject.toml +++ b/python/pyproject.toml @@ -128,7 +128,7 @@ module = [ 'sklearn.*', 'PyHotKey.*', 'PiFinder.tetra3.*', - 'quaterion', + 'quaternion', 'tetra3.*', 'grpc', 'ceder_detect_pb2', From fae4033677a73118d438b82237d88e57ee88389f Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Sun, 5 Oct 2025 22:39:07 +0200 Subject: [PATCH 215/253] Fix: adapt to changes in imu_pi.py from merging main --- python/PiFinder/imu_pi.py | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/python/PiFinder/imu_pi.py b/python/PiFinder/imu_pi.py index 6424489d5..4d5b52a48 100644 --- a/python/PiFinder/imu_pi.py +++ b/python/PiFinder/imu_pi.py @@ -6,6 +6,7 @@ """ import time +from PiFinder import config from PiFinder.multiproclogging import MultiprocLogging import board import adafruit_bno055 @@ -46,8 +47,13 @@ def __init__(self): # First value is delta to exceed between samples # to start moving, second is threshold to fall below # to stop moving. - self.__moving_threshold = (0.0005, 0.0003) + cfg = config.Config() + imu_threshold_scale = cfg.get_option("imu_threshold_scale", 1) + self.__moving_threshold = ( + 0.0005 * imu_threshold_scale, + 0.0003 * imu_threshold_scale, + ) def moving(self): """ Compares most recent reading From ce12196c9a6617efe0eec96b891b66350f5d257d Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sun, 5 Oct 2025 21:48:56 +0100 Subject: [PATCH 216/253] Add details to issue in README --- python/PiFinder/pointing_model/README.md | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/python/PiFinder/pointing_model/README.md b/python/PiFinder/pointing_model/README.md index c1b35a33e..032c03a02 100644 --- a/python/PiFinder/pointing_model/README.md +++ b/python/PiFinder/pointing_model/README.md @@ -11,9 +11,11 @@ See Discord thread: https://discord.com/channels/1087556380724052059/14065992960 Issues: * Fails nox -* When in "Chart Mode", alt/az seems to be swapped round. OK in Align mode. Is -it the way the fake IMU is generated? Does it try to account for the IMU -orientation which is removed in imu_pi.py? +* Chart orientation: Under TestMode for desktop testing, When in "Chart Mode", +alt/az seems to be swapped round. Looks OK in Align mode at first sight but +this is because the chart is oriented 90-degrees around . Is it the way the +fake IMU is generated? Does it try to account for the IMU orientation which is +removed in imu_pi.py? Also check "Chart Mode" when sky testing. TODO: * Sky test From 398e538090316e5d72e927f660a6f8817d8d48c1 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Mon, 20 Oct 2025 22:46:54 +0200 Subject: [PATCH 217/253] Fix README --- python/PiFinder/pointing_model/README.md | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/python/PiFinder/pointing_model/README.md b/python/PiFinder/pointing_model/README.md index 032c03a02..fea622b65 100644 --- a/python/PiFinder/pointing_model/README.md +++ b/python/PiFinder/pointing_model/README.md @@ -268,11 +268,11 @@ The alignment offset between the PiFinder camera frame and the scope frame is determined during alignment of the PiFinder with the scope and is assumed to be fixed. The goal of alignment is to determine the quaternion $q_{cam2scope}$. -During alignment, the user user selects the target seen in the center the -scope, which gives the (RA, Dec) of the scope pointing but not the roll. We can -assume some arbitrary roll value (say roll = 0) and get $q_{eq2scope}$. At the -same time, plate solving measures the (RA, Dec, Roll) at the camera center or -$q_{eq2cam}$. We can express the relation by, +During alignment, the user user selects the target seen in the center of the +eyepiece, which gives the (RA, Dec) of the scope pointing but not the roll. We +can assume some arbitrary roll value (say roll = 0) and get $q_{eq2scope}$. At +the same time, plate solving measures the (RA, Dec, Roll) at the camera center +or $q_{eq2cam}$. We can express the relation by, $$q_{eq2scope} = q_{eq2cam} \; q_{cam2scope}$$ From 7519b7dc5c5dfa435b0b09378f595bedbcbca8d2 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Tue, 21 Oct 2025 21:38:24 +0200 Subject: [PATCH 218/253] Edit README --- python/PiFinder/pointing_model/README.md | 23 +++-------------------- 1 file changed, 3 insertions(+), 20 deletions(-) diff --git a/python/PiFinder/pointing_model/README.md b/python/PiFinder/pointing_model/README.md index fea622b65..f13fa2f74 100644 --- a/python/PiFinder/pointing_model/README.md +++ b/python/PiFinder/pointing_model/README.md @@ -9,25 +9,14 @@ README: IMU support prototyping See Discord thread: https://discord.com/channels/1087556380724052059/1406599296002035895 -Issues: -* Fails nox -* Chart orientation: Under TestMode for desktop testing, When in "Chart Mode", -alt/az seems to be swapped round. Looks OK in Align mode at first sight but -this is because the chart is oriented 90-degrees around . Is it the way the -fake IMU is generated? Does it try to account for the IMU orientation which is -removed in imu_pi.py? Also check "Chart Mode" when sky testing. - -TODO: -* Sky test For future: +* Calibration to align IMU frame to camera frame to remove the residual error. * Update imu_pi.py -* Set alignment once at alignment rather than calculating it every loop - * Alignment is currently done in `integrator.py` where `set_alignment()` is - called every iteration of the loop. Would like to set the alignment onece - to pre-compute the `q_scope2cam` quaternion, etc. +* Set alignment once at alignment rather than calculating it every loop? Done: +* Fails nox * Support other PiFinder types * Adjust Roll depending on mount_type for charts * Lint @@ -104,12 +93,6 @@ cd ~/PiFinder/python python3 -m PiFinder.main ``` -For testing, running the following command will dump the raw IMU measurements to the terminal: - -```bash -python PiFinder/imu_print_measurements.py -``` - # Theory ## Quaternion rotation From 4276701eed31204f17394b13a1897f091a28ae35 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Sat, 25 Oct 2025 00:08:08 +0200 Subject: [PATCH 219/253] Add test notes to README --- python/PiFinder/pointing_model/README.md | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/python/PiFinder/pointing_model/README.md b/python/PiFinder/pointing_model/README.md index f13fa2f74..439866561 100644 --- a/python/PiFinder/pointing_model/README.md +++ b/python/PiFinder/pointing_model/README.md @@ -37,6 +37,14 @@ Done: >Remove this before release! +## 20251021: 7519b (tested 24 Oct) + +* v2 Flat. +* Pointings in RA, Dec were OK but in Chart mode, the chart rotated 180 degrees as I +crossed to the East of around Mirfak in Perseus with the result that slewing to the +East showed up as moving to the right. +* Brickbots tested Right version got strange estimates like the axes were swapped around. + ## 20251001: c6422 (tested 5 Oct) * v2 Flat. Exposure 0.4s. From 2b8d178c9dd4c4de660aa7233cfcfc211e058ffa Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Sat, 25 Oct 2025 00:09:29 +0200 Subject: [PATCH 220/253] Formatting --- python/PiFinder/pointing_model/README.md | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/python/PiFinder/pointing_model/README.md b/python/PiFinder/pointing_model/README.md index 439866561..ec119e903 100644 --- a/python/PiFinder/pointing_model/README.md +++ b/python/PiFinder/pointing_model/README.md @@ -40,10 +40,11 @@ Done: ## 20251021: 7519b (tested 24 Oct) * v2 Flat. -* Pointings in RA, Dec were OK but in Chart mode, the chart rotated 180 degrees as I -crossed to the East of around Mirfak in Perseus with the result that slewing to the -East showed up as moving to the right. -* Brickbots tested Right version got strange estimates like the axes were swapped around. +* Pointings in RA, Dec were OK but in Chart mode, the chart rotated 180 degrees +as I crossed to the East of around Mirfak in Perseus with the result that +slewing to the East showed up as moving to the right. +* Brickbots tested Right version got strange estimates like the axes were + swapped around. ## 20251001: c6422 (tested 5 Oct) From 6f7e17b7b1b652da41ddf8d1687bb1bc80436717 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Sat, 25 Oct 2025 00:21:28 +0200 Subject: [PATCH 221/253] Fixed q_imu2cam for 'right' --- python/PiFinder/pointing_model/imu_dead_reckoning.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/python/PiFinder/pointing_model/imu_dead_reckoning.py b/python/PiFinder/pointing_model/imu_dead_reckoning.py index 30e3ced26..1cfedd335 100644 --- a/python/PiFinder/pointing_model/imu_dead_reckoning.py +++ b/python/PiFinder/pointing_model/imu_dead_reckoning.py @@ -197,10 +197,10 @@ def get_screen_direction_q_imu2cam(screen_direction: str) -> quaternion.quaterni q_imu2cam = (q1 * q2).normalized() elif screen_direction == "right": # Right: - # Rotate -90° around y_imu so that z_imu' points along z_camera - q1 = qt.axis_angle2quat([0, 1, 0], np.pi / 2) + # Rotate -90° around x_imu so that z_imu' points along z_camera + q1 = qt.axis_angle2quat([1, 0, 0], -np.pi / 2) # Rotate 90° around z_imu' to align with the camera cooridnates - q2 = qt.axis_angle2quat([0, 0, 1], -np.pi / 2) + q2 = qt.axis_angle2quat([0, 0, 1], np.pi / 2) q_imu2cam = (q1 * q2).normalized() elif screen_direction == "straight": # Straight: From 808ddb74c4daefc48c27c15770fc5f0c2a720bd1 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Sat, 25 Oct 2025 12:16:55 +0200 Subject: [PATCH 222/253] Fix rotation q_imu2cam for the "straight" type --- python/PiFinder/pointing_model/imu_dead_reckoning.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/python/PiFinder/pointing_model/imu_dead_reckoning.py b/python/PiFinder/pointing_model/imu_dead_reckoning.py index 1cfedd335..cd6de755f 100644 --- a/python/PiFinder/pointing_model/imu_dead_reckoning.py +++ b/python/PiFinder/pointing_model/imu_dead_reckoning.py @@ -205,13 +205,13 @@ def get_screen_direction_q_imu2cam(screen_direction: str) -> quaternion.quaterni elif screen_direction == "straight": # Straight: # Rotate 180° around y_imu so that z_imu' points along z_camera - q1 = qt.axis_angle2quat([0, 1, 0], np.pi / 2) + q1 = qt.axis_angle2quat([0, 1, 0], np.pi) # Rotate -90° around z_imu' to align with the camera cooridnates q2 = qt.axis_angle2quat([0, 0, 1], -np.pi / 2) q_imu2cam = (q1 * q2).normalized() elif screen_direction == "flat3": # Flat v3: - # Camera is tilted a further 30° compared to Flat v2 + # Camera is tilted 30° further down from the screen compared to Flat v2 # Rotate -120° around y_imu so that z_imu' points along z_camera q1 = qt.axis_angle2quat([0, 1, 0], -np.pi * 2 / 3) # Rotate -90° around z_imu' to align with the camera cooridnates From 3af5d570af6980d161472595048655d757c9a681 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Sat, 25 Oct 2025 12:43:47 +0200 Subject: [PATCH 223/253] Fix typo in comment --- python/PiFinder/camera_interface.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/python/PiFinder/camera_interface.py b/python/PiFinder/camera_interface.py index 3dad52656..073b94fc2 100644 --- a/python/PiFinder/camera_interface.py +++ b/python/PiFinder/camera_interface.py @@ -132,7 +132,7 @@ def get_image_loop( "imu": imu_end, "imu_delta": np.rad2deg( pointing_diff - ), # Pointing chiange during exposure in degrees + ), # Pointing change during exposure in degrees } ) From 1ced258435cc62abc765fc12fb5ab348b42657cb Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Thu, 30 Oct 2025 22:26:34 +0100 Subject: [PATCH 224/253] Remove TODO in comments that's done --- python/PiFinder/pointing_model/astro_coords.py | 5 +---- 1 file changed, 1 insertion(+), 4 deletions(-) diff --git a/python/PiFinder/pointing_model/astro_coords.py b/python/PiFinder/pointing_model/astro_coords.py index c2fb8997a..a33e383a2 100644 --- a/python/PiFinder/pointing_model/astro_coords.py +++ b/python/PiFinder/pointing_model/astro_coords.py @@ -121,12 +121,9 @@ def initialized_solved_dict() -> dict: Returns an initialized 'solved' dictionary with cooridnate and other information. - TODO: The solved dict is used by other components. Move this func - and use this elsewhere (e.g. solver.py) to enforce consistency. TODO: use RaDecRoll class for the RA, Dec, Roll coordinates here? + TODO: "Alt" and "Az" could be removed but seems to be required by catalogs? """ - # TODO: This dict is duplicated in solver.py - Refactor? - # "Alt" and "Az" could be removed once we move to Eq-based dead-reckoning solved = { # RA, Dec, Roll of the scope at the target pixel "RA": None, From b8e09ff65a64b6fda1dda72567fee171634f2ec5 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Thu, 30 Oct 2025 23:06:20 +0100 Subject: [PATCH 225/253] Update comments --- python/PiFinder/integrator.py | 13 +++++++------ python/PiFinder/pointing_model/astro_coords.py | 9 +++++---- 2 files changed, 12 insertions(+), 10 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index ef79f4f07..b49026279 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -251,7 +251,8 @@ def get_roll_by_mount_type( is displayed appropriately for the mount type. The RA and Dec of the target should be provided (in degrees). - * Alt/Az mount: Display the chart in the horizontal coordinate so the + * Alt/Az mount: Display the chart in the horizontal coordinate so that up + in the chart points to the Zenith. * EQ mount: Display the chart in the equatorial coordinate system with the NCP up so roll = 0. @@ -264,14 +265,14 @@ def get_roll_by_mount_type( # Roll at the target RA/Dec in the horizontal frame roll_deg = calc_utils.sf_utils.radec_to_roll(ra_deg, dec_deg, dt) else: - # No position or time/date available, so set roll to 0 - roll_deg = 0 + # No position or time/date available, so set roll to 0.0 + roll_deg = 0.0 elif mount_type == "EQ": - # EQ-mounts: Display chart with NCP up so roll = 0 - roll_deg = 0 + # EQ-mounts: Display chart with NCP up so roll = 0.0 + roll_deg = 0.0 else: logger.error(f"Unknown mount type: {mount_type}. Cannot set roll.") - roll_deg = 0 + roll_deg = 0.0 return roll_deg diff --git a/python/PiFinder/pointing_model/astro_coords.py b/python/PiFinder/pointing_model/astro_coords.py index a33e383a2..48428bdd9 100644 --- a/python/PiFinder/pointing_model/astro_coords.py +++ b/python/PiFinder/pointing_model/astro_coords.py @@ -125,11 +125,11 @@ def initialized_solved_dict() -> dict: TODO: "Alt" and "Az" could be removed but seems to be required by catalogs? """ solved = { - # RA, Dec, Roll of the scope at the target pixel + # RA, Dec, Roll [deg] of the scope at the target pixel "RA": None, "Dec": None, "Roll": None, - # RA, Dec, Roll solved at the center of the camera FoV + # RA, Dec, Roll [deg] solved at the center of the camera FoV # update by the IMU in the integrator "camera_center": { "RA": None, @@ -138,14 +138,15 @@ def initialized_solved_dict() -> dict: "Alt": None, # NOTE: Altaz needed by catalogs for altaz mounts "Az": None, }, - # RA, Dec, Roll from the camera, not updated by IMU in integrator + # RA, Dec, Roll [deg] from the camera, not updated by IMU in integrator "camera_solve": { "RA": None, "Dec": None, "Roll": None, }, "imu_quat": None, # IMU quaternion as numpy quaternion (scalar-first) - "Alt": None, # Alt of scope + # Alt, Az [deg] of scope + "Alt": None, "Az": None, "solve_source": None, "solve_time": None, From 06df9be430cb6f21b48efe86aa24aab9e9632f2f Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Sat, 1 Nov 2025 10:14:21 +0100 Subject: [PATCH 226/253] Add notes from testing to README --- python/PiFinder/pointing_model/README.md | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/python/PiFinder/pointing_model/README.md b/python/PiFinder/pointing_model/README.md index ec119e903..67a473636 100644 --- a/python/PiFinder/pointing_model/README.md +++ b/python/PiFinder/pointing_model/README.md @@ -37,6 +37,12 @@ Done: >Remove this before release! +## 20251030: b8e09ff (tested 31 Oct) + +* v2 Flat. +* Issue with chart as before. Switches over in the E at around RA=+6hrs and +also in the West around 22hrs? + ## 20251021: 7519b (tested 24 Oct) * v2 Flat. From 958ce2c11f6ea3cd316858122e4572192b3890de Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Sun, 2 Nov 2025 01:26:54 +0100 Subject: [PATCH 227/253] Decrease IMU_MOVED_ANG_THRESHOLD from 0.1 deg to 0.06 deg, which is same as the value used in the original code (when converted to deg). --- python/PiFinder/integrator.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index b49026279..ce02dd097 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -28,7 +28,8 @@ # Constants: # Use IMU tracking if the angle moved is above this -IMU_MOVED_ANG_THRESHOLD = np.deg2rad(0.1) +# TODO: May need to adjust this depending on the IMU sensitivity thresholds +IMU_MOVED_ANG_THRESHOLD = np.deg2rad(0.06) def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=False): From 175e32ef9af854f7e21623ce860a8c5588e7fcdd Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Tue, 4 Nov 2025 22:31:18 +0100 Subject: [PATCH 228/253] Lint --- python/PiFinder/integrator.py | 1 - 1 file changed, 1 deletion(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index ce02dd097..682bb5318 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -268,7 +268,6 @@ def get_roll_by_mount_type( else: # No position or time/date available, so set roll to 0.0 roll_deg = 0.0 - elif mount_type == "EQ": # EQ-mounts: Display chart with NCP up so roll = 0.0 roll_deg = 0.0 From 48230afba1237408def0824e908a5ce50f2d8b21 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Tue, 4 Nov 2025 22:31:38 +0100 Subject: [PATCH 229/253] For testing: Disable 180 degree rotation of roll --- python/PiFinder/calc_utils.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/python/PiFinder/calc_utils.py b/python/PiFinder/calc_utils.py index 311718181..fdc4c8677 100644 --- a/python/PiFinder/calc_utils.py +++ b/python/PiFinder/calc_utils.py @@ -250,7 +250,8 @@ def hadec_to_roll(ha_deg, dec_deg, lat_deg): if dec_deg <= lat_deg: roll_deg = -pa_deg else: - roll_deg = -pa_deg + np.sign(ha_deg) * 180 + roll_deg = -pa_deg + #roll_deg = -pa_deg + np.sign(ha_deg) * 180 # Disable for testing return roll_deg From 92ba5e5c1fabbdacdc4c3536fd7bda03f133c1f4 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Wed, 5 Nov 2025 16:43:54 +0100 Subject: [PATCH 230/253] Update README --- python/PiFinder/pointing_model/README.md | 1 + 1 file changed, 1 insertion(+) diff --git a/python/PiFinder/pointing_model/README.md b/python/PiFinder/pointing_model/README.md index 67a473636..45baec45d 100644 --- a/python/PiFinder/pointing_model/README.md +++ b/python/PiFinder/pointing_model/README.md @@ -32,6 +32,7 @@ Done: * Clean up README * Remove instruction on venv * Remove descriptions of frames +* Brickbots tested Right version got strange estimates like the axes were swapped around --> Was due to an incorrect rotation `q_imu2cam` for the "right" PiFinder. Check the others. --> Fixed 25 Oct 2025 (6f7e17b) # Sky test log From af785d9873ebf476650183e51a28dae72f6bac67 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Fri, 14 Nov 2025 21:39:33 +0100 Subject: [PATCH 231/253] Refactor: Rename functions/methodds --- python/PiFinder/pointing_model/astro_coords.py | 2 +- python/PiFinder/pointing_model/imu_dead_reckoning.py | 6 +++--- python/PiFinder/pointing_model/quaternion_transforms.py | 9 ++++++--- 3 files changed, 10 insertions(+), 7 deletions(-) diff --git a/python/PiFinder/pointing_model/astro_coords.py b/python/PiFinder/pointing_model/astro_coords.py index 48428bdd9..2162cde6a 100644 --- a/python/PiFinder/pointing_model/astro_coords.py +++ b/python/PiFinder/pointing_model/astro_coords.py @@ -58,7 +58,7 @@ def set_from_deg( def set_from_quaternion(self, q_eq: quaternion.quaternion): """ Set from a quaternion rotation relative to the Equatorial frame. - Re-using code from quaternion_transforms.get_radec_of_q_eq. + Re-using code from quaternion_transforms.q_eq2radec. """ # Pure quaternion along camera boresight pz_frame = q_eq * quaternion.quaternion(0, 0, 0, 1) * q_eq.conj() diff --git a/python/PiFinder/pointing_model/imu_dead_reckoning.py b/python/PiFinder/pointing_model/imu_dead_reckoning.py index cd6de755f..29ed49b3f 100644 --- a/python/PiFinder/pointing_model/imu_dead_reckoning.py +++ b/python/PiFinder/pointing_model/imu_dead_reckoning.py @@ -77,8 +77,8 @@ def set_alignment(self, solved_cam: RaDecRoll, solved_scope: RaDecRoll): solved_scope: Equatorial coordinate of the scope center at alignement. """ # Calculate q_scope2cam (alignment) - q_eq2cam = qt.get_q_eq(solved_cam.ra, solved_cam.dec, solved_cam.roll) - q_eq2scope = qt.get_q_eq(solved_scope.ra, solved_scope.dec, solved_scope.roll) + q_eq2cam = qt.radec2q_eq(solved_cam.ra, solved_cam.dec, solved_cam.roll) + q_eq2scope = qt.radec2q_eq(solved_scope.ra, solved_scope.dec, solved_scope.roll) q_scope2cam = q_eq2scope.conjugate() * q_eq2cam # Set the alignmen attributes: @@ -107,7 +107,7 @@ def update_plate_solve_and_imu( # Update plate-solved coord: Camera frame relative to the Equatorial # frame where the +y camera frame (i.e. "up") points to the North # Celestial Pole (NCP) -- i.e. zero roll offset: - self.q_eq2cam = qt.get_q_eq(solved_cam.ra, solved_cam.dec, solved_cam.roll) + self.q_eq2cam = qt.radec2q_eq(solved_cam.ra, solved_cam.dec, solved_cam.roll) self.dead_reckoning = False # Using plate solve, no dead_reckoning # Update IMU: Calculate the IMU's unknown reference frame X using the diff --git a/python/PiFinder/pointing_model/quaternion_transforms.py b/python/PiFinder/pointing_model/quaternion_transforms.py index 898b4d8bb..25bbb7717 100644 --- a/python/PiFinder/pointing_model/quaternion_transforms.py +++ b/python/PiFinder/pointing_model/quaternion_transforms.py @@ -30,7 +30,10 @@ def axis_angle2quat(axis, theta: float) -> quaternion.quaternion: INPUTS: axis: (3,) Axis of rotation (doesn't need to be a unit vector) - angle: Angle of rotation [rad] + angle: Angle of rotation [rad]. It uses the right-hand rule; positive + when for clock-wise rotation as viewed outwards along the axis vector. + You can also point the thumb of the right hand in the direction of the + axis vector. Positive turn in the direction that the fingers point. """ assert len(axis) == 3, "axis should be a list or numpy array of length 3." # Define the vector part of the quaternion @@ -62,7 +65,7 @@ def get_quat_angular_diff( # ========== Equatorial frame functions ============================ -def get_q_eq(ra_rad: float, dec_rad: float, roll_rad: float) -> quaternion.quaternion: +def radec2q_eq(ra_rad: float, dec_rad: float, roll_rad: float) -> quaternion.quaternion: """ Express the equatorial coordinates (RA, Dec, Roll) in radians in a quaternion rotation the relative to the Equatorial frame. @@ -84,7 +87,7 @@ def get_q_eq(ra_rad: float, dec_rad: float, roll_rad: float) -> quaternion.quate return q_eq -def get_radec_of_q_eq(q_eq2frame: quaternion.quaternion) -> tuple[float, float, float]: +def q_eq2radec(q_eq2frame: quaternion.quaternion) -> tuple[float, float, float]: """ Returns the (ra, dec, roll) angles of the quaterion rotation relative to the equatorial frame. From 85b4bfd76d0feca80e6df6ac975bf04ee283a8ed Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Fri, 14 Nov 2025 22:19:42 +0100 Subject: [PATCH 232/253] Update README & comments --- python/PiFinder/pointing_model/README.md | 3 ++- .../PiFinder/pointing_model/quaternion_transforms.py | 12 ++++++++++-- 2 files changed, 12 insertions(+), 3 deletions(-) diff --git a/python/PiFinder/pointing_model/README.md b/python/PiFinder/pointing_model/README.md index 45baec45d..2dff9d9b9 100644 --- a/python/PiFinder/pointing_model/README.md +++ b/python/PiFinder/pointing_model/README.md @@ -213,7 +213,8 @@ tracking error between the plate solved coordinates and the IMU dead-reckoning. The roll (as given by Tetra3) is defined as the rotation of the north pole relative to the camera image's "up" direction ($+y$). A positive roll angle -means that the pole is counter-clockwise from image "up" (i.e. towards West). +means that the pole is counter-clockwise from image "up" when looking out +towards the sky (i.e. towards East). ### Telescope coordinate transformations diff --git a/python/PiFinder/pointing_model/quaternion_transforms.py b/python/PiFinder/pointing_model/quaternion_transforms.py index 25bbb7717..8005ed559 100644 --- a/python/PiFinder/pointing_model/quaternion_transforms.py +++ b/python/PiFinder/pointing_model/quaternion_transforms.py @@ -69,6 +69,15 @@ def radec2q_eq(ra_rad: float, dec_rad: float, roll_rad: float) -> quaternion.qua """ Express the equatorial coordinates (RA, Dec, Roll) in radians in a quaternion rotation the relative to the Equatorial frame. + + Equatorial frame: +z points to the NCP, +x points to the Vernal equinox + (RA = 0, Dec = 0), +y points to RA = 6h (+pi / 2), Dec = 0. + + Roll: Roll is the angle of north celestial pole (NP) relative to image up. + positive roll when NP s counter-clockwise from image up when looking + out towards the sky towards the East (zero if +y_cam points up along + # the great circle towards the NP). Alternatively, roll is positive when + rotated clockwise when looking from the sky to the camera. """ # Intrinsic rotation of q_ra followed by q_dec gives a quaternion rotation # that points +z towards the boresight of the camera. +y to the left and @@ -78,8 +87,7 @@ def radec2q_eq(ra_rad: float, dec_rad: float, roll_rad: float) -> quaternion.qua # Need to rotate this +90 degrees around z_cam so that +y_cam points up # and +x_cam points to the left of the Camera frame. In addition, need to - # account for the roll offset of the camera (zero if +y_cam points up along - # the great circle towards the NCP) + # account for the roll offset of the camera. q_roll = axis_angle2quat([0, 0, 1], np.pi / 2 + roll_rad) # Intrinsic rotation: From 5015dce541e2c1ea37cd71f57ef4ee3299d0a29e Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Fri, 14 Nov 2025 22:21:41 +0000 Subject: [PATCH 233/253] Remove duplicate code and use the function from quaternion_transforms.py --- .../PiFinder/pointing_model/astro_coords.py | 20 +++---------------- 1 file changed, 3 insertions(+), 17 deletions(-) diff --git a/python/PiFinder/pointing_model/astro_coords.py b/python/PiFinder/pointing_model/astro_coords.py index 2162cde6a..9d81b9c63 100644 --- a/python/PiFinder/pointing_model/astro_coords.py +++ b/python/PiFinder/pointing_model/astro_coords.py @@ -7,6 +7,8 @@ import quaternion from typing import Union # When updated to Python 3.10+, remove and use new type hints +import PiFinder.pointing_model.quaternion_transforms as qt + @dataclass class RaDecRoll: @@ -60,23 +62,7 @@ def set_from_quaternion(self, q_eq: quaternion.quaternion): Set from a quaternion rotation relative to the Equatorial frame. Re-using code from quaternion_transforms.q_eq2radec. """ - # Pure quaternion along camera boresight - pz_frame = q_eq * quaternion.quaternion(0, 0, 0, 1) * q_eq.conj() - - # Calculate RA, Dec from the camera boresight: - dec = np.arcsin(pz_frame.z) - ra = np.arctan2(pz_frame.y, pz_frame.x) - - # Calcualte Roll: - # Pure quaternion along y_cam which points to NCP when roll = 0 - py_cam = q_eq * quaternion.quaternion(0, 0, 1, 0) * q_eq.conj() - # Local East and North vectors (roll is the angle between py_cam and the north vector) - vec_east = np.array([-np.sin(ra), np.cos(ra), 0]) - vec_north = np.array( - [-np.sin(dec) * np.cos(ra), -np.sin(dec) * np.sin(ra), np.cos(dec)] - ) - roll = -np.arctan2(np.dot(py_cam.vec, vec_east), np.dot(py_cam.vec, vec_north)) - + ra, dec, roll = qt.q_eq2radec(q_eq) self.set(ra, dec, roll) def get( From ba3761e0e909b7695c285a9d077daf75035f00cc Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Fri, 14 Nov 2025 22:42:52 +0000 Subject: [PATCH 234/253] For southern hemisphere, show south up. --- python/PiFinder/integrator.py | 14 ++++++++++++++ 1 file changed, 14 insertions(+) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 682bb5318..ea572c8cc 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -258,6 +258,13 @@ def get_roll_by_mount_type( NCP up so roll = 0. Assumes that location has already been set in calc_utils.sf_utils. + + PARAMETERS: + ra_deg: Right Ascension of the target in degrees + dec_deg: Declination of the target in degrees + location: astropy EarthLocation object or None + dt: datetime.datetime object or None + mount_type: "Alt/Az" or "EQ" """ if mount_type == "Alt/Az": # Altaz mounts: Display chart in horizontal coordinates @@ -275,4 +282,11 @@ def get_roll_by_mount_type( logger.error(f"Unknown mount type: {mount_type}. Cannot set roll.") roll_deg = 0.0 + # If location is available, adjust roll for hemisphere: + # For altaz, North up in northern hemisphere, South up in southern hemisphere + # For EQ mounts, NCP up in northern hemisphere, SCP up in southern hemisphere + if location: + if location.lat < 0.0: + roll_deg += 180.0 # Southern hemisphere + return roll_deg From d364fef968c9b3b0a5471bc71e8d0eee34bfdc61 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Fri, 14 Nov 2025 22:45:31 +0000 Subject: [PATCH 235/253] Big change: Change sign of rol calculated by quaternion_transforms --- python/PiFinder/pointing_model/quaternion_transforms.py | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/python/PiFinder/pointing_model/quaternion_transforms.py b/python/PiFinder/pointing_model/quaternion_transforms.py index 8005ed559..87001f70e 100644 --- a/python/PiFinder/pointing_model/quaternion_transforms.py +++ b/python/PiFinder/pointing_model/quaternion_transforms.py @@ -88,10 +88,11 @@ def radec2q_eq(ra_rad: float, dec_rad: float, roll_rad: float) -> quaternion.qua # Need to rotate this +90 degrees around z_cam so that +y_cam points up # and +x_cam points to the left of the Camera frame. In addition, need to # account for the roll offset of the camera. - q_roll = axis_angle2quat([0, 0, 1], np.pi / 2 + roll_rad) + q_roll = axis_angle2quat([0, 0, 1], np.pi / 2 - roll_rad) # Intrinsic rotation: q_eq = (q_ra * q_dec * q_roll).normalized() + return q_eq @@ -113,6 +114,6 @@ def q_eq2radec(q_eq2frame: quaternion.quaternion) -> tuple[float, float, float]: vec_north = np.array( [-np.sin(dec) * np.cos(ra), -np.sin(dec) * np.sin(ra), np.cos(dec)] ) - roll = -np.arctan2(np.dot(py_cam.vec, vec_east), np.dot(py_cam.vec, vec_north)) + roll = np.arctan2(np.dot(py_cam.vec, vec_east), np.dot(py_cam.vec, vec_north)) return ra, dec, roll # In radians From 478a5c901fa9ab1567d296a7fc75995d2668fa12 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Fri, 14 Nov 2025 22:59:05 +0000 Subject: [PATCH 236/253] Update comments --- python/PiFinder/calc_utils.py | 2 +- python/PiFinder/integrator.py | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/python/PiFinder/calc_utils.py b/python/PiFinder/calc_utils.py index fdc4c8677..8c81035b8 100644 --- a/python/PiFinder/calc_utils.py +++ b/python/PiFinder/calc_utils.py @@ -251,7 +251,7 @@ def hadec_to_roll(ha_deg, dec_deg, lat_deg): roll_deg = -pa_deg else: roll_deg = -pa_deg - #roll_deg = -pa_deg + np.sign(ha_deg) * 180 # Disable for testing + #roll_deg = -pa_deg + np.sign(ha_deg) * 180 # Disable for testing TODO: Check this return roll_deg diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index ea572c8cc..e323f5978 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -283,8 +283,8 @@ def get_roll_by_mount_type( roll_deg = 0.0 # If location is available, adjust roll for hemisphere: - # For altaz, North up in northern hemisphere, South up in southern hemisphere - # For EQ mounts, NCP up in northern hemisphere, SCP up in southern hemisphere + # Altaz: North up in northern hemisphere, South up in southern hemisphere + # EQ mounts: NCP up in northern hemisphere, SCP up in southern hemisphere if location: if location.lat < 0.0: roll_deg += 180.0 # Southern hemisphere From d487b16cc66241fabbc946eb229831432fcf5e5d Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 15 Nov 2025 11:42:42 +0000 Subject: [PATCH 237/253] Merge issue fix: camera_interface.py: Now "focus" shows image. Still issue in test mode. --- python/PiFinder/camera_interface.py | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/python/PiFinder/camera_interface.py b/python/PiFinder/camera_interface.py index 5ad80ad87..821ef7a32 100644 --- a/python/PiFinder/camera_interface.py +++ b/python/PiFinder/camera_interface.py @@ -18,6 +18,7 @@ import logging from PiFinder import state_utils, utils +import PiFinder.pointing_model.quaternion_transforms as qt from PiFinder.auto_exposure import ( ExposurePIDController, SweepZeroStarHandler, @@ -126,15 +127,15 @@ def get_image_loop( # see if we moved during exposure if imu_start and imu_end: - # Pointing difference between start and end of exposure [rad] - pointing_diff = utils.calc_quat_angle_diff(imu_start["quat"], imu_end["quat"]) + # Returns the pointing difference between successive IMU quaternions as + # an angle (radians). Note that this also accounts for rotation around the + # scope axis. Returns an angle in radians. + pointing_diff = qt.get_quat_angular_diff( + imu_start["quat"], imu_end["quat"] + ) else: pointing_diff = 0.0 - # TODO: Merge issue: Rename reading_diff? - # Pointing change during exposure in degrees - #reading_diff = np.rad2deg(pointing_diff) if isinstance(pointing_diff, (int, float)) else 0.0 - camera_image.paste(base_image) image_metadata = { From 32165d2115a01731dc9991624ddcb76b369ecfc1 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 15 Nov 2025 11:56:25 +0000 Subject: [PATCH 238/253] Copy pre-merge versions of integrator.py to debug merge conflict issues. --- python/PiFinder/integrator_main.py | 302 +++++++++++++++++++++++++ python/PiFinder/integrator_premerge.py | 292 ++++++++++++++++++++++++ 2 files changed, 594 insertions(+) create mode 100644 python/PiFinder/integrator_main.py create mode 100644 python/PiFinder/integrator_premerge.py diff --git a/python/PiFinder/integrator_main.py b/python/PiFinder/integrator_main.py new file mode 100644 index 000000000..80828a534 --- /dev/null +++ b/python/PiFinder/integrator_main.py @@ -0,0 +1,302 @@ +#!/usr/bin/python +# -*- coding:utf-8 -*- +""" +This module is the solver +* Checks IMU +* Plate solves high-res image + +""" + +import queue +import time +import copy +import logging + +from PiFinder import config +from PiFinder import state_utils +import PiFinder.calc_utils as calc_utils +from PiFinder.multiproclogging import MultiprocLogging + +IMU_ALT = 2 +IMU_AZ = 0 + +logger = logging.getLogger("IMU.Integrator") + + +def imu_moved(imu_a, imu_b): + """ + Compares two IMU states to determine if they are the 'same' + if either is none, returns False + """ + if imu_a is None: + return False + if imu_b is None: + return False + + # figure out the abs difference + diff = ( + abs(imu_a[0] - imu_b[0]) + abs(imu_a[1] - imu_b[1]) + abs(imu_a[2] - imu_b[2]) + ) + if diff > 0.001: + return True + return False + + +def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=False): + MultiprocLogging.configurer(log_queue) + try: + if is_debug: + logger.setLevel(logging.DEBUG) + logger.debug("Starting Integrator") + + solved = { + "RA": None, + "Dec": None, + "Roll": None, + "camera_center": { + "RA": None, + "Dec": None, + "Roll": None, + "Alt": None, + "Az": None, + }, + "camera_solve": { + "RA": None, + "Dec": None, + "Roll": None, + }, + "Roll_offset": 0, # May/may not be needed - for experimentation + "imu_pos": None, + "Alt": None, + "Az": None, + "solve_source": None, + "solve_time": None, + "cam_solve_time": 0, + "constellation": None, + } + cfg = config.Config() + if ( + cfg.get_option("screen_direction") == "left" + or cfg.get_option("screen_direction") == "flat" + or cfg.get_option("screen_direction") == "flat3" + or cfg.get_option("screen_direction") == "straight" + ): + flip_alt_offset = True + else: + flip_alt_offset = False + + # This holds the last image solve position info + # so we can delta for IMU updates + last_image_solve = None + last_solve_time = time.time() + while True: + state_utils.sleep_for_framerate(shared_state) + + # Check for new camera solve in queue + next_image_solve = None + try: + next_image_solve = solver_queue.get(block=False) + except queue.Empty: + pass + + if type(next_image_solve) is dict: + # For camera solves, always start from last successful camera solve + # NOT from shared_state (which may contain IMU drift) + # This prevents IMU noise accumulation during failed solves + if last_image_solve: + solved = copy.deepcopy(last_image_solve) + # If no successful solve yet, keep initial solved dict + + # Update solve metadata (always needed for auto-exposure) + for key in [ + "Matches", + "RMSE", + "last_solve_attempt", + "last_solve_success", + ]: + if key in next_image_solve: + solved[key] = next_image_solve[key] + + # Only update position data if solve succeeded (RA not None) + if next_image_solve.get("RA") is not None: + solved.update(next_image_solve) + + # Recalculate Alt/Az for NEW successful solve + location = shared_state.location() + dt = shared_state.datetime() + + if location and dt: + # We have position and time/date and a valid solve! + calc_utils.sf_utils.set_location( + location.lat, + location.lon, + location.altitude, + ) + alt, az = calc_utils.sf_utils.radec_to_altaz( + solved["RA"], + solved["Dec"], + dt, + ) + solved["Alt"] = alt + solved["Az"] = az + + alt, az = calc_utils.sf_utils.radec_to_altaz( + solved["camera_center"]["RA"], + solved["camera_center"]["Dec"], + dt, + ) + solved["camera_center"]["Alt"] = alt + solved["camera_center"]["Az"] = az + + # Experimental: For monitoring roll offset + # Estimate the roll offset due misalignment of the + # camera sensor with the Pole-to-Source great circle. + solved["Roll_offset"] = estimate_roll_offset(solved, dt) + # Find the roll at the target RA/Dec. Note that this doesn't include the + # roll offset so it's not the roll that the PiFinder camear sees but the + # roll relative to the celestial pole + roll_target_calculated = calc_utils.sf_utils.radec_to_roll( + solved["RA"], solved["Dec"], dt + ) + # Compensate for the roll offset. This gives the roll at the target + # as seen by the camera. + solved["Roll"] = roll_target_calculated + solved["Roll_offset"] + + # calculate roll for camera center + roll_target_calculated = calc_utils.sf_utils.radec_to_roll( + solved["camera_center"]["RA"], + solved["camera_center"]["Dec"], + dt, + ) + # Compensate for the roll offset. This gives the roll at the target + # as seen by the camera. + solved["camera_center"]["Roll"] = ( + roll_target_calculated + solved["Roll_offset"] + ) + # For failed solves, preserve ALL position data from previous solve + # Don't recalculate from GPS (causes drift from GPS noise) + + # Set solve_source and push camera solves immediately + if solved["RA"] is not None: + last_image_solve = copy.deepcopy(solved) + solved["solve_source"] = "CAM" + # Calculate constellation for successful solve + solved["constellation"] = ( + calc_utils.sf_utils.radec_to_constellation( + solved["RA"], solved["Dec"] + ) + ) + else: + # Failed solve - clear constellation + solved["solve_source"] = "CAM_FAILED" + solved["constellation"] = "" + + # Push all camera solves (success and failure) immediately + # This ensures auto-exposure sees Matches=0 for failed solves + shared_state.set_solution(solved) + shared_state.set_solve_state(True) + + # Use IMU dead-reckoning from the last camera solve: + # Check we have an alt/az solve, otherwise we can't use the IMU + elif solved["Alt"]: + imu = shared_state.imu() + if imu: + dt = shared_state.datetime() + if last_image_solve and last_image_solve["Alt"]: + # If we have alt, then we have a position/time + + # calc new alt/az + lis_imu = last_image_solve["imu_pos"] + imu_pos = imu["pos"] + if imu_moved(lis_imu, imu_pos): + alt_offset = imu_pos[IMU_ALT] - lis_imu[IMU_ALT] + if flip_alt_offset: + alt_offset = ((alt_offset + 180) % 360 - 180) * -1 + else: + alt_offset = (alt_offset + 180) % 360 - 180 + solved["Alt"] = (last_image_solve["Alt"] - alt_offset) % 360 + solved["camera_center"]["Alt"] = ( + last_image_solve["camera_center"]["Alt"] - alt_offset + ) % 360 + + az_offset = imu_pos[IMU_AZ] - lis_imu[IMU_AZ] + az_offset = (az_offset + 180) % 360 - 180 + solved["Az"] = (last_image_solve["Az"] + az_offset) % 360 + solved["camera_center"]["Az"] = ( + last_image_solve["camera_center"]["Az"] + az_offset + ) % 360 + + # N.B. Assumes that location hasn't changed since last solve + # Turn this into RA/DEC + ( + solved["RA"], + solved["Dec"], + ) = calc_utils.sf_utils.altaz_to_radec( + solved["Alt"], solved["Az"], dt + ) + # Calculate the roll at the target RA/Dec and compensate for the offset. + solved["Roll"] = ( + calc_utils.sf_utils.radec_to_roll( + solved["RA"], solved["Dec"], dt + ) + + solved["Roll_offset"] + ) + + # Now for camera centered solve + ( + solved["camera_center"]["RA"], + solved["camera_center"]["Dec"], + ) = calc_utils.sf_utils.altaz_to_radec( + solved["camera_center"]["Alt"], + solved["camera_center"]["Az"], + dt, + ) + # Calculate the roll at the target RA/Dec and compensate for the offset. + solved["camera_center"]["Roll"] = ( + calc_utils.sf_utils.radec_to_roll( + solved["camera_center"]["RA"], + solved["camera_center"]["Dec"], + dt, + ) + + solved["Roll_offset"] + ) + + solved["solve_time"] = time.time() + solved["solve_source"] = "IMU" + + # Push IMU updates only if newer than last push + # (Camera solves already pushed above at line 185) + if ( + solved["RA"] + and solved["solve_time"] > last_solve_time + and solved.get("solve_source") == "IMU" + ): + last_solve_time = time.time() + # Calculate constellation for IMU dead-reckoning position + solved["constellation"] = calc_utils.sf_utils.radec_to_constellation( + solved["RA"], solved["Dec"] + ) + + # Push IMU update + shared_state.set_solution(solved) + shared_state.set_solve_state(True) + except EOFError: + logger.error("Main no longer running for integrator") + + +def estimate_roll_offset(solved, dt): + """ + Estimate the roll offset due to misalignment of the camera sensor with + the mount/scope's coordinate system. The offset is calculated at the + center of the camera's FoV. + + To calculate the roll with offset: roll = calculated_roll + roll_offset + """ + # Calculate the expected roll at the camera center given the RA/Dec of + # of the camera center. + roll_camera_calculated = calc_utils.sf_utils.radec_to_roll( + solved["camera_center"]["RA"], solved["camera_center"]["Dec"], dt + ) + roll_offset = solved["camera_center"]["Roll"] - roll_camera_calculated + + return roll_offset diff --git a/python/PiFinder/integrator_premerge.py b/python/PiFinder/integrator_premerge.py new file mode 100644 index 000000000..e323f5978 --- /dev/null +++ b/python/PiFinder/integrator_premerge.py @@ -0,0 +1,292 @@ +#!/usr/bin/python +# -*- coding:utf-8 -*- +""" +This module is the solver +* Checks IMU +* Plate solves high-res image + +""" + +import datetime +import queue +import time +import copy +import logging +import numpy as np +import quaternion # numpy-quaternion + +from PiFinder import config +from PiFinder import state_utils +import PiFinder.calc_utils as calc_utils +from PiFinder.multiproclogging import MultiprocLogging +from PiFinder.pointing_model.astro_coords import initialized_solved_dict, RaDecRoll +from PiFinder.pointing_model.imu_dead_reckoning import ImuDeadReckoning +import PiFinder.pointing_model.quaternion_transforms as qt + + +logger = logging.getLogger("IMU.Integrator") + +# Constants: +# Use IMU tracking if the angle moved is above this +# TODO: May need to adjust this depending on the IMU sensitivity thresholds +IMU_MOVED_ANG_THRESHOLD = np.deg2rad(0.06) + + +def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=False): + MultiprocLogging.configurer(log_queue) + """ """ + if is_debug: + logger.setLevel(logging.DEBUG) + logger.debug("Starting Integrator") + + try: + # Dict of RA, Dec, etc. initialized to None: + solved = initialized_solved_dict() + cfg = config.Config() + + mount_type = cfg.get_option("mount_type") + logger.debug(f"mount_type = {mount_type}") + + # Set up dead-reckoning tracking by the IMU: + imu_dead_reckoning = ImuDeadReckoning(cfg.get_option("screen_direction")) + # imu_dead_reckoning.set_alignment(q_scope2cam) # TODO: Enable when q_scope2cam is available from alignment + + # This holds the last image solve position info + # so we can delta for IMU updates + last_image_solve = None + last_solve_time = time.time() + + while True: + state_utils.sleep_for_framerate(shared_state) + + # Check for new camera solve in queue + next_image_solve = None + try: + next_image_solve = solver_queue.get(block=False) + except queue.Empty: + pass + + if type(next_image_solve) is dict: + # We have a new image solve: Use plate-solving for RA/Dec + solved = next_image_solve + update_plate_solve_and_imu(imu_dead_reckoning, solved) + + last_image_solve = copy.deepcopy(solved) + solved["solve_source"] = "CAM" + + elif imu_dead_reckoning.tracking: + # Previous plate-solve exists so use IMU dead-reckoning from + # the last plate solved coordinates. + imu = shared_state.imu() + if imu: + update_imu(imu_dead_reckoning, solved, last_image_solve, imu) + + # Is the solution new? + if solved["RA"] and solved["solve_time"] > last_solve_time: + last_solve_time = time.time() + + # Try to set date and time + location = shared_state.location() + dt = shared_state.datetime() + # Set location for roll and altaz calculations. + # TODO: Is itnecessary to set location? + # TODO: Altaz doesn't seem to be required for catalogs when in + # EQ mode? Could be disabled in future when in EQ mode? + calc_utils.sf_utils.set_location( + location.lat, location.lon, location.altitude + ) + + # Set the roll so that the chart is displayed appropriately for the mount type + solved["Roll"] = get_roll_by_mount_type( + solved["RA"], solved["Dec"], location, dt, mount_type + ) + + # Update remaining solved keys + solved["constellation"] = calc_utils.sf_utils.radec_to_constellation( + solved["RA"], solved["Dec"] + ) + + # Set Alt/Az because it's needed for the catalogs for the + # Alt/Az mount type. TODO: Can this be moved to the catalog? + dt = shared_state.datetime() + if location and dt: + solved["Alt"], solved["Az"] = calc_utils.sf_utils.radec_to_altaz( + solved["RA"], solved["Dec"], dt + ) + + # add solution + shared_state.set_solution(solved) + shared_state.set_solve_state(True) + + except EOFError: + logger.error("Main no longer running for integrator") + + +# ======== Wrapper and helper functions =============================== + + +def update_plate_solve_and_imu(imu_dead_reckoning: ImuDeadReckoning, solved: dict): + """ + Wrapper for ImuDeadReckoning.update_plate_solve_and_imu() to + interface angles in degrees to radians. + + This updates the pointing model with the plate-solved coordinates and the + IMU measurements which are assumed to have been taken at the same time. + """ + if (solved["RA"] is None) or (solved["Dec"] is None): + return # No update + else: + # Successfully plate solved & camera pointing exists + if solved["imu_quat"] is None: + q_x2imu = quaternion.quaternion(np.nan) + else: + q_x2imu = solved["imu_quat"] # IMU measurement at the time of plate solving + + # Update: + solved_cam = RaDecRoll() + solved_cam.set_from_deg( + solved["camera_center"]["RA"], + solved["camera_center"]["Dec"], + solved["camera_center"]["Roll"], + ) + imu_dead_reckoning.update_plate_solve_and_imu(solved_cam, q_x2imu) + + # Set alignment. TODO: Do this once at alignment. Move out of here. + set_alignment(imu_dead_reckoning, solved) + + +def set_alignment(imu_dead_reckoning: ImuDeadReckoning, solved: dict): + """ + Set alignment. + TODO: Do this once at alignment + """ + # RA, Dec of camera center:: + solved_cam = RaDecRoll() + solved_cam.set_from_deg( + solved["camera_center"]["RA"], + solved["camera_center"]["Dec"], + solved["camera_center"]["Roll"], + ) + + # RA, Dec of target (where scope is pointing): + solved["Roll"] = 0 # Target roll isn't calculated by Tetra3. Set to zero here + solved_scope = RaDecRoll() + solved_scope.set_from_deg(solved["RA"], solved["Dec"], solved["Roll"]) + + # Set alignment in imu_dead_reckoning + imu_dead_reckoning.set_alignment(solved_cam, solved_scope) + + +def update_imu( + imu_dead_reckoning: ImuDeadReckoning, + solved: dict, + last_image_solve: dict, + imu: dict, +): + """ + Updates the solved dictionary using IMU dead-reckoning from the last + solved pointing. + """ + if not (last_image_solve and imu_dead_reckoning.tracking): + return # Need all of these to do IMU dead-reckoning + + assert isinstance( + imu["quat"], quaternion.quaternion + ), "Expecting quaternion.quaternion type" # TODO: Can be removed later + q_x2imu = imu["quat"] # Current IMU measurement (quaternion) + + # When moving, switch to tracking using the IMU + angle_moved = qt.get_quat_angular_diff(last_image_solve["imu_quat"], q_x2imu) + if angle_moved > IMU_MOVED_ANG_THRESHOLD: + # Estimate camera pointing using IMU dead-reckoning + logger.debug( + "Track using IMU: Angle moved since last_image_solve = " + "{:}(> threshold = {:}) | IMU quat = ({:}, {:}, {:}, {:})".format( + np.rad2deg(angle_moved), + np.rad2deg(IMU_MOVED_ANG_THRESHOLD), + q_x2imu.w, + q_x2imu.x, + q_x2imu.y, + q_x2imu.z, + ) + ) + + # Dead-reckoning using IMU + imu_dead_reckoning.update_imu(q_x2imu) # Latest IMU measurement + + # Store current camera pointing estimate: + cam_eq = imu_dead_reckoning.get_cam_radec() + ( + solved["camera_center"]["RA"], + solved["camera_center"]["Dec"], + solved["camera_center"]["Roll"], + ) = cam_eq.get_deg(use_none=True) + + # Store the current scope pointing estimate + scope_eq = imu_dead_reckoning.get_scope_radec() + solved["RA"], solved["Dec"], solved["Roll"] = scope_eq.get_deg(use_none=True) + + solved["solve_time"] = time.time() + solved["solve_source"] = "IMU" + + # Logging for states updated in solved: + logger.debug( + "IMU update: scope: RA: {:}, Dec: {:}, Roll: {:}".format( + solved["RA"], solved["Dec"], solved["Roll"] + ) + ) + logger.debug( + "IMU update: camera_center: RA: {:}, Dec: {:}, Roll: {:}".format( + solved["camera_center"]["RA"], + solved["camera_center"]["Dec"], + solved["camera_center"]["Roll"], + ) + ) + + +def get_roll_by_mount_type( + ra_deg: float, dec_deg: float, location, dt: datetime.datetime, mount_type: str +) -> float: + """ + Returns the roll (in degrees) depending on the mount type so that the chart + is displayed appropriately for the mount type. The RA and Dec of the target + should be provided (in degrees). + + * Alt/Az mount: Display the chart in the horizontal coordinate so that up + in the chart points to the Zenith. + * EQ mount: Display the chart in the equatorial coordinate system with the + NCP up so roll = 0. + + Assumes that location has already been set in calc_utils.sf_utils. + + PARAMETERS: + ra_deg: Right Ascension of the target in degrees + dec_deg: Declination of the target in degrees + location: astropy EarthLocation object or None + dt: datetime.datetime object or None + mount_type: "Alt/Az" or "EQ" + """ + if mount_type == "Alt/Az": + # Altaz mounts: Display chart in horizontal coordinates + if location and dt: + # We have location and time/date (and assume that location has been set) + # Roll at the target RA/Dec in the horizontal frame + roll_deg = calc_utils.sf_utils.radec_to_roll(ra_deg, dec_deg, dt) + else: + # No position or time/date available, so set roll to 0.0 + roll_deg = 0.0 + elif mount_type == "EQ": + # EQ-mounts: Display chart with NCP up so roll = 0.0 + roll_deg = 0.0 + else: + logger.error(f"Unknown mount type: {mount_type}. Cannot set roll.") + roll_deg = 0.0 + + # If location is available, adjust roll for hemisphere: + # Altaz: North up in northern hemisphere, South up in southern hemisphere + # EQ mounts: NCP up in northern hemisphere, SCP up in southern hemisphere + if location: + if location.lat < 0.0: + roll_deg += 180.0 # Southern hemisphere + + return roll_deg From 3aed06b616887a64f4023aa562ea60397f144f44 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Sat, 15 Nov 2025 12:06:15 +0000 Subject: [PATCH 239/253] Copy integrator from the last merge from main (ebca2) before the auto exposure feature was added. --- python/PiFinder/integrator_main_pre_AE.py | 262 ++++++++++++++++++++++ 1 file changed, 262 insertions(+) create mode 100644 python/PiFinder/integrator_main_pre_AE.py diff --git a/python/PiFinder/integrator_main_pre_AE.py b/python/PiFinder/integrator_main_pre_AE.py new file mode 100644 index 000000000..0f19d0cd5 --- /dev/null +++ b/python/PiFinder/integrator_main_pre_AE.py @@ -0,0 +1,262 @@ +#!/usr/bin/python +# -*- coding:utf-8 -*- +""" +This module is the solver +* Checks IMU +* Plate solves high-res image + +""" + +import queue +import time +import copy +import logging + +from PiFinder import config +from PiFinder import state_utils +import PiFinder.calc_utils as calc_utils +from PiFinder.multiproclogging import MultiprocLogging + +IMU_ALT = 2 +IMU_AZ = 0 + +logger = logging.getLogger("IMU.Integrator") + + +def imu_moved(imu_a, imu_b): + """ + Compares two IMU states to determine if they are the 'same' + if either is none, returns False + """ + if imu_a is None: + return False + if imu_b is None: + return False + + # figure out the abs difference + diff = ( + abs(imu_a[0] - imu_b[0]) + abs(imu_a[1] - imu_b[1]) + abs(imu_a[2] - imu_b[2]) + ) + if diff > 0.001: + return True + return False + + +def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=False): + MultiprocLogging.configurer(log_queue) + try: + if is_debug: + logger.setLevel(logging.DEBUG) + logger.debug("Starting Integrator") + + solved = { + "RA": None, + "Dec": None, + "Roll": None, + "camera_center": { + "RA": None, + "Dec": None, + "Roll": None, + "Alt": None, + "Az": None, + }, + "camera_solve": { + "RA": None, + "Dec": None, + "Roll": None, + }, + "Roll_offset": 0, # May/may not be needed - for experimentation + "imu_pos": None, + "Alt": None, + "Az": None, + "solve_source": None, + "solve_time": None, + "cam_solve_time": 0, + "constellation": None, + } + cfg = config.Config() + if ( + cfg.get_option("screen_direction") == "left" + or cfg.get_option("screen_direction") == "flat" + or cfg.get_option("screen_direction") == "flat3" + or cfg.get_option("screen_direction") == "straight" + ): + flip_alt_offset = True + else: + flip_alt_offset = False + + # This holds the last image solve position info + # so we can delta for IMU updates + last_image_solve = None + last_solve_time = time.time() + while True: + state_utils.sleep_for_framerate(shared_state) + + # Check for new camera solve in queue + next_image_solve = None + try: + next_image_solve = solver_queue.get(block=False) + except queue.Empty: + pass + + if type(next_image_solve) is dict: + solved = next_image_solve + + # see if we can generate alt/az + location = shared_state.location() + dt = shared_state.datetime() + + # see if we can calc alt-az + solved["Alt"] = None + solved["Az"] = None + if location and dt: + # We have position and time/date! + calc_utils.sf_utils.set_location( + location.lat, + location.lon, + location.altitude, + ) + alt, az = calc_utils.sf_utils.radec_to_altaz( + solved["RA"], + solved["Dec"], + dt, + ) + solved["Alt"] = alt + solved["Az"] = az + + alt, az = calc_utils.sf_utils.radec_to_altaz( + solved["camera_center"]["RA"], + solved["camera_center"]["Dec"], + dt, + ) + solved["camera_center"]["Alt"] = alt + solved["camera_center"]["Az"] = az + + # Experimental: For monitoring roll offset + # Estimate the roll offset due misalignment of the + # camera sensor with the Pole-to-Source great circle. + solved["Roll_offset"] = estimate_roll_offset(solved, dt) + # Find the roll at the target RA/Dec. Note that this doesn't include the + # roll offset so it's not the roll that the PiFinder camear sees but the + # roll relative to the celestial pole + roll_target_calculated = calc_utils.sf_utils.radec_to_roll( + solved["RA"], solved["Dec"], dt + ) + # Compensate for the roll offset. This gives the roll at the target + # as seen by the camera. + solved["Roll"] = roll_target_calculated + solved["Roll_offset"] + + # calculate roll for camera center + roll_target_calculated = calc_utils.sf_utils.radec_to_roll( + solved["camera_center"]["RA"], + solved["camera_center"]["Dec"], + dt, + ) + # Compensate for the roll offset. This gives the roll at the target + # as seen by the camera. + solved["camera_center"]["Roll"] = ( + roll_target_calculated + solved["Roll_offset"] + ) + + last_image_solve = copy.deepcopy(solved) + solved["solve_source"] = "CAM" + + # Use IMU dead-reckoning from the last camera solve: + # Check we have an alt/az solve, otherwise we can't use the IMU + elif solved["Alt"]: + imu = shared_state.imu() + if imu: + dt = shared_state.datetime() + if last_image_solve and last_image_solve["Alt"]: + # If we have alt, then we have a position/time + + # calc new alt/az + lis_imu = last_image_solve["imu_pos"] + imu_pos = imu["pos"] + if imu_moved(lis_imu, imu_pos): + alt_offset = imu_pos[IMU_ALT] - lis_imu[IMU_ALT] + if flip_alt_offset: + alt_offset = ((alt_offset + 180) % 360 - 180) * -1 + else: + alt_offset = (alt_offset + 180) % 360 - 180 + solved["Alt"] = (last_image_solve["Alt"] - alt_offset) % 360 + solved["camera_center"]["Alt"] = ( + last_image_solve["camera_center"]["Alt"] - alt_offset + ) % 360 + + az_offset = imu_pos[IMU_AZ] - lis_imu[IMU_AZ] + az_offset = (az_offset + 180) % 360 - 180 + solved["Az"] = (last_image_solve["Az"] + az_offset) % 360 + solved["camera_center"]["Az"] = ( + last_image_solve["camera_center"]["Az"] + az_offset + ) % 360 + + # N.B. Assumes that location hasn't changed since last solve + # Turn this into RA/DEC + ( + solved["RA"], + solved["Dec"], + ) = calc_utils.sf_utils.altaz_to_radec( + solved["Alt"], solved["Az"], dt + ) + # Calculate the roll at the target RA/Dec and compensate for the offset. + solved["Roll"] = ( + calc_utils.sf_utils.radec_to_roll( + solved["RA"], solved["Dec"], dt + ) + + solved["Roll_offset"] + ) + + # Now for camera centered solve + ( + solved["camera_center"]["RA"], + solved["camera_center"]["Dec"], + ) = calc_utils.sf_utils.altaz_to_radec( + solved["camera_center"]["Alt"], + solved["camera_center"]["Az"], + dt, + ) + # Calculate the roll at the target RA/Dec and compensate for the offset. + solved["camera_center"]["Roll"] = ( + calc_utils.sf_utils.radec_to_roll( + solved["camera_center"]["RA"], + solved["camera_center"]["Dec"], + dt, + ) + + solved["Roll_offset"] + ) + + solved["solve_time"] = time.time() + solved["solve_source"] = "IMU" + + # Is the solution new? + if solved["RA"] and solved["solve_time"] > last_solve_time: + last_solve_time = time.time() + # Update remaining solved keys + solved["constellation"] = calc_utils.sf_utils.radec_to_constellation( + solved["RA"], solved["Dec"] + ) + + # add solution + shared_state.set_solution(solved) + shared_state.set_solve_state(True) + except EOFError: + logger.error("Main no longer running for integrator") + + +def estimate_roll_offset(solved, dt): + """ + Estimate the roll offset due to misalignment of the camera sensor with + the mount/scope's coordinate system. The offset is calculated at the + center of the camera's FoV. + + To calculate the roll with offset: roll = calculated_roll + roll_offset + """ + # Calculate the expected roll at the camera center given the RA/Dec of + # of the camera center. + roll_camera_calculated = calc_utils.sf_utils.radec_to_roll( + solved["camera_center"]["RA"], solved["camera_center"]["Dec"], dt + ) + roll_offset = solved["camera_center"]["Roll"] - roll_camera_calculated + + return roll_offset From b6cc66e4f7baaeb25b91e235569c10d449fe369d Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Tue, 25 Nov 2025 23:43:31 +0100 Subject: [PATCH 240/253] Copy integrator from main and pre-merge for debugging --- python/PiFinder/camera_interface_main.py | 451 +++++++++++++++++++ python/PiFinder/camera_interface_premerge.py | 214 +++++++++ 2 files changed, 665 insertions(+) create mode 100644 python/PiFinder/camera_interface_main.py create mode 100644 python/PiFinder/camera_interface_premerge.py diff --git a/python/PiFinder/camera_interface_main.py b/python/PiFinder/camera_interface_main.py new file mode 100644 index 000000000..1b2a03e5b --- /dev/null +++ b/python/PiFinder/camera_interface_main.py @@ -0,0 +1,451 @@ +#!/usr/bin/python +# -*- coding:utf-8 -*- +""" +This module is the camera +* Captures images +* Places preview images in queue +* Places solver images in queue +* Takes full res images on demand + +""" + +import datetime +import logging +import os +import queue +import time +from typing import Tuple, Optional + +from PIL import Image + +from PiFinder import state_utils, utils +from PiFinder.auto_exposure import ( + ExposurePIDController, + SweepZeroStarHandler, + ExponentialSweepZeroStarHandler, + ResetZeroStarHandler, + HistogramZeroStarHandler, + generate_exposure_sweep, +) + +logger = logging.getLogger("Camera.Interface") + + +class CameraInterface: + """The CameraInterface interface.""" + + _camera_started = False + _auto_exposure_enabled = False + _auto_exposure_pid: Optional[ExposurePIDController] = None + _last_solve_time: Optional[float] = None + + def initialize(self) -> None: + pass + + def capture(self) -> Image.Image: + return Image.Image() + + def capture_file(self, filename) -> None: + pass + + def capture_raw_file(self, filename) -> None: + pass + + def set_camera_config( + self, exposure_time: float, gain: float + ) -> Tuple[float, float]: + return (0, 0) + + def get_cam_type(self) -> str: + return "foo" + + def start_camera(self) -> None: + pass + + def stop_camera(self) -> None: + pass + + def get_image_loop( + self, shared_state, camera_image, command_queue, console_queue, cfg + ): + try: + debug = False + + # Check if auto-exposure was previously enabled in config + config_exp = cfg.get_option("camera_exp") + if config_exp == "auto": + self._auto_exposure_enabled = True + self._last_solve_time = None + if self._auto_exposure_pid is None: + self._auto_exposure_pid = ExposurePIDController() + else: + self._auto_exposure_pid.reset() + logger.info("Auto-exposure mode enabled from config") + + screen_direction = cfg.get_option("screen_direction") + camera_rotation = cfg.get_option("camera_rotation") + + # Set path for test mode image + root_dir = os.path.realpath( + os.path.join(os.path.dirname(__file__), "..", "..") + ) + test_image_path = os.path.join( + root_dir, "test_images", "pifinder_debug_02.png" + ) + + # 60 half-second cycles + sleep_delay = 60 + while True: + sleeping = state_utils.sleep_for_framerate( + shared_state, limit_framerate=False + ) + if sleeping: + # Even in sleep mode, we want to take photos every + # so often to update positions + sleep_delay -= 1 + if sleep_delay > 0: + continue + else: + sleep_delay = 60 + + imu_start = shared_state.imu() + image_start_time = time.time() + if self._camera_started: + if not debug: + base_image = self.capture() + base_image = base_image.convert("L") + rotate_amount = 0 + if camera_rotation is None: + if screen_direction in [ + "right", + "straight", + "flat3", + ]: + rotate_amount = 90 + elif screen_direction == "as_bloom": + rotate_amount = 90 # Specific rotation for AS Bloom + else: + rotate_amount = 270 + else: + base_image = base_image.rotate(int(camera_rotation) * -1) + + base_image = base_image.rotate(rotate_amount) + else: + # Test Mode: load image from disc and wait + base_image = Image.open(test_image_path) + time.sleep(1) + image_end_time = time.time() + # check imu to make sure we're still static + imu_end = shared_state.imu() + + # see if we moved during exposure + reading_diff = 0 + if imu_start and imu_end: + reading_diff = ( + abs(imu_start["pos"][0] - imu_end["pos"][0]) + + abs(imu_start["pos"][1] - imu_end["pos"][1]) + + abs(imu_start["pos"][2] - imu_end["pos"][2]) + ) + + camera_image.paste(base_image) + image_metadata = { + "exposure_start": image_start_time, + "exposure_end": image_end_time, + "imu": imu_end, + "imu_delta": reading_diff, + "exposure_time": self.exposure_time, + "gain": self.gain, + } + shared_state.set_last_image_metadata(image_metadata) + + # Auto-exposure: adjust based on plate solve results + # Updates as fast as new solve results arrive (naturally rate-limited) + if self._auto_exposure_enabled and self._auto_exposure_pid: + solution = shared_state.solution() + solve_source = ( + solution.get("solve_source") if solution else None + ) + + # Handle camera solves (successful or failed) + if solve_source in ("CAM", "CAM_FAILED"): + matched_stars = solution.get("Matches", 0) + solve_attempt_time = solution.get("last_solve_attempt") + solve_rmse = solution.get("RMSE") + + # Only update on NEW solve results (not re-processing same solution) + # Use last_solve_attempt since it's set for both success and failure + if ( + solve_attempt_time + and solve_attempt_time != self._last_solve_time + ): + rmse_str = ( + f"{solve_rmse:.1f}" + if solve_rmse is not None + else "N/A" + ) + logger.info( + f"Auto-exposure feedback - Stars: {matched_stars}, " + f"RMSE: {rmse_str}, Current exposure: {self.exposure_time}µs" + ) + + # Call PID update (now handles zero stars with recovery mode) + # Pass base_image for histogram analysis in zero-star handler + new_exposure = self._auto_exposure_pid.update( + matched_stars, self.exposure_time, base_image + ) + + if ( + new_exposure is not None + and new_exposure != self.exposure_time + ): + # Exposure value actually changed - update camera + logger.info( + f"Auto-exposure adjustment: {matched_stars} stars → " + f"{self.exposure_time}µs → {new_exposure}µs " + f"(change: {new_exposure - self.exposure_time:+d}µs)" + ) + self.exposure_time = new_exposure + self.set_camera_config( + self.exposure_time, self.gain + ) + elif new_exposure is None: + logger.debug( + f"Auto-exposure: {matched_stars} stars, no adjustment needed" + ) + self._last_solve_time = solve_attempt_time + + # Loop over any pending commands + # There may be more than one! + command = True + while command: + try: + command = command_queue.get(block=True, timeout=0.1) + except queue.Empty: + command = "" + continue + except Exception as e: + logger.error(f"CameraInterface: Command error: {e}") + + try: + if command == "debug": + if debug: + debug = False + else: + debug = True + + if command.startswith("set_exp"): + exp_value = command.split(":")[1] + if exp_value == "auto": + # Enable auto-exposure mode + self._auto_exposure_enabled = True + self._last_solve_time = None # Reset solve tracking + if self._auto_exposure_pid is None: + self._auto_exposure_pid = ExposurePIDController() + else: + self._auto_exposure_pid.reset() + console_queue.put("CAM: Auto-Exposure Enabled") + logger.info("Auto-exposure mode enabled") + else: + # Disable auto-exposure and set manual exposure + self._auto_exposure_enabled = False + self.exposure_time = int(exp_value) + self.set_camera_config(self.exposure_time, self.gain) + # Update config to reflect manual exposure value + cfg.set_option("camera_exp", self.exposure_time) + console_queue.put("CAM: Exp=" + str(self.exposure_time)) + logger.info( + f"Manual exposure set: {self.exposure_time}µs" + ) + + if command.startswith("set_gain"): + old_gain = self.gain + self.gain = int(command.split(":")[1]) + self.exposure_time, self.gain = self.set_camera_config( + self.exposure_time, self.gain + ) + console_queue.put("CAM: Gain=" + str(self.gain)) + logger.info(f"Gain changed: {old_gain}x → {self.gain}x") + + if command.startswith("set_ae_handler"): + handler_type = command.split(":")[1] + if self._auto_exposure_pid is not None: + new_handler = None + if handler_type == "sweep": + new_handler = SweepZeroStarHandler( + min_exposure=self._auto_exposure_pid.min_exposure, + max_exposure=self._auto_exposure_pid.max_exposure, + ) + elif handler_type == "exponential": + new_handler = ExponentialSweepZeroStarHandler( + min_exposure=self._auto_exposure_pid.min_exposure, + max_exposure=self._auto_exposure_pid.max_exposure, + ) + elif handler_type == "reset": + new_handler = ResetZeroStarHandler( + reset_exposure=400000 # 0.4s + ) + elif handler_type == "histogram": + new_handler = HistogramZeroStarHandler( + min_exposure=self._auto_exposure_pid.min_exposure, + max_exposure=self._auto_exposure_pid.max_exposure, + ) + else: + logger.warning( + f"Unknown zero-star handler type: {handler_type}" + ) + + if new_handler is not None: + self._auto_exposure_pid._zero_star_handler = ( + new_handler + ) + console_queue.put(f"CAM: AE Handler={handler_type}") + logger.info( + f"Auto-exposure zero-star handler changed to: {handler_type}" + ) + else: + logger.warning( + "Cannot set AE handler: auto-exposure not initialized" + ) + + if command == "exp_up" or command == "exp_dn": + # Manual exposure adjustments disable auto-exposure + self._auto_exposure_enabled = False + if command == "exp_up": + self.exposure_time = int(self.exposure_time * 1.25) + else: + self.exposure_time = int(self.exposure_time * 0.75) + self.set_camera_config(self.exposure_time, self.gain) + console_queue.put("CAM: Exp=" + str(self.exposure_time)) + if command == "exp_save": + # Saving exposure disables auto-exposure and locks to current value + self._auto_exposure_enabled = False + cfg.set_option("camera_exp", self.exposure_time) + cfg.set_option("camera_gain", int(self.gain)) + console_queue.put( + f"CAM: Exp Saved ({self.exposure_time}µs)" + ) + logger.info( + f"Exposure saved and auto-exposure disabled: {self.exposure_time}µs" + ) + + if command.startswith("save"): + filename = command.split(":")[1] + filename = f"{utils.data_dir}/captures/{filename}.png" + self.capture_file(filename) + console_queue.put("CAM: Saved Image") + + if command == "capture_exp_sweep": + # Capture exposure sweep - save both RAW and processed images + # at different exposures for SQM testing + # RAW: 16-bit TIFF to preserve full sensor bit depth + # Processed: 8-bit PNG from normal camera.capture() pipeline + logger.info( + "Starting exposure sweep capture (100 image pairs)" + ) + console_queue.put("CAM: Starting sweep...") + + # Save current settings + original_exposure = self.exposure_time + original_gain = self.gain + original_ae_enabled = self._auto_exposure_enabled + + # Disable auto-exposure during sweep + self._auto_exposure_enabled = False + + # Generate 100 exposure values with logarithmic spacing + # from 25ms (25000µs) to 1s (1000000µs) + min_exp = 25000 # 25ms + max_exp = 1000000 # 1s + num_images = 100 + + # Generate logarithmic sweep using shared utility + sweep_exposures = generate_exposure_sweep( + min_exp, max_exp, num_images + ) + + # Generate timestamp for this sweep session + timestamp = datetime.datetime.now().strftime( + "%Y%m%d_%H%M%S" + ) + + # Create sweep directory + sweep_dir = f"{utils.data_dir}/captures/sweep_{timestamp}" + os.makedirs(sweep_dir, exist_ok=True) + + logger.info(f"Saving sweep to: {sweep_dir}") + console_queue.put(f"CAM: {num_images} image pairs") + + for i, exp_us in enumerate(sweep_exposures, 1): + # Set exposure + self.exposure_time = exp_us + self.set_camera_config(self.exposure_time, self.gain) + + # Flush camera buffer - discard pre-buffered frames with old exposure + # Picamera2 maintains a frame queue, need to flush frames captured + # before the new exposure setting was applied + logger.debug( + f"Flushing camera buffer for {exp_us}µs exposure" + ) + _ = self.capture() # Discard buffered frame 1 + _ = self.capture() # Discard buffered frame 2 + + # Now capture both processed and RAW images with correct exposure + exp_ms = exp_us / 1000 + + # Save processed PNG (8-bit, from camera.capture()) + processed_filename = f"{sweep_dir}/img_{i:03d}_{exp_ms:.2f}ms_processed.png" + self.capture_file(processed_filename) + + # Save RAW TIFF (16-bit, from camera.capture_raw_file()) + raw_filename = ( + f"{sweep_dir}/img_{i:03d}_{exp_ms:.2f}ms_raw.tiff" + ) + self.capture_raw_file(raw_filename) + + # Update console every 10 images to avoid spam + if i % 10 == 0 or i == num_images: + console_queue.put(f"CAM: Sweep {i}/{num_images}") + + logger.debug( + f"Captured sweep images {i}/{num_images}: {exp_ms:.2f}ms (PNG+TIFF)" + ) + + # Restore original settings + self.exposure_time = original_exposure + self.gain = original_gain + self._auto_exposure_enabled = original_ae_enabled + self.set_camera_config(self.exposure_time, self.gain) + + console_queue.put("CAM: Sweep done!") + logger.info( + f"Exposure sweep completed: {num_images} image pairs in {sweep_dir}" + ) + + if command.startswith("stop"): + self.stop_camera() + console_queue.put("CAM: Stopped camera") + if command.startswith("start"): + self.start_camera() + console_queue.put("CAM: Started camera") + except ValueError as e: + logger.error( + f"Error processing camera command '{command}': {str(e)}" + ) + console_queue.put( + f"CAM ERROR: Invalid command format - {str(e)}" + ) + except AttributeError as e: + logger.error( + f"Camera component not initialized for command '{command}': {str(e)}" + ) + console_queue.put("CAM ERROR: Camera not properly initialized") + except Exception as e: + logger.error( + f"Unexpected error processing camera command '{command}': {str(e)}" + ) + console_queue.put(f"CAM ERROR: {str(e)}") + logger.info( + f"CameraInterface: Camera loop exited with command: '{command}'" + ) + except (BrokenPipeError, EOFError, FileNotFoundError): + logger.exception("Error in Camera Loop") diff --git a/python/PiFinder/camera_interface_premerge.py b/python/PiFinder/camera_interface_premerge.py new file mode 100644 index 000000000..073b94fc2 --- /dev/null +++ b/python/PiFinder/camera_interface_premerge.py @@ -0,0 +1,214 @@ +#!/usr/bin/python +# -*- coding:utf-8 -*- +""" +This module is the camera +* Captures images +* Places preview images in queue +* Places solver images in queue +* Takes full res images on demand + +""" + +import os +import queue +import time +from PIL import Image +import numpy as np +from typing import Tuple +import logging + +from PiFinder import state_utils, utils +import PiFinder.pointing_model.quaternion_transforms as qt + +logger = logging.getLogger("Camera.Interface") + + +class CameraInterface: + """The CameraInterface interface.""" + + _camera_started = False + + def initialize(self) -> None: + pass + + def capture(self) -> Image.Image: + return Image.Image() + + def capture_file(self, filename) -> None: + pass + + def set_camera_config( + self, exposure_time: float, gain: float + ) -> Tuple[float, float]: + return (0, 0) + + def get_cam_type(self) -> str: + return "foo" + + def start_camera(self) -> None: + pass + + def stop_camera(self) -> None: + pass + + def get_image_loop( + self, shared_state, camera_image, command_queue, console_queue, cfg + ): + try: + debug = False + + screen_direction = cfg.get_option("screen_direction") + camera_rotation = cfg.get_option("camera_rotation") + + # Set path for test mode image + root_dir = os.path.realpath( + os.path.join(os.path.dirname(__file__), "..", "..") + ) + test_image_path = os.path.join( + root_dir, "test_images", "pifinder_debug_02.png" + ) + + # 60 half-second cycles + sleep_delay = 60 + while True: + sleeping = state_utils.sleep_for_framerate( + shared_state, limit_framerate=False + ) + if sleeping: + # Even in sleep mode, we want to take photos every + # so often to update positions + sleep_delay -= 1 + if sleep_delay > 0: + continue + else: + sleep_delay = 60 + + imu_start = shared_state.imu() + image_start_time = time.time() + if self._camera_started: + if not debug: + base_image = self.capture() + base_image = base_image.convert("L") + rotate_amount = 0 + if camera_rotation is None: + if screen_direction in [ + "right", + "straight", + "flat3", + ]: + rotate_amount = 90 + elif screen_direction == "as_bloom": + rotate_amount = 90 # Specific rotation for AS Bloom + else: + rotate_amount = 270 + else: + base_image = base_image.rotate(int(camera_rotation) * -1) + + base_image = base_image.rotate(rotate_amount) + else: + # Test Mode: load image from disc and wait + base_image = Image.open(test_image_path) + time.sleep(1) + image_end_time = time.time() + # check imu to make sure we're still static + imu_end = shared_state.imu() + + # see if we moved during exposure + if imu_start and imu_end: + # Returns the pointing difference between successive IMU quaternions as + # an angle (radians). Note that this also accounts for rotation around the + # scope axis. Returns an angle in radians. + pointing_diff = qt.get_quat_angular_diff( + imu_start["quat"], imu_end["quat"] + ) + else: + pointing_diff = 0.0 + + camera_image.paste(base_image) + shared_state.set_last_image_metadata( + { + "exposure_start": image_start_time, + "exposure_end": image_end_time, + "imu": imu_end, + "imu_delta": np.rad2deg( + pointing_diff + ), # Pointing change during exposure in degrees + } + ) + + # Loop over any pending commands + # There may be more than one! + command = True + while command: + try: + command = command_queue.get(block=True, timeout=0.1) + except queue.Empty: + command = "" + continue + except Exception as e: + logger.error(f"CameraInterface: Command error: {e}") + + try: + if command == "debug": + if debug: + debug = False + else: + debug = True + + if command.startswith("set_exp"): + self.exposure_time = int(command.split(":")[1]) + self.set_camera_config(self.exposure_time, self.gain) + console_queue.put("CAM: Exp=" + str(self.exposure_time)) + + if command.startswith("set_gain"): + self.gain = int(command.split(":")[1]) + self.exposure_time, self.gain = self.set_camera_config( + self.exposure_time, self.gain + ) + console_queue.put("CAM: Gain=" + str(self.gain)) + + if command == "exp_up" or command == "exp_dn": + if command == "exp_up": + self.exposure_time = int(self.exposure_time * 1.25) + else: + self.exposure_time = int(self.exposure_time * 0.75) + self.set_camera_config(self.exposure_time, self.gain) + console_queue.put("CAM: Exp=" + str(self.exposure_time)) + if command == "exp_save": + console_queue.put("CAM: Exp Saved") + cfg.set_option("camera_exp", self.exposure_time) + cfg.set_option("camera_gain", int(self.gain)) + + if command.startswith("save"): + filename = command.split(":")[1] + filename = f"{utils.data_dir}/captures/{filename}.png" + self.capture_file(filename) + console_queue.put("CAM: Saved Image") + if command.startswith("stop"): + self.stop_camera() + console_queue.put("CAM: Stopped camera") + if command.startswith("start"): + self.start_camera() + console_queue.put("CAM: Started camera") + except ValueError as e: + logger.error( + f"Error processing camera command '{command}': {str(e)}" + ) + console_queue.put( + f"CAM ERROR: Invalid command format - {str(e)}" + ) + except AttributeError as e: + logger.error( + f"Camera component not initialized for command '{command}': {str(e)}" + ) + console_queue.put("CAM ERROR: Camera not properly initialized") + except Exception as e: + logger.error( + f"Unexpected error processing camera command '{command}': {str(e)}" + ) + console_queue.put(f"CAM ERROR: {str(e)}") + logger.info( + f"CameraInterface: Camera loop exited with command: '{command}'" + ) + except (BrokenPipeError, EOFError, FileNotFoundError): + logger.exception("Error in Camera Loop") From b75dd8a4096c3c5bb80b187e33bdc5b844891f55 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Tue, 25 Nov 2025 23:59:45 +0100 Subject: [PATCH 241/253] Fix merge: Compared with camera_interface.py in main and restored changes for Auto Exposure that was lost in merge --- python/PiFinder/camera_interface.py | 134 ++++++++++++++++++++-------- 1 file changed, 98 insertions(+), 36 deletions(-) diff --git a/python/PiFinder/camera_interface.py b/python/PiFinder/camera_interface.py index 821ef7a32..a01b61ec7 100644 --- a/python/PiFinder/camera_interface.py +++ b/python/PiFinder/camera_interface.py @@ -28,7 +28,6 @@ generate_exposure_sweep, ) -# TODO: Check: qt module not used after merge? logger = logging.getLogger("Camera.Interface") @@ -106,21 +105,36 @@ def get_image_loop( # so often to update positions sleep_delay -= 1 if sleep_delay > 0: - # continue in sleep mode continue else: - # reset counter and keep going for a capture sleep_delay = 60 imu_start = shared_state.imu() image_start_time = time.time() if self._camera_started: if not debug: - # actual capture would happen here in a concrete subclass base_image = self.capture() + base_image = base_image.convert("L") + rotate_amount = 0 + if camera_rotation is None: + if screen_direction in [ + "right", + "straight", + "flat3", + ]: + rotate_amount = 90 + elif screen_direction == "as_bloom": + rotate_amount = 90 # Specific rotation for AS Bloom + else: + rotate_amount = 270 + else: + base_image = base_image.rotate(int(camera_rotation) * -1) + + base_image = base_image.rotate(rotate_amount) else: - # debug mode: load test image + # Test Mode: load image from disc and wait base_image = Image.open(test_image_path) + time.sleep(1) image_end_time = time.time() # check imu to make sure we're still static imu_end = shared_state.imu() @@ -143,8 +157,8 @@ def get_image_loop( "exposure_end": image_end_time, "imu": imu_end, "imu_delta": np.rad2deg(pointing_diff), - "exposure_time": getattr(self, "exposure_time", None), - "gain": getattr(self, "gain", None), + "exposure_time": self.exposure_time, + "gain": self.gain, } shared_state.set_last_image_metadata(image_metadata) @@ -188,12 +202,20 @@ def get_image_loop( new_exposure is not None and new_exposure != self.exposure_time ): - # update camera config with new exposure + # Exposure value actually changed - update camera + logger.info( + f"Auto-exposure adjustment: {matched_stars} stars → " + f"{self.exposure_time}µs → {new_exposure}µs " + f"(change: {new_exposure - self.exposure_time:+d}µs)" + ) self.exposure_time = new_exposure - self.exposure_time, self.gain = self.set_camera_config(self.exposure_time, self.gain) - logger.info(f"Auto-exposure set exposure to {new_exposure}") + self.set_camera_config( + self.exposure_time, self.gain + ) elif new_exposure is None: - logger.debug("Auto-exposure returned no change") + logger.debug( + f"Auto-exposure: {matched_stars} stars, no adjustment needed" + ) self._last_solve_time = solve_attempt_time # Loop over any pending commands @@ -252,23 +274,42 @@ def get_image_loop( handler_type = command.split(":")[1] if self._auto_exposure_pid is not None: new_handler = None - # Choose from available handlers if handler_type == "sweep": - new_handler = SweepZeroStarHandler() - elif handler_type == "exp": - new_handler = ExponentialSweepZeroStarHandler() + new_handler = SweepZeroStarHandler( + min_exposure=self._auto_exposure_pid.min_exposure, + max_exposure=self._auto_exposure_pid.max_exposure, + ) + elif handler_type == "exponential": + new_handler = ExponentialSweepZeroStarHandler( + min_exposure=self._auto_exposure_pid.min_exposure, + max_exposure=self._auto_exposure_pid.max_exposure, + ) elif handler_type == "reset": - new_handler = ResetZeroStarHandler() - elif handler_type == "hist": - new_handler = HistogramZeroStarHandler() - if new_handler: - self._auto_exposure_pid.set_zero_star_handler(new_handler) - console_queue.put(f"CAM: Set AE handler to {handler_type}") - logger.info(f"Auto-exposure handler set: {handler_type}") + new_handler = ResetZeroStarHandler( + reset_exposure=400000 # 0.4s + ) + elif handler_type == "histogram": + new_handler = HistogramZeroStarHandler( + min_exposure=self._auto_exposure_pid.min_exposure, + max_exposure=self._auto_exposure_pid.max_exposure, + ) else: - console_queue.put("CAM: Unknown AE handler") + logger.warning( + f"Unknown zero-star handler type: {handler_type}" + ) + + if new_handler is not None: + self._auto_exposure_pid._zero_star_handler = ( + new_handler + ) + console_queue.put(f"CAM: AE Handler={handler_type}") + logger.info( + f"Auto-exposure zero-star handler changed to: {handler_type}" + ) else: - console_queue.put("CAM: AE PID not initialized") + logger.warning( + "Cannot set AE handler: auto-exposure not initialized" + ) if command == "exp_up" or command == "exp_dn": # Manual exposure adjustments disable auto-exposure @@ -276,7 +317,7 @@ def get_image_loop( if command == "exp_up": self.exposure_time = int(self.exposure_time * 1.25) else: - self.exposure_time = int(self.exposure_time * 0.8) + self.exposure_time = int(self.exposure_time * 0.75) self.set_camera_config(self.exposure_time, self.gain) console_queue.put("CAM: Exp=" + str(self.exposure_time)) if command == "exp_save": @@ -339,18 +380,39 @@ def get_image_loop( console_queue.put(f"CAM: {num_images} image pairs") for i, exp_us in enumerate(sweep_exposures, 1): - # set exposure and capture image pairs - self.exposure_time = int(exp_us) + # Set exposure + self.exposure_time = exp_us self.set_camera_config(self.exposure_time, self.gain) - # save processed image - filename_proc = f"{sweep_dir}/proc_{i:03d}.png" - self.capture_file(filename_proc) - # save raw (if supported) - filename_raw = f"{sweep_dir}/raw_{i:03d}.tiff" - try: - self.capture_raw_file(filename_raw) - except Exception: - logger.debug("Raw capture not supported on this camera") + + # Flush camera buffer - discard pre-buffered frames with old exposure + # Picamera2 maintains a frame queue, need to flush frames captured + # before the new exposure setting was applied + logger.debug( + f"Flushing camera buffer for {exp_us}µs exposure" + ) + _ = self.capture() # Discard buffered frame 1 + _ = self.capture() # Discard buffered frame 2 + + # Now capture both processed and RAW images with correct exposure + exp_ms = exp_us / 1000 + + # Save processed PNG (8-bit, from camera.capture()) + processed_filename = f"{sweep_dir}/img_{i:03d}_{exp_ms:.2f}ms_processed.png" + self.capture_file(processed_filename) + + # Save RAW TIFF (16-bit, from camera.capture_raw_file()) + raw_filename = ( + f"{sweep_dir}/img_{i:03d}_{exp_ms:.2f}ms_raw.tiff" + ) + self.capture_raw_file(raw_filename) + + # Update console every 10 images to avoid spam + if i % 10 == 0 or i == num_images: + console_queue.put(f"CAM: Sweep {i}/{num_images}") + + logger.debug( + f"Captured sweep images {i}/{num_images}: {exp_ms:.2f}ms (PNG+TIFF)" + ) # Restore original settings self.exposure_time = original_exposure From 5dffb1513c2a17a8e7fcd51df02c05a89e3f1e9c Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Wed, 26 Nov 2025 00:00:06 +0100 Subject: [PATCH 242/253] Update as_dream --> as_bloom from main --- python/PiFinder/pointing_model/imu_dead_reckoning.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/python/PiFinder/pointing_model/imu_dead_reckoning.py b/python/PiFinder/pointing_model/imu_dead_reckoning.py index 29ed49b3f..382df5051 100644 --- a/python/PiFinder/pointing_model/imu_dead_reckoning.py +++ b/python/PiFinder/pointing_model/imu_dead_reckoning.py @@ -224,7 +224,7 @@ def get_screen_direction_q_imu2cam(screen_direction: str) -> quaternion.quaterni # Rotate -90° around z_imu' to align with the camera cooridnates q2 = qt.axis_angle2quat([0, 0, 1], -np.pi / 2) q_imu2cam = (q1 * q2).normalized() - elif screen_direction == "as_dream": # TODO: Propose to rename to "back"? + elif screen_direction == "as_bloom": # As Dream: # Camera points back up from the screen # NOTE: Need to check if the orientation of the camera is correct From a35c72b5af0f01e4f7b0d6b1c9d852af9358825d Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Wed, 26 Nov 2025 00:15:06 +0100 Subject: [PATCH 243/253] Add TODO --- python/PiFinder/calc_utils.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/python/PiFinder/calc_utils.py b/python/PiFinder/calc_utils.py index 8c81035b8..3161c0cda 100644 --- a/python/PiFinder/calc_utils.py +++ b/python/PiFinder/calc_utils.py @@ -159,7 +159,7 @@ def aim_degrees(shared_state, mount_type, screen_direction, target): az_diff = target_az - solution["Az"] az_diff = (az_diff + 180) % 360 - 180 if screen_direction in ["flat", "as_bloom"]: - az_diff *= -1 + az_diff *= -1 # TODO: Why should this depend on the screen type? alt_diff = target_alt - solution["Alt"] alt_diff = (alt_diff + 180) % 360 - 180 From 1ad6aaff71e90c10dbca632e60789f5223843d67 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Wed, 26 Nov 2025 00:16:09 +0100 Subject: [PATCH 244/253] Update initialized_solved_dict() to have same dict keys as main. --- python/PiFinder/pointing_model/astro_coords.py | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/python/PiFinder/pointing_model/astro_coords.py b/python/PiFinder/pointing_model/astro_coords.py index 9c90d1d88..1e7c0148f 100644 --- a/python/PiFinder/pointing_model/astro_coords.py +++ b/python/PiFinder/pointing_model/astro_coords.py @@ -131,15 +131,16 @@ def initialized_solved_dict() -> dict: "Roll": None, }, "imu_quat": None, # IMU quaternion as numpy quaternion (scalar-first) - # Alt, Az [deg] of scope - Not used in Autoexposure? TODO: Remove? - #"Alt": None, - #"Az": None, - #"solve_source": None, - Not used in Autoexposure? TODO: Remove? + # Alt, Az [deg] of scope: + "Alt": None, + "Az": None, + # Diagnostics: + "solve_source": None, "solve_time": None, "cam_solve_time": 0, "last_solve_attempt": 0, # Timestamp of last solve attempt - tracks exposure_end of last processed image "last_solve_success": None, # Timestamp of last successful solve - #"constellation": None, - Not used in Autoexposure? TODO: Remove? + "constellation": None, } return solved From ac7cac7cd37472e58b8f5590bed00c815a99f7d5 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Wed, 26 Nov 2025 00:29:53 +0100 Subject: [PATCH 245/253] Copy from main and pre-merge for debugging --- python/PiFinder/solver_main.py | 279 +++++++++++++++++++++++++++++ python/PiFinder/solver_premerge.py | 222 +++++++++++++++++++++++ 2 files changed, 501 insertions(+) create mode 100644 python/PiFinder/solver_main.py create mode 100644 python/PiFinder/solver_premerge.py diff --git a/python/PiFinder/solver_main.py b/python/PiFinder/solver_main.py new file mode 100644 index 000000000..5964e0e11 --- /dev/null +++ b/python/PiFinder/solver_main.py @@ -0,0 +1,279 @@ +#!/usr/bin/python +# -*- coding:utf-8 -*- +""" +This module is the solver +* runs loop looking for new images +* tries to solve them +* If solved, emits solution into queue + +""" + +from PiFinder.multiproclogging import MultiprocLogging +import queue +import numpy as np +import time +import logging +import sys +from time import perf_counter as precision_timestamp +import os +import threading + +from PiFinder import state_utils +from PiFinder import utils + +sys.path.append(str(utils.tetra3_dir)) +import tetra3 +from tetra3 import cedar_detect_client + +logger = logging.getLogger("Solver") + + +def solver( + shared_state, + solver_queue, + camera_image, + console_queue, + log_queue, + align_command_queue, + align_result_queue, + is_debug=False, +): + MultiprocLogging.configurer(log_queue) + logger.debug("Starting Solver") + t3 = tetra3.Tetra3( + str(utils.cwd_dir / "PiFinder/tetra3/tetra3/data/default_database.npz") + ) + align_ra = 0 + align_dec = 0 + solved = { + # RA, Dec, Roll solved at the center of the camera FoV + # update by integrator + "camera_center": { + "RA": None, + "Dec": None, + "Roll": None, + "Alt": None, + "Az": None, + }, + # RA, Dec, Roll from the camera, not + # affected by IMU in integrator + "camera_solve": { + "RA": None, + "Dec": None, + "Roll": None, + }, + # RA, Dec, Roll at the target pixel + "RA": None, + "Dec": None, + "Roll": None, + "imu_pos": None, + "solve_time": None, + "cam_solve_time": 0, + "last_solve_attempt": 0, # Timestamp of last solve attempt - tracks exposure_end of last processed image + "last_solve_success": None, # Timestamp of last successful solve + } + + centroids = [] + log_no_stars_found = True + + while True: + logger.info("Starting Solver Loop") + # Start cedar detect server + try: + cedar_detect = cedar_detect_client.CedarDetectClient( + binary_path=str(utils.cwd_dir / "../bin/cedar-detect-server-") + + shared_state.arch() + ) + except FileNotFoundError as e: + logger.warning( + "Not using cedar_detect, as corresponding file '%s' could not be found", + e.filename, + ) + cedar_detect = None + except ValueError: + logger.exception("Not using cedar_detect") + cedar_detect = None + + try: + while True: + # Loop over any pending commands + # There may be more than one! + command = True + while command: + try: + command = align_command_queue.get(block=False) + print(f"the command is {command}") + except queue.Empty: + command = False + + if command is not False: + if command[0] == "align_on_radec": + logger.debug("Align Command Received") + # search image pixels to find the best match + # for this RA/DEC and set it as alignment pixel + align_ra = command[1] + align_dec = command[2] + + if command[0] == "align_cancel": + align_ra = 0 + align_dec = 0 + + state_utils.sleep_for_framerate(shared_state) + + # use the time the exposure started here to + # reject images started before the last solve + # which might be from the IMU + try: + last_image_metadata = shared_state.last_image_metadata() + except (BrokenPipeError, ConnectionResetError) as e: + logger.error(f"Lost connection to shared state manager: {e}") + + # Check if we should process this image + is_new_image = ( + last_image_metadata["exposure_end"] > solved["last_solve_attempt"] + ) + is_stationary = last_image_metadata["imu_delta"] < 1 + + if is_new_image and not is_stationary: + logger.debug( + f"Skipping image - IMU delta {last_image_metadata['imu_delta']:.2f}° >= 1° (moving)" + ) + + if is_new_image and is_stationary: + img = camera_image.copy() + img = img.convert(mode="L") + np_image = np.asarray(img, dtype=np.uint8) + + # Mark that we're attempting a solve - use image exposure_end timestamp + # This is more accurate than wall clock and ties the attempt to the actual image + solved["last_solve_attempt"] = last_image_metadata["exposure_end"] + + t0 = precision_timestamp() + if cedar_detect is None: + # Use old tetr3 centroider + centroids = tetra3.get_centroids_from_image(np_image) + else: + centroids = cedar_detect.extract_centroids( + np_image, sigma=8, max_size=10, use_binned=True + ) + t_extract = (precision_timestamp() - t0) * 1000 + logger.debug( + "File %s, extracted %d centroids in %.2fms" + % ("camera", len(centroids), t_extract) + ) + + if len(centroids) == 0: + if log_no_stars_found: + logger.info("No stars found, skipping (Logged only once)") + log_no_stars_found = False + # Clear solve results to mark solve as failed (otherwise old values persist) + solved["RA"] = None + solved["Dec"] = None + solved["Matches"] = 0 + else: + log_no_stars_found = True + _solver_args = {} + if align_ra != 0 and align_dec != 0: + _solver_args["target_sky_coord"] = [[align_ra, align_dec]] + + solution = t3.solve_from_centroids( + centroids, + (512, 512), + fov_estimate=12.0, + fov_max_error=4.0, + match_max_error=0.005, + # return_matches=True, + target_pixel=shared_state.solve_pixel(), + solve_timeout=1000, + **_solver_args, + ) + + if "matched_centroids" in solution: + # Don't clutter printed solution with these fields. + # del solution['matched_centroids'] + # del solution['matched_stars'] + del solution["matched_catID"] + del solution["pattern_centroids"] + del solution["epoch_equinox"] + del solution["epoch_proper_motion"] + del solution["cache_hit_fraction"] + + solved |= solution + + total_tetra_time = t_extract + solved["T_solve"] + if total_tetra_time > 1000: + console_queue.put(f"SLV: Long: {total_tetra_time}") + logger.warning("Long solver time: %i", total_tetra_time) + + if solved["RA"] is not None: + # RA, Dec, Roll at the center of the camera's FoV: + solved["camera_center"]["RA"] = solved["RA"] + solved["camera_center"]["Dec"] = solved["Dec"] + solved["camera_center"]["Roll"] = solved["Roll"] + + # RA, Dec, Roll at the center of the camera's not imu: + solved["camera_solve"]["RA"] = solved["RA"] + solved["camera_solve"]["Dec"] = solved["Dec"] + solved["camera_solve"]["Roll"] = solved["Roll"] + # RA, Dec, Roll at the target pixel: + solved["RA"] = solved["RA_target"] + solved["Dec"] = solved["Dec_target"] + if last_image_metadata["imu"]: + solved["imu_pos"] = last_image_metadata["imu"]["pos"] + solved["imu_quat"] = last_image_metadata["imu"]["quat"] + else: + solved["imu_pos"] = None + solved["imu_quat"] = None + solved["solve_time"] = time.time() + solved["cam_solve_time"] = solved["solve_time"] + # Mark successful solve - use same timestamp as last_solve_attempt for comparison + solved["last_solve_success"] = solved["last_solve_attempt"] + + logger.info( + f"Solve SUCCESS - {len(centroids)} centroids → " + f"{solved.get('Matches', 0)} matches, " + f"RMSE: {solved.get('RMSE', 0):.1f}px" + ) + + # See if we are waiting for alignment + if align_ra != 0 and align_dec != 0: + if solved.get("x_target") is not None: + align_target_pixel = ( + solved["y_target"], + solved["x_target"], + ) + logger.debug(f"Align {align_target_pixel=}") + align_result_queue.put( + ["aligned", align_target_pixel] + ) + align_ra = 0 + align_dec = 0 + solved["x_target"] = None + solved["y_target"] = None + else: + # Centroids found but solve failed - clear Matches + solved["Matches"] = 0 + logger.warning( + f"Solve FAILED - {len(centroids)} centroids detected but " + f"pattern match failed (FOV est: 12.0°, max err: 4.0°)" + ) + + # Always push to queue after every solve attempt (success or failure) + solver_queue.put(solved) + except EOFError as eof: + logger.error(f"Main process no longer running for solver: {eof}") + logger.exception(eof) # This logs the full stack trace + # Optionally log additional context + logger.error(f"Current solver state: {solved}") # If you have state info + except Exception as e: + logger.error(f"Exception in Solver: {e.__class__.__name__}: {str(e)}") + logger.exception(e) # Logs the full stack trace + # Log additional context that might be helpful + logger.error(f"Current process ID: {os.getpid()}") + logger.error(f"Current thread: {threading.current_thread().name}") + try: + logger.error( + f"Active threads: {[t.name for t in threading.enumerate()]}" + ) + except Exception as e: + pass # Don't let diagnostic logging fail diff --git a/python/PiFinder/solver_premerge.py b/python/PiFinder/solver_premerge.py new file mode 100644 index 000000000..026ccb8f7 --- /dev/null +++ b/python/PiFinder/solver_premerge.py @@ -0,0 +1,222 @@ +#!/usr/bin/python +# -*- coding:utf-8 -*- +""" +This module is the solver +* runs loop looking for new images +* tries to solve them +* If solved, emits solution into queue + +""" + +from PiFinder.multiproclogging import MultiprocLogging +import queue +import numpy as np +import time +import logging +import sys +from time import perf_counter as precision_timestamp +import os +import threading + +from PiFinder import state_utils +from PiFinder import utils +from PiFinder.pointing_model.astro_coords import initialized_solved_dict + +sys.path.append(str(utils.tetra3_dir)) +import tetra3 +from tetra3 import cedar_detect_client + +logger = logging.getLogger("Solver") + + +def solver( + shared_state, + solver_queue, + camera_image, + console_queue, + log_queue, + align_command_queue, + align_result_queue, + is_debug=False, + max_imu_ang_during_exposure=1.0, # Max allowed turn during exp [degrees] +): + MultiprocLogging.configurer(log_queue) + logger.debug("Starting Solver") + t3 = tetra3.Tetra3( + str(utils.cwd_dir / "PiFinder/tetra3/tetra3/data/default_database.npz") + ) + last_solve_time = 0 + align_ra = 0 + align_dec = 0 + # Dict of RA, Dec, etc. initialized to None: + solved = initialized_solved_dict() + + centroids = [] + log_no_stars_found = True + + while True: + logger.info("Starting Solver Loop") + # Start cedar detect server + try: + cedar_detect = cedar_detect_client.CedarDetectClient( + binary_path=str(utils.cwd_dir / "../bin/cedar-detect-server-") + + shared_state.arch() + ) + except FileNotFoundError as e: + logger.warning( + "Not using cedar_detect, as corresponding file '%s' could not be found", + e.filename, + ) + cedar_detect = None + except ValueError: + logger.exception("Not using cedar_detect") + cedar_detect = None + + try: + while True: + # Loop over any pending commands + # There may be more than one! + command = True + while command: + try: + command = align_command_queue.get(block=False) + print(f"the command is {command}") + except queue.Empty: + command = False + + if command is not False: + if command[0] == "align_on_radec": + logger.debug("Align Command Received") + # search image pixels to find the best match + # for this RA/DEC and set it as alignment pixel + align_ra = command[1] + align_dec = command[2] + + if command[0] == "align_cancel": + align_ra = 0 + align_dec = 0 + + state_utils.sleep_for_framerate(shared_state) + + # use the time the exposure started here to + # reject images started before the last solve + # which might be from the IMU + try: + last_image_metadata = shared_state.last_image_metadata() + except (BrokenPipeError, ConnectionResetError) as e: + logger.error(f"Lost connection to shared state manager: {e}") + if ( + last_image_metadata["exposure_end"] > (last_solve_time) + and last_image_metadata["imu_delta"] < max_imu_ang_during_exposure + ): + img = camera_image.copy() + img = img.convert(mode="L") + np_image = np.asarray(img, dtype=np.uint8) + + t0 = precision_timestamp() + if cedar_detect is None: + # Use old tetr3 centroider + centroids = tetra3.get_centroids_from_image(np_image) + else: + centroids = cedar_detect.extract_centroids( + np_image, sigma=8, max_size=10, use_binned=True + ) + t_extract = (precision_timestamp() - t0) * 1000 + logger.debug( + "File %s, extracted %d centroids in %.2fms" + % ("camera", len(centroids), t_extract) + ) + + if len(centroids) == 0: + if log_no_stars_found: + logger.info("No stars found, skipping (Logged only once)") + log_no_stars_found = False + continue + else: + log_no_stars_found = True + _solver_args = {} + if align_ra != 0 and align_dec != 0: + _solver_args["target_sky_coord"] = [[align_ra, align_dec]] + + solution = t3.solve_from_centroids( + centroids, + (512, 512), + fov_estimate=12.0, + fov_max_error=4.0, + match_max_error=0.005, + # return_matches=True, + target_pixel=shared_state.solve_pixel(), + solve_timeout=1000, + **_solver_args, + ) + + if "matched_centroids" in solution: + # Don't clutter printed solution with these fields. + # del solution['matched_centroids'] + # del solution['matched_stars'] + del solution["matched_catID"] + del solution["pattern_centroids"] + del solution["epoch_equinox"] + del solution["epoch_proper_motion"] + del solution["cache_hit_fraction"] + + solved |= solution + + total_tetra_time = t_extract + solved["T_solve"] + if total_tetra_time > 1000: + console_queue.put(f"SLV: Long: {total_tetra_time}") + logger.warning("Long solver time: %i", total_tetra_time) + + if solved["RA"] is not None: + # RA, Dec, Roll at the center of the camera's FoV: + solved["camera_center"]["RA"] = solved["RA"] + solved["camera_center"]["Dec"] = solved["Dec"] + solved["camera_center"]["Roll"] = solved["Roll"] + + # RA, Dec, Roll at the center of the camera's not imu: + solved["camera_solve"]["RA"] = solved["RA"] + solved["camera_solve"]["Dec"] = solved["Dec"] + solved["camera_solve"]["Roll"] = solved["Roll"] + # RA, Dec, Roll at the target pixel: + solved["RA"] = solved["RA_target"] + solved["Dec"] = solved["Dec_target"] + if last_image_metadata["imu"]: + solved["imu_quat"] = last_image_metadata["imu"]["quat"] + else: + solved["imu_quat"] = None + solved["solve_time"] = time.time() + solved["cam_solve_time"] = solved["solve_time"] + solver_queue.put(solved) + + # See if we are waiting for alignment + if align_ra != 0 and align_dec != 0: + if solved.get("x_target") is not None: + align_target_pixel = ( + solved["y_target"], + solved["x_target"], + ) + logger.debug(f"Align {align_target_pixel=}") + align_result_queue.put(["aligned", align_target_pixel]) + align_ra = 0 + align_dec = 0 + solved["x_target"] = None + solved["y_target"] = None + + last_solve_time = last_image_metadata["exposure_end"] + except EOFError as eof: + logger.error(f"Main process no longer running for solver: {eof}") + logger.exception(eof) # This logs the full stack trace + # Optionally log additional context + logger.error(f"Current solver state: {solved}") # If you have state info + except Exception as e: + logger.error(f"Exception in Solver: {e.__class__.__name__}: {str(e)}") + logger.exception(e) # Logs the full stack trace + # Log additional context that might be helpful + logger.error(f"Current process ID: {os.getpid()}") + logger.error(f"Current thread: {threading.current_thread().name}") + try: + logger.error( + f"Active threads: {[t.name for t in threading.enumerate()]}" + ) + except Exception as e: + pass # Don't let diagnostic logging fail From a543144e60e3272fcbd43dc936ebdf95e0a6cd4d Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Wed, 26 Nov 2025 00:47:49 +0100 Subject: [PATCH 246/253] Fix merge issues. Align `solve.py` with main --- python/PiFinder/solver.py | 20 ++++++++------------ 1 file changed, 8 insertions(+), 12 deletions(-) diff --git a/python/PiFinder/solver.py b/python/PiFinder/solver.py index 764b8797b..58c73513e 100644 --- a/python/PiFinder/solver.py +++ b/python/PiFinder/solver.py @@ -110,7 +110,7 @@ def solver( last_image_metadata["exposure_end"] > solved["last_solve_attempt"] ) # Use configured max_imu_ang_during_exposure (degrees) - is_stationary = last_image_metadata.get("imu_delta", float("inf")) < max_imu_ang_during_exposure + is_stationary = last_image_metadata["imu_delta"] < max_imu_ang_during_exposure if is_new_image and not is_stationary: logger.debug( @@ -183,29 +183,25 @@ def solver( console_queue.put(f"SLV: Long: {total_tetra_time}") logger.warning("Long solver time: %i", total_tetra_time) - # RA, Dec, Roll at the center of the camera's FoV: - # TODO: Check merge: where did .get() come from? - if solved.get("RA") is not None: + if solved["RA"] is not None: + # RA, Dec, Roll at the center of the camera's FoV: solved["camera_center"]["RA"] = solved["RA"] solved["camera_center"]["Dec"] = solved["Dec"] solved["camera_center"]["Roll"] = solved["Roll"] - # RA, Dec, Roll at the camera solve (no IMU compensation) + # RA, Dec, Roll at the camera center from plate-solve (no IMU compensation) solved["camera_solve"]["RA"] = solved["RA"] solved["camera_solve"]["Dec"] = solved["Dec"] solved["camera_solve"]["Roll"] = solved["Roll"] # RA, Dec, Roll at the target pixel: - # Replace the central RA/Dec with the RA/Dec for the target pixel - solved["RA"] = solved.get("RA_target", solved["RA"]) - solved["Dec"] = solved.get("Dec_target", solved["Dec"]) + # Replace the camera center RA/Dec with the RA/Dec for the target pixel + solved["RA"] = solved["RA_target"] + solved["Dec"] = solved["Dec_target"] if last_image_metadata.get("imu"): - # TODO: imu_pos isn't used any more? - solved["imu_pos"] = last_image_metadata["imu"].get("pos") - solved["imu_quat"] = last_image_metadata["imu"].get("quat") + solved["imu_quat"] = last_image_metadata["imu"]["quat"] else: - solved["imu_pos"] = None solved["imu_quat"] = None solved["solve_time"] = time.time() From 31d1cebc2861fc41f4368d45677e7cf528f98872 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Wed, 26 Nov 2025 00:51:34 +0100 Subject: [PATCH 247/253] Update comment --- python/PiFinder/ui/status.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/python/PiFinder/ui/status.py b/python/PiFinder/ui/status.py index 836bbeaae..69aedc752 100644 --- a/python/PiFinder/ui/status.py +++ b/python/PiFinder/ui/status.py @@ -265,7 +265,7 @@ def update_status_dict(self): self.status_dict["IMU"] = f"{mtext : >11}" + " " + str(imu["status"]) self.status_dict["IMU PS"] = ( "imu NA" - # f"{imu['quat'][0] : >6.1f}/{imu['quat'][2] : >6.1f}" # TODO: Quick hack for now. This was changed from imu["pos"] and should be changed. + # f"{imu['quat'][0] : >6.1f}/{imu['quat'][2] : >6.1f}" ) location = self.shared_state.location() sats = self.shared_state.sats() From c41785c7b357fbb04a0ead42069e52841ee6093e Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Wed, 26 Nov 2025 17:04:39 +0100 Subject: [PATCH 248/253] Resolving merge conflicts in integrator.py --- python/PiFinder/integrator.py | 23 +++++++++++++---------- 1 file changed, 13 insertions(+), 10 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 8b9f82ccb..510bf060c 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -67,12 +67,6 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa pass if type(next_image_solve) is dict: - #--------- TODO: Merge removed this? -------- - # We have a new image solve: Use plate-solving for RA/Dec - #solved = next_image_solve - #update_plate_solve_and_imu(imu_dead_reckoning, solved) - #-------------------------------------------- - # For camera solves, always start from last successful camera solve # NOT from shared_state (which may contain IMU drift) # This prevents IMU noise accumulation during failed solves @@ -98,6 +92,10 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa location = shared_state.location() dt = shared_state.datetime() + # Set location for altaz calculations. + # TODO: Is itnecessary to set location? + # TODO: Altaz doesn't seem to be required for catalogs when in + # EQ mode? Could be disabled in future when in EQ mode? if location and dt: # We have position and time/date and a valid solve! calc_utils.sf_utils.set_location( @@ -105,6 +103,9 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa location.lon, location.altitude, ) + + + alt, az = calc_utils.sf_utils.radec_to_altaz( solved["RA"], solved["Dec"], @@ -124,7 +125,8 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa # Experimental: For monitoring roll offset # Estimate the roll offset due misalignment of the # camera sensor with the Pole-to-Source great circle. - solved["Roll_offset"] = estimate_roll_offset(solved, dt) + #solved["Roll_offset"] = estimate_roll_offset(solved, dt) + # Find the roll at the target RA/Dec. Note that this doesn't include the # roll offset so it's not the roll that the PiFinder camear sees but the # roll relative to the celestial pole @@ -148,7 +150,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa ) # Update IMU-dead-reckoning system with the new plate-solve - update_plate_solve_and_imu(imu_dead_reckoning, solved) + #update_plate_solve_and_imu(imu_dead_reckoning, solved) # For failed solves, preserve ALL position data from previous solve # Don't recalculate from GPS (causes drift from GPS noise) @@ -173,6 +175,8 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa shared_state.set_solution(solved) shared_state.set_solve_state(True) + #============== Above from main ============== + elif imu_dead_reckoning.tracking: # Previous plate-solve exists so use IMU dead-reckoning from # the last plate solved coordinates. @@ -185,7 +189,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa if ( solved["RA"] and solved["solve_time"] > last_solve_time - and solved.get("solve_source") == "IMU" + and solved["solve_source"] == "IMU" ): last_solve_time = time.time() @@ -196,7 +200,6 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa # TODO: Is it necessary to set location? # TODO: Altaz doesn't seem to be required for catalogs when in # EQ mode? Could be disabled in future when in EQ mode? - # TODO: Is it necessary to set location? if location: calc_utils.sf_utils.set_location( location.lat, location.lon, location.altitude From ccf5924477a9d7ddcdb050880abf711c1b5fe2c1 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Wed, 10 Dec 2025 16:51:07 +0100 Subject: [PATCH 249/253] Attempt to align the merge with both branches --- python/PiFinder/integrator.py | 92 ++++++----------------------------- 1 file changed, 15 insertions(+), 77 deletions(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 510bf060c..6ab8036cc 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -74,6 +74,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa solved = copy.deepcopy(last_image_solve) # If no successful solve yet, keep initial solved dict + #========= From main ====================== # Update solve metadata (always needed for auto-exposure) for key in [ "Matches", @@ -88,70 +89,6 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa if next_image_solve.get("RA") is not None: solved.update(next_image_solve) - # Recalculate Alt/Az for NEW successful solve - location = shared_state.location() - dt = shared_state.datetime() - - # Set location for altaz calculations. - # TODO: Is itnecessary to set location? - # TODO: Altaz doesn't seem to be required for catalogs when in - # EQ mode? Could be disabled in future when in EQ mode? - if location and dt: - # We have position and time/date and a valid solve! - calc_utils.sf_utils.set_location( - location.lat, - location.lon, - location.altitude, - ) - - - - alt, az = calc_utils.sf_utils.radec_to_altaz( - solved["RA"], - solved["Dec"], - dt, - ) - solved["Alt"] = alt - solved["Az"] = az - - alt, az = calc_utils.sf_utils.radec_to_altaz( - solved["camera_center"]["RA"], - solved["camera_center"]["Dec"], - dt, - ) - solved["camera_center"]["Alt"] = alt - solved["camera_center"]["Az"] = az - - # Experimental: For monitoring roll offset - # Estimate the roll offset due misalignment of the - # camera sensor with the Pole-to-Source great circle. - #solved["Roll_offset"] = estimate_roll_offset(solved, dt) - - # Find the roll at the target RA/Dec. Note that this doesn't include the - # roll offset so it's not the roll that the PiFinder camear sees but the - # roll relative to the celestial pole - roll_target_calculated = calc_utils.sf_utils.radec_to_roll( - solved["RA"], solved["Dec"], dt - ) - # Compensate for the roll offset. This gives the roll at the target - # as seen by the camera. - solved["Roll"] = roll_target_calculated + solved["Roll_offset"] - - # calculate roll for camera center - roll_target_calculated = calc_utils.sf_utils.radec_to_roll( - solved["camera_center"]["RA"], - solved["camera_center"]["Dec"], - dt, - ) - # Compensate for the roll offset. This gives the roll at the target - # as seen by the camera. - solved["camera_center"]["Roll"] = ( - roll_target_calculated + solved["Roll_offset"] - ) - - # Update IMU-dead-reckoning system with the new plate-solve - #update_plate_solve_and_imu(imu_dead_reckoning, solved) - # For failed solves, preserve ALL position data from previous solve # Don't recalculate from GPS (causes drift from GPS noise) @@ -159,23 +96,21 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa if solved["RA"] is not None: last_image_solve = copy.deepcopy(solved) solved["solve_source"] = "CAM" - # Calculate constellation for successful solve - solved["constellation"] = ( - calc_utils.sf_utils.radec_to_constellation( - solved["RA"], solved["Dec"] - ) - ) else: # Failed solve - clear constellation solved["solve_source"] = "CAM_FAILED" - solved["constellation"] = "" # Push all camera solves (success and failure) immediately # This ensures auto-exposure sees Matches=0 for failed solves shared_state.set_solution(solved) shared_state.set_solve_state(True) + + # We have a new image solve: Use plate-solving for RA/Dec + update_plate_solve_and_imu(imu_dead_reckoning, solved) - #============== Above from main ============== + # TODO: main also calculates (alt, az) for target & camera center. + # Is this needed? + #==================================================== elif imu_dead_reckoning.tracking: # Previous plate-solve exists so use IMU dead-reckoning from @@ -189,13 +124,14 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa if ( solved["RA"] and solved["solve_time"] > last_solve_time - and solved["solve_source"] == "IMU" + #and solved["solve_source"] == "IMU" ): - last_solve_time = time.time() + last_solve_time = time.time() # TODO: solve_time is ambiguous because it's also used for IMU dead-reckoning # Try to set date and time location = shared_state.location() dt = shared_state.datetime() + # Set location for roll and altaz calculations. # TODO: Is it necessary to set location? # TODO: Altaz doesn't seem to be required for catalogs when in @@ -211,10 +147,12 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa ) # Update remaining solved keys - # Calculate constellation for IMU dead-reckoning position - solved["constellation"] = calc_utils.sf_utils.radec_to_constellation( + # Calculate constellation for current position + solved["constellation"] = ( + calc_utils.sf_utils.radec_to_constellation( solved["RA"], solved["Dec"] - ) + ) + ) # TODO: Can the outer brackets be omitted? # Set Alt/Az because it's needed for the catalogs for the # Alt/Az mount type. TODO: Can this be moved to the catalog? From 8d569c798c71543148b5d5802f1b9f9c332acca5 Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Wed, 10 Dec 2025 17:08:57 +0100 Subject: [PATCH 250/253] Add comments --- python/PiFinder/integrator.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/python/PiFinder/integrator.py b/python/PiFinder/integrator.py index 6ab8036cc..fd4a446fe 100644 --- a/python/PiFinder/integrator.py +++ b/python/PiFinder/integrator.py @@ -75,6 +75,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa # If no successful solve yet, keep initial solved dict #========= From main ====================== + # TODO: Create a function to update solve? # Update solve metadata (always needed for auto-exposure) for key in [ "Matches", @@ -109,7 +110,7 @@ def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=Fa update_plate_solve_and_imu(imu_dead_reckoning, solved) # TODO: main also calculates (alt, az) for target & camera center. - # Is this needed? + # Don't think this is needed because they are done by the update functions?s #==================================================== elif imu_dead_reckoning.tracking: From 60e8f4533413ec8c283521040d2b5fbbbc7599a8 Mon Sep 17 00:00:00 2001 From: TakKanekoGit <> Date: Thu, 11 Dec 2025 19:08:27 +0000 Subject: [PATCH 251/253] Initialize Imu.__reading_diff --- python/PiFinder/imu_pi.py | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/python/PiFinder/imu_pi.py b/python/PiFinder/imu_pi.py index 4d5b52a48..aa51489ce 100644 --- a/python/PiFinder/imu_pi.py +++ b/python/PiFinder/imu_pi.py @@ -38,7 +38,8 @@ def __init__(self): self.calibration = 0 self.avg_quat = (0, 0, 0, 0) # Scalar-first quaternion: (w, x, y, z) self.__moving = False - + self.__reading_diff = 0.0 + self.last_sample_time = time.time() # Calibration settings @@ -213,6 +214,7 @@ def imu_monitor(shared_state, console_queue, log_queue): imu = Imu() for i in range(10): imu.update() + print(imu) time.sleep(0.5) except Exception as e: logger.exception("Error starting phyiscal IMU", e) From c2ceec94259dd8c37f135604a1df7d9c976e9bdf Mon Sep 17 00:00:00 2001 From: Tak Kaneko <> Date: Thu, 11 Dec 2025 21:52:55 +0100 Subject: [PATCH 252/253] Remove files added for debugging --- python/PiFinder/camera_interface_main.py | 451 ------------------- python/PiFinder/camera_interface_premerge.py | 214 --------- python/PiFinder/integrator_main.py | 302 ------------- python/PiFinder/integrator_main_pre_AE.py | 262 ----------- python/PiFinder/integrator_premerge.py | 292 ------------ 5 files changed, 1521 deletions(-) delete mode 100644 python/PiFinder/camera_interface_main.py delete mode 100644 python/PiFinder/camera_interface_premerge.py delete mode 100644 python/PiFinder/integrator_main.py delete mode 100644 python/PiFinder/integrator_main_pre_AE.py delete mode 100644 python/PiFinder/integrator_premerge.py diff --git a/python/PiFinder/camera_interface_main.py b/python/PiFinder/camera_interface_main.py deleted file mode 100644 index 1b2a03e5b..000000000 --- a/python/PiFinder/camera_interface_main.py +++ /dev/null @@ -1,451 +0,0 @@ -#!/usr/bin/python -# -*- coding:utf-8 -*- -""" -This module is the camera -* Captures images -* Places preview images in queue -* Places solver images in queue -* Takes full res images on demand - -""" - -import datetime -import logging -import os -import queue -import time -from typing import Tuple, Optional - -from PIL import Image - -from PiFinder import state_utils, utils -from PiFinder.auto_exposure import ( - ExposurePIDController, - SweepZeroStarHandler, - ExponentialSweepZeroStarHandler, - ResetZeroStarHandler, - HistogramZeroStarHandler, - generate_exposure_sweep, -) - -logger = logging.getLogger("Camera.Interface") - - -class CameraInterface: - """The CameraInterface interface.""" - - _camera_started = False - _auto_exposure_enabled = False - _auto_exposure_pid: Optional[ExposurePIDController] = None - _last_solve_time: Optional[float] = None - - def initialize(self) -> None: - pass - - def capture(self) -> Image.Image: - return Image.Image() - - def capture_file(self, filename) -> None: - pass - - def capture_raw_file(self, filename) -> None: - pass - - def set_camera_config( - self, exposure_time: float, gain: float - ) -> Tuple[float, float]: - return (0, 0) - - def get_cam_type(self) -> str: - return "foo" - - def start_camera(self) -> None: - pass - - def stop_camera(self) -> None: - pass - - def get_image_loop( - self, shared_state, camera_image, command_queue, console_queue, cfg - ): - try: - debug = False - - # Check if auto-exposure was previously enabled in config - config_exp = cfg.get_option("camera_exp") - if config_exp == "auto": - self._auto_exposure_enabled = True - self._last_solve_time = None - if self._auto_exposure_pid is None: - self._auto_exposure_pid = ExposurePIDController() - else: - self._auto_exposure_pid.reset() - logger.info("Auto-exposure mode enabled from config") - - screen_direction = cfg.get_option("screen_direction") - camera_rotation = cfg.get_option("camera_rotation") - - # Set path for test mode image - root_dir = os.path.realpath( - os.path.join(os.path.dirname(__file__), "..", "..") - ) - test_image_path = os.path.join( - root_dir, "test_images", "pifinder_debug_02.png" - ) - - # 60 half-second cycles - sleep_delay = 60 - while True: - sleeping = state_utils.sleep_for_framerate( - shared_state, limit_framerate=False - ) - if sleeping: - # Even in sleep mode, we want to take photos every - # so often to update positions - sleep_delay -= 1 - if sleep_delay > 0: - continue - else: - sleep_delay = 60 - - imu_start = shared_state.imu() - image_start_time = time.time() - if self._camera_started: - if not debug: - base_image = self.capture() - base_image = base_image.convert("L") - rotate_amount = 0 - if camera_rotation is None: - if screen_direction in [ - "right", - "straight", - "flat3", - ]: - rotate_amount = 90 - elif screen_direction == "as_bloom": - rotate_amount = 90 # Specific rotation for AS Bloom - else: - rotate_amount = 270 - else: - base_image = base_image.rotate(int(camera_rotation) * -1) - - base_image = base_image.rotate(rotate_amount) - else: - # Test Mode: load image from disc and wait - base_image = Image.open(test_image_path) - time.sleep(1) - image_end_time = time.time() - # check imu to make sure we're still static - imu_end = shared_state.imu() - - # see if we moved during exposure - reading_diff = 0 - if imu_start and imu_end: - reading_diff = ( - abs(imu_start["pos"][0] - imu_end["pos"][0]) - + abs(imu_start["pos"][1] - imu_end["pos"][1]) - + abs(imu_start["pos"][2] - imu_end["pos"][2]) - ) - - camera_image.paste(base_image) - image_metadata = { - "exposure_start": image_start_time, - "exposure_end": image_end_time, - "imu": imu_end, - "imu_delta": reading_diff, - "exposure_time": self.exposure_time, - "gain": self.gain, - } - shared_state.set_last_image_metadata(image_metadata) - - # Auto-exposure: adjust based on plate solve results - # Updates as fast as new solve results arrive (naturally rate-limited) - if self._auto_exposure_enabled and self._auto_exposure_pid: - solution = shared_state.solution() - solve_source = ( - solution.get("solve_source") if solution else None - ) - - # Handle camera solves (successful or failed) - if solve_source in ("CAM", "CAM_FAILED"): - matched_stars = solution.get("Matches", 0) - solve_attempt_time = solution.get("last_solve_attempt") - solve_rmse = solution.get("RMSE") - - # Only update on NEW solve results (not re-processing same solution) - # Use last_solve_attempt since it's set for both success and failure - if ( - solve_attempt_time - and solve_attempt_time != self._last_solve_time - ): - rmse_str = ( - f"{solve_rmse:.1f}" - if solve_rmse is not None - else "N/A" - ) - logger.info( - f"Auto-exposure feedback - Stars: {matched_stars}, " - f"RMSE: {rmse_str}, Current exposure: {self.exposure_time}µs" - ) - - # Call PID update (now handles zero stars with recovery mode) - # Pass base_image for histogram analysis in zero-star handler - new_exposure = self._auto_exposure_pid.update( - matched_stars, self.exposure_time, base_image - ) - - if ( - new_exposure is not None - and new_exposure != self.exposure_time - ): - # Exposure value actually changed - update camera - logger.info( - f"Auto-exposure adjustment: {matched_stars} stars → " - f"{self.exposure_time}µs → {new_exposure}µs " - f"(change: {new_exposure - self.exposure_time:+d}µs)" - ) - self.exposure_time = new_exposure - self.set_camera_config( - self.exposure_time, self.gain - ) - elif new_exposure is None: - logger.debug( - f"Auto-exposure: {matched_stars} stars, no adjustment needed" - ) - self._last_solve_time = solve_attempt_time - - # Loop over any pending commands - # There may be more than one! - command = True - while command: - try: - command = command_queue.get(block=True, timeout=0.1) - except queue.Empty: - command = "" - continue - except Exception as e: - logger.error(f"CameraInterface: Command error: {e}") - - try: - if command == "debug": - if debug: - debug = False - else: - debug = True - - if command.startswith("set_exp"): - exp_value = command.split(":")[1] - if exp_value == "auto": - # Enable auto-exposure mode - self._auto_exposure_enabled = True - self._last_solve_time = None # Reset solve tracking - if self._auto_exposure_pid is None: - self._auto_exposure_pid = ExposurePIDController() - else: - self._auto_exposure_pid.reset() - console_queue.put("CAM: Auto-Exposure Enabled") - logger.info("Auto-exposure mode enabled") - else: - # Disable auto-exposure and set manual exposure - self._auto_exposure_enabled = False - self.exposure_time = int(exp_value) - self.set_camera_config(self.exposure_time, self.gain) - # Update config to reflect manual exposure value - cfg.set_option("camera_exp", self.exposure_time) - console_queue.put("CAM: Exp=" + str(self.exposure_time)) - logger.info( - f"Manual exposure set: {self.exposure_time}µs" - ) - - if command.startswith("set_gain"): - old_gain = self.gain - self.gain = int(command.split(":")[1]) - self.exposure_time, self.gain = self.set_camera_config( - self.exposure_time, self.gain - ) - console_queue.put("CAM: Gain=" + str(self.gain)) - logger.info(f"Gain changed: {old_gain}x → {self.gain}x") - - if command.startswith("set_ae_handler"): - handler_type = command.split(":")[1] - if self._auto_exposure_pid is not None: - new_handler = None - if handler_type == "sweep": - new_handler = SweepZeroStarHandler( - min_exposure=self._auto_exposure_pid.min_exposure, - max_exposure=self._auto_exposure_pid.max_exposure, - ) - elif handler_type == "exponential": - new_handler = ExponentialSweepZeroStarHandler( - min_exposure=self._auto_exposure_pid.min_exposure, - max_exposure=self._auto_exposure_pid.max_exposure, - ) - elif handler_type == "reset": - new_handler = ResetZeroStarHandler( - reset_exposure=400000 # 0.4s - ) - elif handler_type == "histogram": - new_handler = HistogramZeroStarHandler( - min_exposure=self._auto_exposure_pid.min_exposure, - max_exposure=self._auto_exposure_pid.max_exposure, - ) - else: - logger.warning( - f"Unknown zero-star handler type: {handler_type}" - ) - - if new_handler is not None: - self._auto_exposure_pid._zero_star_handler = ( - new_handler - ) - console_queue.put(f"CAM: AE Handler={handler_type}") - logger.info( - f"Auto-exposure zero-star handler changed to: {handler_type}" - ) - else: - logger.warning( - "Cannot set AE handler: auto-exposure not initialized" - ) - - if command == "exp_up" or command == "exp_dn": - # Manual exposure adjustments disable auto-exposure - self._auto_exposure_enabled = False - if command == "exp_up": - self.exposure_time = int(self.exposure_time * 1.25) - else: - self.exposure_time = int(self.exposure_time * 0.75) - self.set_camera_config(self.exposure_time, self.gain) - console_queue.put("CAM: Exp=" + str(self.exposure_time)) - if command == "exp_save": - # Saving exposure disables auto-exposure and locks to current value - self._auto_exposure_enabled = False - cfg.set_option("camera_exp", self.exposure_time) - cfg.set_option("camera_gain", int(self.gain)) - console_queue.put( - f"CAM: Exp Saved ({self.exposure_time}µs)" - ) - logger.info( - f"Exposure saved and auto-exposure disabled: {self.exposure_time}µs" - ) - - if command.startswith("save"): - filename = command.split(":")[1] - filename = f"{utils.data_dir}/captures/{filename}.png" - self.capture_file(filename) - console_queue.put("CAM: Saved Image") - - if command == "capture_exp_sweep": - # Capture exposure sweep - save both RAW and processed images - # at different exposures for SQM testing - # RAW: 16-bit TIFF to preserve full sensor bit depth - # Processed: 8-bit PNG from normal camera.capture() pipeline - logger.info( - "Starting exposure sweep capture (100 image pairs)" - ) - console_queue.put("CAM: Starting sweep...") - - # Save current settings - original_exposure = self.exposure_time - original_gain = self.gain - original_ae_enabled = self._auto_exposure_enabled - - # Disable auto-exposure during sweep - self._auto_exposure_enabled = False - - # Generate 100 exposure values with logarithmic spacing - # from 25ms (25000µs) to 1s (1000000µs) - min_exp = 25000 # 25ms - max_exp = 1000000 # 1s - num_images = 100 - - # Generate logarithmic sweep using shared utility - sweep_exposures = generate_exposure_sweep( - min_exp, max_exp, num_images - ) - - # Generate timestamp for this sweep session - timestamp = datetime.datetime.now().strftime( - "%Y%m%d_%H%M%S" - ) - - # Create sweep directory - sweep_dir = f"{utils.data_dir}/captures/sweep_{timestamp}" - os.makedirs(sweep_dir, exist_ok=True) - - logger.info(f"Saving sweep to: {sweep_dir}") - console_queue.put(f"CAM: {num_images} image pairs") - - for i, exp_us in enumerate(sweep_exposures, 1): - # Set exposure - self.exposure_time = exp_us - self.set_camera_config(self.exposure_time, self.gain) - - # Flush camera buffer - discard pre-buffered frames with old exposure - # Picamera2 maintains a frame queue, need to flush frames captured - # before the new exposure setting was applied - logger.debug( - f"Flushing camera buffer for {exp_us}µs exposure" - ) - _ = self.capture() # Discard buffered frame 1 - _ = self.capture() # Discard buffered frame 2 - - # Now capture both processed and RAW images with correct exposure - exp_ms = exp_us / 1000 - - # Save processed PNG (8-bit, from camera.capture()) - processed_filename = f"{sweep_dir}/img_{i:03d}_{exp_ms:.2f}ms_processed.png" - self.capture_file(processed_filename) - - # Save RAW TIFF (16-bit, from camera.capture_raw_file()) - raw_filename = ( - f"{sweep_dir}/img_{i:03d}_{exp_ms:.2f}ms_raw.tiff" - ) - self.capture_raw_file(raw_filename) - - # Update console every 10 images to avoid spam - if i % 10 == 0 or i == num_images: - console_queue.put(f"CAM: Sweep {i}/{num_images}") - - logger.debug( - f"Captured sweep images {i}/{num_images}: {exp_ms:.2f}ms (PNG+TIFF)" - ) - - # Restore original settings - self.exposure_time = original_exposure - self.gain = original_gain - self._auto_exposure_enabled = original_ae_enabled - self.set_camera_config(self.exposure_time, self.gain) - - console_queue.put("CAM: Sweep done!") - logger.info( - f"Exposure sweep completed: {num_images} image pairs in {sweep_dir}" - ) - - if command.startswith("stop"): - self.stop_camera() - console_queue.put("CAM: Stopped camera") - if command.startswith("start"): - self.start_camera() - console_queue.put("CAM: Started camera") - except ValueError as e: - logger.error( - f"Error processing camera command '{command}': {str(e)}" - ) - console_queue.put( - f"CAM ERROR: Invalid command format - {str(e)}" - ) - except AttributeError as e: - logger.error( - f"Camera component not initialized for command '{command}': {str(e)}" - ) - console_queue.put("CAM ERROR: Camera not properly initialized") - except Exception as e: - logger.error( - f"Unexpected error processing camera command '{command}': {str(e)}" - ) - console_queue.put(f"CAM ERROR: {str(e)}") - logger.info( - f"CameraInterface: Camera loop exited with command: '{command}'" - ) - except (BrokenPipeError, EOFError, FileNotFoundError): - logger.exception("Error in Camera Loop") diff --git a/python/PiFinder/camera_interface_premerge.py b/python/PiFinder/camera_interface_premerge.py deleted file mode 100644 index 073b94fc2..000000000 --- a/python/PiFinder/camera_interface_premerge.py +++ /dev/null @@ -1,214 +0,0 @@ -#!/usr/bin/python -# -*- coding:utf-8 -*- -""" -This module is the camera -* Captures images -* Places preview images in queue -* Places solver images in queue -* Takes full res images on demand - -""" - -import os -import queue -import time -from PIL import Image -import numpy as np -from typing import Tuple -import logging - -from PiFinder import state_utils, utils -import PiFinder.pointing_model.quaternion_transforms as qt - -logger = logging.getLogger("Camera.Interface") - - -class CameraInterface: - """The CameraInterface interface.""" - - _camera_started = False - - def initialize(self) -> None: - pass - - def capture(self) -> Image.Image: - return Image.Image() - - def capture_file(self, filename) -> None: - pass - - def set_camera_config( - self, exposure_time: float, gain: float - ) -> Tuple[float, float]: - return (0, 0) - - def get_cam_type(self) -> str: - return "foo" - - def start_camera(self) -> None: - pass - - def stop_camera(self) -> None: - pass - - def get_image_loop( - self, shared_state, camera_image, command_queue, console_queue, cfg - ): - try: - debug = False - - screen_direction = cfg.get_option("screen_direction") - camera_rotation = cfg.get_option("camera_rotation") - - # Set path for test mode image - root_dir = os.path.realpath( - os.path.join(os.path.dirname(__file__), "..", "..") - ) - test_image_path = os.path.join( - root_dir, "test_images", "pifinder_debug_02.png" - ) - - # 60 half-second cycles - sleep_delay = 60 - while True: - sleeping = state_utils.sleep_for_framerate( - shared_state, limit_framerate=False - ) - if sleeping: - # Even in sleep mode, we want to take photos every - # so often to update positions - sleep_delay -= 1 - if sleep_delay > 0: - continue - else: - sleep_delay = 60 - - imu_start = shared_state.imu() - image_start_time = time.time() - if self._camera_started: - if not debug: - base_image = self.capture() - base_image = base_image.convert("L") - rotate_amount = 0 - if camera_rotation is None: - if screen_direction in [ - "right", - "straight", - "flat3", - ]: - rotate_amount = 90 - elif screen_direction == "as_bloom": - rotate_amount = 90 # Specific rotation for AS Bloom - else: - rotate_amount = 270 - else: - base_image = base_image.rotate(int(camera_rotation) * -1) - - base_image = base_image.rotate(rotate_amount) - else: - # Test Mode: load image from disc and wait - base_image = Image.open(test_image_path) - time.sleep(1) - image_end_time = time.time() - # check imu to make sure we're still static - imu_end = shared_state.imu() - - # see if we moved during exposure - if imu_start and imu_end: - # Returns the pointing difference between successive IMU quaternions as - # an angle (radians). Note that this also accounts for rotation around the - # scope axis. Returns an angle in radians. - pointing_diff = qt.get_quat_angular_diff( - imu_start["quat"], imu_end["quat"] - ) - else: - pointing_diff = 0.0 - - camera_image.paste(base_image) - shared_state.set_last_image_metadata( - { - "exposure_start": image_start_time, - "exposure_end": image_end_time, - "imu": imu_end, - "imu_delta": np.rad2deg( - pointing_diff - ), # Pointing change during exposure in degrees - } - ) - - # Loop over any pending commands - # There may be more than one! - command = True - while command: - try: - command = command_queue.get(block=True, timeout=0.1) - except queue.Empty: - command = "" - continue - except Exception as e: - logger.error(f"CameraInterface: Command error: {e}") - - try: - if command == "debug": - if debug: - debug = False - else: - debug = True - - if command.startswith("set_exp"): - self.exposure_time = int(command.split(":")[1]) - self.set_camera_config(self.exposure_time, self.gain) - console_queue.put("CAM: Exp=" + str(self.exposure_time)) - - if command.startswith("set_gain"): - self.gain = int(command.split(":")[1]) - self.exposure_time, self.gain = self.set_camera_config( - self.exposure_time, self.gain - ) - console_queue.put("CAM: Gain=" + str(self.gain)) - - if command == "exp_up" or command == "exp_dn": - if command == "exp_up": - self.exposure_time = int(self.exposure_time * 1.25) - else: - self.exposure_time = int(self.exposure_time * 0.75) - self.set_camera_config(self.exposure_time, self.gain) - console_queue.put("CAM: Exp=" + str(self.exposure_time)) - if command == "exp_save": - console_queue.put("CAM: Exp Saved") - cfg.set_option("camera_exp", self.exposure_time) - cfg.set_option("camera_gain", int(self.gain)) - - if command.startswith("save"): - filename = command.split(":")[1] - filename = f"{utils.data_dir}/captures/{filename}.png" - self.capture_file(filename) - console_queue.put("CAM: Saved Image") - if command.startswith("stop"): - self.stop_camera() - console_queue.put("CAM: Stopped camera") - if command.startswith("start"): - self.start_camera() - console_queue.put("CAM: Started camera") - except ValueError as e: - logger.error( - f"Error processing camera command '{command}': {str(e)}" - ) - console_queue.put( - f"CAM ERROR: Invalid command format - {str(e)}" - ) - except AttributeError as e: - logger.error( - f"Camera component not initialized for command '{command}': {str(e)}" - ) - console_queue.put("CAM ERROR: Camera not properly initialized") - except Exception as e: - logger.error( - f"Unexpected error processing camera command '{command}': {str(e)}" - ) - console_queue.put(f"CAM ERROR: {str(e)}") - logger.info( - f"CameraInterface: Camera loop exited with command: '{command}'" - ) - except (BrokenPipeError, EOFError, FileNotFoundError): - logger.exception("Error in Camera Loop") diff --git a/python/PiFinder/integrator_main.py b/python/PiFinder/integrator_main.py deleted file mode 100644 index 80828a534..000000000 --- a/python/PiFinder/integrator_main.py +++ /dev/null @@ -1,302 +0,0 @@ -#!/usr/bin/python -# -*- coding:utf-8 -*- -""" -This module is the solver -* Checks IMU -* Plate solves high-res image - -""" - -import queue -import time -import copy -import logging - -from PiFinder import config -from PiFinder import state_utils -import PiFinder.calc_utils as calc_utils -from PiFinder.multiproclogging import MultiprocLogging - -IMU_ALT = 2 -IMU_AZ = 0 - -logger = logging.getLogger("IMU.Integrator") - - -def imu_moved(imu_a, imu_b): - """ - Compares two IMU states to determine if they are the 'same' - if either is none, returns False - """ - if imu_a is None: - return False - if imu_b is None: - return False - - # figure out the abs difference - diff = ( - abs(imu_a[0] - imu_b[0]) + abs(imu_a[1] - imu_b[1]) + abs(imu_a[2] - imu_b[2]) - ) - if diff > 0.001: - return True - return False - - -def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=False): - MultiprocLogging.configurer(log_queue) - try: - if is_debug: - logger.setLevel(logging.DEBUG) - logger.debug("Starting Integrator") - - solved = { - "RA": None, - "Dec": None, - "Roll": None, - "camera_center": { - "RA": None, - "Dec": None, - "Roll": None, - "Alt": None, - "Az": None, - }, - "camera_solve": { - "RA": None, - "Dec": None, - "Roll": None, - }, - "Roll_offset": 0, # May/may not be needed - for experimentation - "imu_pos": None, - "Alt": None, - "Az": None, - "solve_source": None, - "solve_time": None, - "cam_solve_time": 0, - "constellation": None, - } - cfg = config.Config() - if ( - cfg.get_option("screen_direction") == "left" - or cfg.get_option("screen_direction") == "flat" - or cfg.get_option("screen_direction") == "flat3" - or cfg.get_option("screen_direction") == "straight" - ): - flip_alt_offset = True - else: - flip_alt_offset = False - - # This holds the last image solve position info - # so we can delta for IMU updates - last_image_solve = None - last_solve_time = time.time() - while True: - state_utils.sleep_for_framerate(shared_state) - - # Check for new camera solve in queue - next_image_solve = None - try: - next_image_solve = solver_queue.get(block=False) - except queue.Empty: - pass - - if type(next_image_solve) is dict: - # For camera solves, always start from last successful camera solve - # NOT from shared_state (which may contain IMU drift) - # This prevents IMU noise accumulation during failed solves - if last_image_solve: - solved = copy.deepcopy(last_image_solve) - # If no successful solve yet, keep initial solved dict - - # Update solve metadata (always needed for auto-exposure) - for key in [ - "Matches", - "RMSE", - "last_solve_attempt", - "last_solve_success", - ]: - if key in next_image_solve: - solved[key] = next_image_solve[key] - - # Only update position data if solve succeeded (RA not None) - if next_image_solve.get("RA") is not None: - solved.update(next_image_solve) - - # Recalculate Alt/Az for NEW successful solve - location = shared_state.location() - dt = shared_state.datetime() - - if location and dt: - # We have position and time/date and a valid solve! - calc_utils.sf_utils.set_location( - location.lat, - location.lon, - location.altitude, - ) - alt, az = calc_utils.sf_utils.radec_to_altaz( - solved["RA"], - solved["Dec"], - dt, - ) - solved["Alt"] = alt - solved["Az"] = az - - alt, az = calc_utils.sf_utils.radec_to_altaz( - solved["camera_center"]["RA"], - solved["camera_center"]["Dec"], - dt, - ) - solved["camera_center"]["Alt"] = alt - solved["camera_center"]["Az"] = az - - # Experimental: For monitoring roll offset - # Estimate the roll offset due misalignment of the - # camera sensor with the Pole-to-Source great circle. - solved["Roll_offset"] = estimate_roll_offset(solved, dt) - # Find the roll at the target RA/Dec. Note that this doesn't include the - # roll offset so it's not the roll that the PiFinder camear sees but the - # roll relative to the celestial pole - roll_target_calculated = calc_utils.sf_utils.radec_to_roll( - solved["RA"], solved["Dec"], dt - ) - # Compensate for the roll offset. This gives the roll at the target - # as seen by the camera. - solved["Roll"] = roll_target_calculated + solved["Roll_offset"] - - # calculate roll for camera center - roll_target_calculated = calc_utils.sf_utils.radec_to_roll( - solved["camera_center"]["RA"], - solved["camera_center"]["Dec"], - dt, - ) - # Compensate for the roll offset. This gives the roll at the target - # as seen by the camera. - solved["camera_center"]["Roll"] = ( - roll_target_calculated + solved["Roll_offset"] - ) - # For failed solves, preserve ALL position data from previous solve - # Don't recalculate from GPS (causes drift from GPS noise) - - # Set solve_source and push camera solves immediately - if solved["RA"] is not None: - last_image_solve = copy.deepcopy(solved) - solved["solve_source"] = "CAM" - # Calculate constellation for successful solve - solved["constellation"] = ( - calc_utils.sf_utils.radec_to_constellation( - solved["RA"], solved["Dec"] - ) - ) - else: - # Failed solve - clear constellation - solved["solve_source"] = "CAM_FAILED" - solved["constellation"] = "" - - # Push all camera solves (success and failure) immediately - # This ensures auto-exposure sees Matches=0 for failed solves - shared_state.set_solution(solved) - shared_state.set_solve_state(True) - - # Use IMU dead-reckoning from the last camera solve: - # Check we have an alt/az solve, otherwise we can't use the IMU - elif solved["Alt"]: - imu = shared_state.imu() - if imu: - dt = shared_state.datetime() - if last_image_solve and last_image_solve["Alt"]: - # If we have alt, then we have a position/time - - # calc new alt/az - lis_imu = last_image_solve["imu_pos"] - imu_pos = imu["pos"] - if imu_moved(lis_imu, imu_pos): - alt_offset = imu_pos[IMU_ALT] - lis_imu[IMU_ALT] - if flip_alt_offset: - alt_offset = ((alt_offset + 180) % 360 - 180) * -1 - else: - alt_offset = (alt_offset + 180) % 360 - 180 - solved["Alt"] = (last_image_solve["Alt"] - alt_offset) % 360 - solved["camera_center"]["Alt"] = ( - last_image_solve["camera_center"]["Alt"] - alt_offset - ) % 360 - - az_offset = imu_pos[IMU_AZ] - lis_imu[IMU_AZ] - az_offset = (az_offset + 180) % 360 - 180 - solved["Az"] = (last_image_solve["Az"] + az_offset) % 360 - solved["camera_center"]["Az"] = ( - last_image_solve["camera_center"]["Az"] + az_offset - ) % 360 - - # N.B. Assumes that location hasn't changed since last solve - # Turn this into RA/DEC - ( - solved["RA"], - solved["Dec"], - ) = calc_utils.sf_utils.altaz_to_radec( - solved["Alt"], solved["Az"], dt - ) - # Calculate the roll at the target RA/Dec and compensate for the offset. - solved["Roll"] = ( - calc_utils.sf_utils.radec_to_roll( - solved["RA"], solved["Dec"], dt - ) - + solved["Roll_offset"] - ) - - # Now for camera centered solve - ( - solved["camera_center"]["RA"], - solved["camera_center"]["Dec"], - ) = calc_utils.sf_utils.altaz_to_radec( - solved["camera_center"]["Alt"], - solved["camera_center"]["Az"], - dt, - ) - # Calculate the roll at the target RA/Dec and compensate for the offset. - solved["camera_center"]["Roll"] = ( - calc_utils.sf_utils.radec_to_roll( - solved["camera_center"]["RA"], - solved["camera_center"]["Dec"], - dt, - ) - + solved["Roll_offset"] - ) - - solved["solve_time"] = time.time() - solved["solve_source"] = "IMU" - - # Push IMU updates only if newer than last push - # (Camera solves already pushed above at line 185) - if ( - solved["RA"] - and solved["solve_time"] > last_solve_time - and solved.get("solve_source") == "IMU" - ): - last_solve_time = time.time() - # Calculate constellation for IMU dead-reckoning position - solved["constellation"] = calc_utils.sf_utils.radec_to_constellation( - solved["RA"], solved["Dec"] - ) - - # Push IMU update - shared_state.set_solution(solved) - shared_state.set_solve_state(True) - except EOFError: - logger.error("Main no longer running for integrator") - - -def estimate_roll_offset(solved, dt): - """ - Estimate the roll offset due to misalignment of the camera sensor with - the mount/scope's coordinate system. The offset is calculated at the - center of the camera's FoV. - - To calculate the roll with offset: roll = calculated_roll + roll_offset - """ - # Calculate the expected roll at the camera center given the RA/Dec of - # of the camera center. - roll_camera_calculated = calc_utils.sf_utils.radec_to_roll( - solved["camera_center"]["RA"], solved["camera_center"]["Dec"], dt - ) - roll_offset = solved["camera_center"]["Roll"] - roll_camera_calculated - - return roll_offset diff --git a/python/PiFinder/integrator_main_pre_AE.py b/python/PiFinder/integrator_main_pre_AE.py deleted file mode 100644 index 0f19d0cd5..000000000 --- a/python/PiFinder/integrator_main_pre_AE.py +++ /dev/null @@ -1,262 +0,0 @@ -#!/usr/bin/python -# -*- coding:utf-8 -*- -""" -This module is the solver -* Checks IMU -* Plate solves high-res image - -""" - -import queue -import time -import copy -import logging - -from PiFinder import config -from PiFinder import state_utils -import PiFinder.calc_utils as calc_utils -from PiFinder.multiproclogging import MultiprocLogging - -IMU_ALT = 2 -IMU_AZ = 0 - -logger = logging.getLogger("IMU.Integrator") - - -def imu_moved(imu_a, imu_b): - """ - Compares two IMU states to determine if they are the 'same' - if either is none, returns False - """ - if imu_a is None: - return False - if imu_b is None: - return False - - # figure out the abs difference - diff = ( - abs(imu_a[0] - imu_b[0]) + abs(imu_a[1] - imu_b[1]) + abs(imu_a[2] - imu_b[2]) - ) - if diff > 0.001: - return True - return False - - -def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=False): - MultiprocLogging.configurer(log_queue) - try: - if is_debug: - logger.setLevel(logging.DEBUG) - logger.debug("Starting Integrator") - - solved = { - "RA": None, - "Dec": None, - "Roll": None, - "camera_center": { - "RA": None, - "Dec": None, - "Roll": None, - "Alt": None, - "Az": None, - }, - "camera_solve": { - "RA": None, - "Dec": None, - "Roll": None, - }, - "Roll_offset": 0, # May/may not be needed - for experimentation - "imu_pos": None, - "Alt": None, - "Az": None, - "solve_source": None, - "solve_time": None, - "cam_solve_time": 0, - "constellation": None, - } - cfg = config.Config() - if ( - cfg.get_option("screen_direction") == "left" - or cfg.get_option("screen_direction") == "flat" - or cfg.get_option("screen_direction") == "flat3" - or cfg.get_option("screen_direction") == "straight" - ): - flip_alt_offset = True - else: - flip_alt_offset = False - - # This holds the last image solve position info - # so we can delta for IMU updates - last_image_solve = None - last_solve_time = time.time() - while True: - state_utils.sleep_for_framerate(shared_state) - - # Check for new camera solve in queue - next_image_solve = None - try: - next_image_solve = solver_queue.get(block=False) - except queue.Empty: - pass - - if type(next_image_solve) is dict: - solved = next_image_solve - - # see if we can generate alt/az - location = shared_state.location() - dt = shared_state.datetime() - - # see if we can calc alt-az - solved["Alt"] = None - solved["Az"] = None - if location and dt: - # We have position and time/date! - calc_utils.sf_utils.set_location( - location.lat, - location.lon, - location.altitude, - ) - alt, az = calc_utils.sf_utils.radec_to_altaz( - solved["RA"], - solved["Dec"], - dt, - ) - solved["Alt"] = alt - solved["Az"] = az - - alt, az = calc_utils.sf_utils.radec_to_altaz( - solved["camera_center"]["RA"], - solved["camera_center"]["Dec"], - dt, - ) - solved["camera_center"]["Alt"] = alt - solved["camera_center"]["Az"] = az - - # Experimental: For monitoring roll offset - # Estimate the roll offset due misalignment of the - # camera sensor with the Pole-to-Source great circle. - solved["Roll_offset"] = estimate_roll_offset(solved, dt) - # Find the roll at the target RA/Dec. Note that this doesn't include the - # roll offset so it's not the roll that the PiFinder camear sees but the - # roll relative to the celestial pole - roll_target_calculated = calc_utils.sf_utils.radec_to_roll( - solved["RA"], solved["Dec"], dt - ) - # Compensate for the roll offset. This gives the roll at the target - # as seen by the camera. - solved["Roll"] = roll_target_calculated + solved["Roll_offset"] - - # calculate roll for camera center - roll_target_calculated = calc_utils.sf_utils.radec_to_roll( - solved["camera_center"]["RA"], - solved["camera_center"]["Dec"], - dt, - ) - # Compensate for the roll offset. This gives the roll at the target - # as seen by the camera. - solved["camera_center"]["Roll"] = ( - roll_target_calculated + solved["Roll_offset"] - ) - - last_image_solve = copy.deepcopy(solved) - solved["solve_source"] = "CAM" - - # Use IMU dead-reckoning from the last camera solve: - # Check we have an alt/az solve, otherwise we can't use the IMU - elif solved["Alt"]: - imu = shared_state.imu() - if imu: - dt = shared_state.datetime() - if last_image_solve and last_image_solve["Alt"]: - # If we have alt, then we have a position/time - - # calc new alt/az - lis_imu = last_image_solve["imu_pos"] - imu_pos = imu["pos"] - if imu_moved(lis_imu, imu_pos): - alt_offset = imu_pos[IMU_ALT] - lis_imu[IMU_ALT] - if flip_alt_offset: - alt_offset = ((alt_offset + 180) % 360 - 180) * -1 - else: - alt_offset = (alt_offset + 180) % 360 - 180 - solved["Alt"] = (last_image_solve["Alt"] - alt_offset) % 360 - solved["camera_center"]["Alt"] = ( - last_image_solve["camera_center"]["Alt"] - alt_offset - ) % 360 - - az_offset = imu_pos[IMU_AZ] - lis_imu[IMU_AZ] - az_offset = (az_offset + 180) % 360 - 180 - solved["Az"] = (last_image_solve["Az"] + az_offset) % 360 - solved["camera_center"]["Az"] = ( - last_image_solve["camera_center"]["Az"] + az_offset - ) % 360 - - # N.B. Assumes that location hasn't changed since last solve - # Turn this into RA/DEC - ( - solved["RA"], - solved["Dec"], - ) = calc_utils.sf_utils.altaz_to_radec( - solved["Alt"], solved["Az"], dt - ) - # Calculate the roll at the target RA/Dec and compensate for the offset. - solved["Roll"] = ( - calc_utils.sf_utils.radec_to_roll( - solved["RA"], solved["Dec"], dt - ) - + solved["Roll_offset"] - ) - - # Now for camera centered solve - ( - solved["camera_center"]["RA"], - solved["camera_center"]["Dec"], - ) = calc_utils.sf_utils.altaz_to_radec( - solved["camera_center"]["Alt"], - solved["camera_center"]["Az"], - dt, - ) - # Calculate the roll at the target RA/Dec and compensate for the offset. - solved["camera_center"]["Roll"] = ( - calc_utils.sf_utils.radec_to_roll( - solved["camera_center"]["RA"], - solved["camera_center"]["Dec"], - dt, - ) - + solved["Roll_offset"] - ) - - solved["solve_time"] = time.time() - solved["solve_source"] = "IMU" - - # Is the solution new? - if solved["RA"] and solved["solve_time"] > last_solve_time: - last_solve_time = time.time() - # Update remaining solved keys - solved["constellation"] = calc_utils.sf_utils.radec_to_constellation( - solved["RA"], solved["Dec"] - ) - - # add solution - shared_state.set_solution(solved) - shared_state.set_solve_state(True) - except EOFError: - logger.error("Main no longer running for integrator") - - -def estimate_roll_offset(solved, dt): - """ - Estimate the roll offset due to misalignment of the camera sensor with - the mount/scope's coordinate system. The offset is calculated at the - center of the camera's FoV. - - To calculate the roll with offset: roll = calculated_roll + roll_offset - """ - # Calculate the expected roll at the camera center given the RA/Dec of - # of the camera center. - roll_camera_calculated = calc_utils.sf_utils.radec_to_roll( - solved["camera_center"]["RA"], solved["camera_center"]["Dec"], dt - ) - roll_offset = solved["camera_center"]["Roll"] - roll_camera_calculated - - return roll_offset diff --git a/python/PiFinder/integrator_premerge.py b/python/PiFinder/integrator_premerge.py deleted file mode 100644 index e323f5978..000000000 --- a/python/PiFinder/integrator_premerge.py +++ /dev/null @@ -1,292 +0,0 @@ -#!/usr/bin/python -# -*- coding:utf-8 -*- -""" -This module is the solver -* Checks IMU -* Plate solves high-res image - -""" - -import datetime -import queue -import time -import copy -import logging -import numpy as np -import quaternion # numpy-quaternion - -from PiFinder import config -from PiFinder import state_utils -import PiFinder.calc_utils as calc_utils -from PiFinder.multiproclogging import MultiprocLogging -from PiFinder.pointing_model.astro_coords import initialized_solved_dict, RaDecRoll -from PiFinder.pointing_model.imu_dead_reckoning import ImuDeadReckoning -import PiFinder.pointing_model.quaternion_transforms as qt - - -logger = logging.getLogger("IMU.Integrator") - -# Constants: -# Use IMU tracking if the angle moved is above this -# TODO: May need to adjust this depending on the IMU sensitivity thresholds -IMU_MOVED_ANG_THRESHOLD = np.deg2rad(0.06) - - -def integrator(shared_state, solver_queue, console_queue, log_queue, is_debug=False): - MultiprocLogging.configurer(log_queue) - """ """ - if is_debug: - logger.setLevel(logging.DEBUG) - logger.debug("Starting Integrator") - - try: - # Dict of RA, Dec, etc. initialized to None: - solved = initialized_solved_dict() - cfg = config.Config() - - mount_type = cfg.get_option("mount_type") - logger.debug(f"mount_type = {mount_type}") - - # Set up dead-reckoning tracking by the IMU: - imu_dead_reckoning = ImuDeadReckoning(cfg.get_option("screen_direction")) - # imu_dead_reckoning.set_alignment(q_scope2cam) # TODO: Enable when q_scope2cam is available from alignment - - # This holds the last image solve position info - # so we can delta for IMU updates - last_image_solve = None - last_solve_time = time.time() - - while True: - state_utils.sleep_for_framerate(shared_state) - - # Check for new camera solve in queue - next_image_solve = None - try: - next_image_solve = solver_queue.get(block=False) - except queue.Empty: - pass - - if type(next_image_solve) is dict: - # We have a new image solve: Use plate-solving for RA/Dec - solved = next_image_solve - update_plate_solve_and_imu(imu_dead_reckoning, solved) - - last_image_solve = copy.deepcopy(solved) - solved["solve_source"] = "CAM" - - elif imu_dead_reckoning.tracking: - # Previous plate-solve exists so use IMU dead-reckoning from - # the last plate solved coordinates. - imu = shared_state.imu() - if imu: - update_imu(imu_dead_reckoning, solved, last_image_solve, imu) - - # Is the solution new? - if solved["RA"] and solved["solve_time"] > last_solve_time: - last_solve_time = time.time() - - # Try to set date and time - location = shared_state.location() - dt = shared_state.datetime() - # Set location for roll and altaz calculations. - # TODO: Is itnecessary to set location? - # TODO: Altaz doesn't seem to be required for catalogs when in - # EQ mode? Could be disabled in future when in EQ mode? - calc_utils.sf_utils.set_location( - location.lat, location.lon, location.altitude - ) - - # Set the roll so that the chart is displayed appropriately for the mount type - solved["Roll"] = get_roll_by_mount_type( - solved["RA"], solved["Dec"], location, dt, mount_type - ) - - # Update remaining solved keys - solved["constellation"] = calc_utils.sf_utils.radec_to_constellation( - solved["RA"], solved["Dec"] - ) - - # Set Alt/Az because it's needed for the catalogs for the - # Alt/Az mount type. TODO: Can this be moved to the catalog? - dt = shared_state.datetime() - if location and dt: - solved["Alt"], solved["Az"] = calc_utils.sf_utils.radec_to_altaz( - solved["RA"], solved["Dec"], dt - ) - - # add solution - shared_state.set_solution(solved) - shared_state.set_solve_state(True) - - except EOFError: - logger.error("Main no longer running for integrator") - - -# ======== Wrapper and helper functions =============================== - - -def update_plate_solve_and_imu(imu_dead_reckoning: ImuDeadReckoning, solved: dict): - """ - Wrapper for ImuDeadReckoning.update_plate_solve_and_imu() to - interface angles in degrees to radians. - - This updates the pointing model with the plate-solved coordinates and the - IMU measurements which are assumed to have been taken at the same time. - """ - if (solved["RA"] is None) or (solved["Dec"] is None): - return # No update - else: - # Successfully plate solved & camera pointing exists - if solved["imu_quat"] is None: - q_x2imu = quaternion.quaternion(np.nan) - else: - q_x2imu = solved["imu_quat"] # IMU measurement at the time of plate solving - - # Update: - solved_cam = RaDecRoll() - solved_cam.set_from_deg( - solved["camera_center"]["RA"], - solved["camera_center"]["Dec"], - solved["camera_center"]["Roll"], - ) - imu_dead_reckoning.update_plate_solve_and_imu(solved_cam, q_x2imu) - - # Set alignment. TODO: Do this once at alignment. Move out of here. - set_alignment(imu_dead_reckoning, solved) - - -def set_alignment(imu_dead_reckoning: ImuDeadReckoning, solved: dict): - """ - Set alignment. - TODO: Do this once at alignment - """ - # RA, Dec of camera center:: - solved_cam = RaDecRoll() - solved_cam.set_from_deg( - solved["camera_center"]["RA"], - solved["camera_center"]["Dec"], - solved["camera_center"]["Roll"], - ) - - # RA, Dec of target (where scope is pointing): - solved["Roll"] = 0 # Target roll isn't calculated by Tetra3. Set to zero here - solved_scope = RaDecRoll() - solved_scope.set_from_deg(solved["RA"], solved["Dec"], solved["Roll"]) - - # Set alignment in imu_dead_reckoning - imu_dead_reckoning.set_alignment(solved_cam, solved_scope) - - -def update_imu( - imu_dead_reckoning: ImuDeadReckoning, - solved: dict, - last_image_solve: dict, - imu: dict, -): - """ - Updates the solved dictionary using IMU dead-reckoning from the last - solved pointing. - """ - if not (last_image_solve and imu_dead_reckoning.tracking): - return # Need all of these to do IMU dead-reckoning - - assert isinstance( - imu["quat"], quaternion.quaternion - ), "Expecting quaternion.quaternion type" # TODO: Can be removed later - q_x2imu = imu["quat"] # Current IMU measurement (quaternion) - - # When moving, switch to tracking using the IMU - angle_moved = qt.get_quat_angular_diff(last_image_solve["imu_quat"], q_x2imu) - if angle_moved > IMU_MOVED_ANG_THRESHOLD: - # Estimate camera pointing using IMU dead-reckoning - logger.debug( - "Track using IMU: Angle moved since last_image_solve = " - "{:}(> threshold = {:}) | IMU quat = ({:}, {:}, {:}, {:})".format( - np.rad2deg(angle_moved), - np.rad2deg(IMU_MOVED_ANG_THRESHOLD), - q_x2imu.w, - q_x2imu.x, - q_x2imu.y, - q_x2imu.z, - ) - ) - - # Dead-reckoning using IMU - imu_dead_reckoning.update_imu(q_x2imu) # Latest IMU measurement - - # Store current camera pointing estimate: - cam_eq = imu_dead_reckoning.get_cam_radec() - ( - solved["camera_center"]["RA"], - solved["camera_center"]["Dec"], - solved["camera_center"]["Roll"], - ) = cam_eq.get_deg(use_none=True) - - # Store the current scope pointing estimate - scope_eq = imu_dead_reckoning.get_scope_radec() - solved["RA"], solved["Dec"], solved["Roll"] = scope_eq.get_deg(use_none=True) - - solved["solve_time"] = time.time() - solved["solve_source"] = "IMU" - - # Logging for states updated in solved: - logger.debug( - "IMU update: scope: RA: {:}, Dec: {:}, Roll: {:}".format( - solved["RA"], solved["Dec"], solved["Roll"] - ) - ) - logger.debug( - "IMU update: camera_center: RA: {:}, Dec: {:}, Roll: {:}".format( - solved["camera_center"]["RA"], - solved["camera_center"]["Dec"], - solved["camera_center"]["Roll"], - ) - ) - - -def get_roll_by_mount_type( - ra_deg: float, dec_deg: float, location, dt: datetime.datetime, mount_type: str -) -> float: - """ - Returns the roll (in degrees) depending on the mount type so that the chart - is displayed appropriately for the mount type. The RA and Dec of the target - should be provided (in degrees). - - * Alt/Az mount: Display the chart in the horizontal coordinate so that up - in the chart points to the Zenith. - * EQ mount: Display the chart in the equatorial coordinate system with the - NCP up so roll = 0. - - Assumes that location has already been set in calc_utils.sf_utils. - - PARAMETERS: - ra_deg: Right Ascension of the target in degrees - dec_deg: Declination of the target in degrees - location: astropy EarthLocation object or None - dt: datetime.datetime object or None - mount_type: "Alt/Az" or "EQ" - """ - if mount_type == "Alt/Az": - # Altaz mounts: Display chart in horizontal coordinates - if location and dt: - # We have location and time/date (and assume that location has been set) - # Roll at the target RA/Dec in the horizontal frame - roll_deg = calc_utils.sf_utils.radec_to_roll(ra_deg, dec_deg, dt) - else: - # No position or time/date available, so set roll to 0.0 - roll_deg = 0.0 - elif mount_type == "EQ": - # EQ-mounts: Display chart with NCP up so roll = 0.0 - roll_deg = 0.0 - else: - logger.error(f"Unknown mount type: {mount_type}. Cannot set roll.") - roll_deg = 0.0 - - # If location is available, adjust roll for hemisphere: - # Altaz: North up in northern hemisphere, South up in southern hemisphere - # EQ mounts: NCP up in northern hemisphere, SCP up in southern hemisphere - if location: - if location.lat < 0.0: - roll_deg += 180.0 # Southern hemisphere - - return roll_deg From 63a7ce6c9575896189e7335cb4d29a59942fe8e1 Mon Sep 17 00:00:00 2001 From: Mike Rosseel Date: Thu, 25 Dec 2025 00:42:00 +0100 Subject: [PATCH 253/253] add constellation is None fix --- python/PiFinder/ui/base.py | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/python/PiFinder/ui/base.py b/python/PiFinder/ui/base.py index 9ee2c6d03..f3402a6d8 100644 --- a/python/PiFinder/ui/base.py +++ b/python/PiFinder/ui/base.py @@ -269,12 +269,13 @@ def screen_update(self, title_bar=True, button_hints=True) -> None: if len(self.title) < 9: # draw the constellation constellation = solution["constellation"] - self.draw.text( - (self.display_class.resX * 0.54, 1), - constellation, - font=self.fonts.bold.font, - fill=fg if self._unmoved else self.colors.get(32), - ) + if constellation is not None: + self.draw.text( + (self.display_class.resX * 0.54, 1), + constellation, + font=self.fonts.bold.font, + fill=fg if self._unmoved else self.colors.get(32), + ) else: # no solve yet.... self.draw.text(