From ee7f3d5c022eaec211047104623e7b944f91ac52 Mon Sep 17 00:00:00 2001 From: dmupadhyay12 <163680080+dmupadhyay12@users.noreply.github.com> Date: Sun, 10 Nov 2024 19:22:26 -0500 Subject: [PATCH] Kalman Filter to get rid of noise from the CV sensor (#33) * created kalman filter library and integrated it with main, added params file for kalman filter params * formatted files * got rid of erroneous files left over from another PR :sob: * removed more erroneous files * reverted accidental delete * added function for visualization the data * added visualizer and integrated into main * addressed more PR comments * implemented further PR changes * added array for acceleration visualization * created some hacky test code * fixed some imports * fixed index error * added code to run for 1000 iterations then visualize * fixed matplotlib issues * removed some print statements * removed an unnecessary function * created arguments to pass into system for easier tuning * formatted the file * made the arguments work * fixed some argument issues * fixed more issues * fixed import issue * implemented logging of noisy measurements * fixed writing to the JSON * commiting the recorded measured points * added offline tuning capability in kalman filter library * commiting a file with less points for debugging * fixed issue where cv data wasn't getting updated and logged properly * added append function to the hacky code * more fixes * updated measurements * quick test * updating the measured_points.json file * updated points to tune on * changes to kalman filter model * more new testing artifacts * new measured points * applied a morphological mask for better tuning * made some changes to CV system * issues with kalman filter initialization * added pause time in camera * more testing code :skull: * another fix * another change to get it working * updating measurement * fixed the sawtoothing issue with kalman filter * removed some comments * more fixes * cleaned up the filter a bit more * more cleanup * reverted some debug artifacts * reverted an unnecessary mask * nuked a bunch unnecessary shit * cleaned up main.py * got rid of visualizer from main * Integration changes --------- Co-authored-by: upadhyaydhruv Co-authored-by: 380 Pi --- pi/camera.py | 15 +- pi/kalman_filter.py | 209 ++++++++ pi/main.py | 29 +- pi/measured_points.json | 1006 +++++++++++++++++++++++++++++++++++++++ 4 files changed, 1236 insertions(+), 23 deletions(-) create mode 100644 pi/kalman_filter.py create mode 100644 pi/measured_points.json diff --git a/pi/camera.py b/pi/camera.py index f5077cc..46cb576 100644 --- a/pi/camera.py +++ b/pi/camera.py @@ -170,6 +170,7 @@ def detect_ball(self, image): # Combine the color mask with the circular mask combined_mask = cv.bitwise_and(mask, mask, mask=circular_mask) + # Apply the combined mask to the original frame res = cv.bitwise_and(frame, frame, mask=combined_mask) @@ -188,7 +189,7 @@ def detect_ball(self, image): dp=1.2, minDist=30, param1=50, - param2=30, + param2=25, minRadius=5, maxRadius=50, ) @@ -257,15 +258,3 @@ def pixel_to_world_coords(self, u, v, height_m): ) return obj_coords_2d_point - - -if __name__ == "__main__": - # from pi/camera_params.json get the data - with open("pi/camera_params.json") as f: - data = json.load(f) - - # Create camera object - cam = Camera(data["u"], data["v"], "/dev/video0", debug=True) - print(cam.u, cam.v, cam.port) - cam.calibrate_cam_from_images() - cam.show_camera_feed() diff --git a/pi/kalman_filter.py b/pi/kalman_filter.py new file mode 100644 index 0000000..2dfbaab --- /dev/null +++ b/pi/kalman_filter.py @@ -0,0 +1,209 @@ +import numpy as np +import matplotlib.pyplot as plt +from point import Point +import argparse +import os +import json + + +class KalmanFilter: + def __init__(self, dt, Q=0.01, R=5.0, outlier_threshold=0.2): + self.K = 1.0 # Initial kalman gain + self.dt = dt + self.X = np.zeros( + (6, 1) + ) # [x, y, vx, vy, ax, ay]^T - current estimate of the ball state + self.P = np.eye(6) * 1000 # Large initial uncertainty + + self.A = np.array( + [ + [1, 0, self.dt, 0, 0.5 * self.dt**2, 0], + [0, 1, 0, self.dt, 0, 0.5 * self.dt**2], + [0, 0, 1, 0, self.dt, 0], + [0, 0, 0, 1, 0, self.dt], + [0, 0, 0, 0, 1, 0], + [0, 0, 0, 0, 0, 1], + ] + ) # Transition matrix to get state estimate given previous estimate + + self.H = np.array( + [[1, 0, 0, 0, 0, 0], [0, 1, 0, 0, 0, 0]] + ) # Measurement matrix + + self.Q = np.eye(6) * Q # Process noise covariance + self.R = np.eye(2) * R # Measurement noise covariance + + # Arrays for visualization of data + self.noisy_positions_x = [] + self.noisy_positions_y = [] + self.filtered_positions_x = [] + self.filtered_positions_y = [] + self.filtered_velocity_x = [] + self.filtered_velocity_y = [] + self.filtered_acceleration_x = [] + self.filtered_acceleration_y = [] + + self.most_recent_measurement_x = 0 + self.most_recent_measurement_y = 0 + + self.new_state = [0, 0, 0, 0, 0, 0] + + def predict(self): + self.X = ( + self.A @ self.X + ) # Get predicted next state based on the transition matrix + self.P = ( + self.A @ self.P @ self.A.T + self.Q + ) # Update the sensor covariance matrix + + self.new_state = [ + self.X[0, 0], + self.X[1, 0], + self.X[2, 0], + self.X[3, 0], + self.X[4, 0], + self.X[5, 0], + ] + + return Point(self.new_state[0], self.new_state[1]) + + def update(self, measured_point): + # Use the new measurements to update the prediction + self.most_recent_measurement_x = measured_point.x + self.most_recent_measurement_y = measured_point.y + Z = np.array( + [self.most_recent_measurement_x, self.most_recent_measurement_y] + ).reshape(2, 1) + + # Update error vector Y + Y = Z - self.H @ self.X + S = self.H @ self.P @ self.H.T + self.R + self.K = self.P @ self.H.T @ np.linalg.inv(S) + + self.P = (np.eye(len(self.P)) - self.K @ self.H) @ self.P + + self.X = self.X + self.K @ Y # Update value based on the new kalman gain + + self.new_state = [ + self.X[0, 0], + self.X[1, 0], + self.X[2, 0], + self.X[3, 0], + self.X[4, 0], + self.X[5, 0], + ] + + return Point(self.new_state[0], self.new_state[1]) + + def visualize_data(self): + plt.figure(figsize=(10, 6)) + + # Plot noisy measurements + plt.scatter( + self.noisy_positions_x, + self.noisy_positions_y, + color="red", + label="Noisy Data", + s=10, + alpha=0.5, + ) + + # Plot filtered estimates + plt.plot( + self.filtered_positions_x, + self.filtered_positions_y, + color="blue", + label="Filtered Position Data (Kalman)", + linewidth=2, + ) + + # Labeling + plt.title("Kalman Filter: Noisy vs. Filtered Position") + plt.xlabel("X Position") + plt.ylabel("Y Position") + plt.legend() + plt.grid(True) + + # Show plot + plt.show() + + def append_noisy_measurement(self): + self.noisy_positions_x.append(self.most_recent_measurement_x) + self.noisy_positions_y.append(self.most_recent_measurement_y) + + self.filtered_positions_x.append(self.new_state[0]) + self.filtered_positions_y.append(self.new_state[1]) + + self.filtered_velocity_x.append(self.new_state[2]) + self.filtered_velocity_y.append(self.new_state[3]) + + self.filtered_acceleration_x.append(self.new_state[4]) + self.filtered_acceleration_y.append(self.new_state[5]) + + +def main(Q_val, R_val, dt_val): + current_dir = os.path.dirname(os.path.realpath(__file__)) + measured_points_file_path = os.path.join(current_dir, "measured_points.json") + with open(measured_points_file_path, "r") as file: + data = json.load(file) # Load JSON data as a dictionary + + measured_points_x = data["x"] + measured_points_y = data["y"] + + kalman_filter = KalmanFilter(Q_val, R_val, dt_val) + + for i in range(500): + noisy_x = measured_points_x[i] + noisy_y = measured_points_y[i] + + if noisy_x is not None and noisy_y is not None: + if ( + kalman_filter.most_recent_measurement_x is None + or kalman_filter.most_recent_measurement_y is None + ): + current_measurement = Point(noisy_x, noisy_y) + + elif ( + np.abs(noisy_x - kalman_filter.most_recent_measurement_x) < 0.02 + and np.abs(noisy_y - kalman_filter.most_recent_measurement_y) < 0.02 + ): + current_measurement = Point(noisy_x, noisy_y) + + else: + current_measurement = None + + else: + current_measurement = None + + filtered_state = kalman_filter.predict() + + if current_measurement is not None: + filtered_state = kalman_filter.update(current_measurement) + else: + print("Ball not detected!!! Using old value for now") + kalman_filter.most_recent_measurement_x = None + kalman_filter.most_recent_measurement_y = None + + kalman_filter.append_noisy_measurement() + + kalman_filter.visualize_data() + + +if __name__ == "__main__": + # Set up argument parser + parser = argparse.ArgumentParser( + description="Run camera and Kalman filter with specified parameters." + ) + + parser.add_argument( + "--Q", type=float, default=0.01, help="Process noise covariance" + ) + parser.add_argument( + "--R", type=float, default=5.0, help="Measurement noise covariance" + ) + parser.add_argument("--dt", type=float, default=1.0, help="Time step interval") + + args = parser.parse_args() + + # Call main function with parsed arguments + main(args.Q, args.R, args.dt) diff --git a/pi/main.py b/pi/main.py index 21c0ebd..c1dbcd2 100644 --- a/pi/main.py +++ b/pi/main.py @@ -10,6 +10,7 @@ import argparse import matplotlib.pyplot as plt from matplotlib.widgets import Slider +from kalman_filter import KalmanFilter import time import json @@ -36,7 +37,7 @@ def __init__( cam_color_mask_detect: bool = False, cam_calibration_images: bool = False, ): - self.pause_period = 0.05 + self.dt = 0.05 self.saturate_angle = 14 self.params = { "lh": 41 / 1000, @@ -74,7 +75,7 @@ def __init__( kp, ki, kd, - self.pause_period, + self.dt, np.deg2rad(self.saturate_angle), ) @@ -104,18 +105,20 @@ def __init__( # get the current directory current_dir = os.path.dirname(os.path.realpath(__file__)) # get the file camera.json with the current dir - file_path = os.path.join(current_dir, "camera_params.json") + cv_params_file_path = os.path.join(current_dir, "camera_params.json") self.camera_debug = camera_debug - with open(file_path, "r") as file: + with open(cv_params_file_path, "r") as file: data = json.load(file) # Load JSON data as a dictionary if self.virtual is not True: self.cv_system = Camera(data["u"], data["v"], camera_port, camera_debug) self.cv_system.load_camera_params("pi/camera_calibration_data.json") - self.current_position = Point(0.0, 0.0) + self.kalman_filter = KalmanFilter(self.dt) # Use default params for now + + self.current_position = Point(0, 0) def create_kinematic_sliders(self): """Create sliders for pitch, roll, and height""" @@ -160,12 +163,18 @@ def run(self): desired_position = Point(0, 0) if self.run_controller: if self.virtual is False: - current_position = self.cv_system.get_ball_coordinates() - print(f"Current position is: {current_position}") + current_measurement = self.cv_system.get_ball_coordinates() + + filtered_state = self.kalman_filter.predict() - if current_position is not None: - self.current_position = current_position + if current_measurement is not None: + self.current_position = self.kalman_filter.update( + current_measurement + ) camera_valid = True + print( + f"Time: {time.time()} | Current position is: {self.current_measurement}" + ) else: if self.camera_debug: print("Ball not detected!!! Using old value for now") @@ -252,7 +261,7 @@ def run(self): ) time_elapsed = time.time() - time_since_start - pause_time = self.pause_period - time_elapsed + pause_time = self.dt - time_elapsed if pause_time < 0: print( f"Loop is taking too long to run! {time_elapsed} seconds, {pause_time} seconds" diff --git a/pi/measured_points.json b/pi/measured_points.json new file mode 100644 index 0000000..7238048 --- /dev/null +++ b/pi/measured_points.json @@ -0,0 +1,1006 @@ +{ + "x": [ + 0.02019081637263298, + 0.02019081637263298, + 0.02019081637263298, + 0.020190313458442688, + 0.02019081637263298, + 0.020189819857478142, + 0.01947050355374813, + 0.01947050355374813, + 0.020189819857478142, + 0.01947050355374813, + 0.01947050355374813, + 0.01947050355374813, + 0.020189819857478142, + 0.018750714138150215, + 0.018031718209385872, + 0.01947050355374813, + 0.02090858668088913, + 0.01875157095491886, + 0.01947050355374813, + 0.020910149440169334, + 0.01947050355374813, + 0.018750714138150215, + 0.018750714138150215, + 0.01947050355374813, + 0.01947050355374813, + 0.018750714138150215, + 0.01947050355374813, + 0.01659172959625721, + 0.01947050355374813, + 0.018750714138150215, + 0.01947050355374813, + 0.01947050355374813, + 0.018750714138150215, + 0.018750714138150215, + 0.01875157095491886, + 0.020189819857478142, + 0.01947050355374813, + 0.018750714138150215, + 0.019471915438771248, + 0.020190313458442688, + 0.01947096921503544, + 0.018750714138150215, + 0.018750714138150215, + 0.01659172959625721, + 0.018030941486358643, + 0.018750714138150215, + 0.015871934592723846, + 0.018030941486358643, + 0.018030941486358643, + 0.01875114068388939, + 0.018750714138150215, + 0.020189819857478142, + 0.018750714138150215, + 0.02090858668088913, + 0.01659172959625721, + 0.02090858668088913, + 0.016591418534517288, + 0.018030941486358643, + 0.02090858668088913, + 0.02090858668088913, + 0.018030941486358643, + 0.02090858668088913, + 0.018030941486358643, + 0.02090858668088913, + 0.018031327053904533, + 0.022347021847963333, + 0.02018885686993599, + 0.018031327053904533, + 0.020188387483358383, + 0.01946871541440487, + 0.016591109335422516, + 0.018026920035481453, + 0.018025243654847145, + 0.01586916483938694, + 0.012271447107195854, + 0.012271614745259285, + 0.01155241671949625, + 0.006513329222798347, + 0.0029121935367584224, + 0.0036323370877653356, + 0.0007474168087355785, + -0.002139884280040861, + -0.002867901930585505, + -0.005037387367337943, + -0.007207388989627362, + -0.005770006682723762, + -0.0050563225522637385, + -0.010853255167603494, + -0.010864662006497385, + -0.007973672822117807, + -0.010142531245946886, + -0.0051028770394623306, + -0.0051028770394623306, + -0.0029390961863100555, + -0.001481745624914768, + 0.002849841723218557, + -0.0073138368315994766, + 0.0028457504231482714, + 0.010090337134897705, + 0.01226203795522451, + 0.011537218466401097, + 0.018054036423563954, + 0.020225770771503445, + 0.025289244949817654, + 0.028184968978166577, + 0.03324706852436066, + 0.03614511713385582, + 0.037588294595479965, + 0.04193168878555298, + 0.04554414004087448, + 0.005765335634350774, + 0.05351047217845917, + 0.052783191204071045, + 0.009383351542055605, + 0.05712190642952919, + 0.05711746960878372, + 0.059280477464199066, + 0.0614539235830307, + 0.06144197657704353, + 0.06143445149064064, + 0.06287121027708054, + 0.0621303990483284, + 0.06212229281663895, + 0.059935957193374634, + 0.0599251464009285, + 0.059918053448200226, + 0.057732950896024704, + 0.055552076548337936, + 0.052650608122348785, + 0.053369760513305664, + 0.05119435489177704, + 0.0497458316385746, + 0.04685237258672714, + 0.04251757264137268, + 0.04396340250968933, + 0.04035337641835213, + 0.03746616095304489, + 0.03602447360754013, + 0.03386203572154045, + 0.03242175653576851, + 0.028817957267165184, + 0.025215862318873405, + 0.024496400728821754, + 0.023055776953697205, + 0.01945486851036549, + 0.018014671280980114, + 0.0151336956769228, + 0.0122551741078496, + 0.011536306701600553, + 0.012256870977580549, + 0.0029011575970798744, + null, + -0.0014169623609632245, + null, + -0.0035839008633047334, + -0.005742296576499938, + -0.009349269792437553, + -0.010793136432766914, + -0.012238025665283203, + -0.014408914372324944, + -0.01875590719282627, + -0.018034866079688072, + -0.018764177337288857, + -0.014422960579395294, + -0.01659836806356907, + -0.013711883686482908, + -0.011544955894351007, + -0.011551038362085821, + -0.009389651007950308, + -0.01372453570365906, + -0.00650762300938368, + -0.003621810115873816, + -0.002181040355935695, + -0.00290249031968415, + -0.007982295006513597, + 0.0014300611801445462, + 0.0007012129062786674, + 0.007207852788269517, + 0.009375131689012049, + 0.010820577852427956, + 0.014435636810958384, + 0.020218094810843464, + 0.020218094810843464, + 0.024556985124945637, + 0.03106758743524551, + 0.032512739300727844, + 0.0101110627874732, + 0.03757879510521889, + 0.04264960065484047, + 0.044092871248722076, + 0.052792251110076904, + 0.05787372961640358, + 0.06006070226430893, + 0.06223927438259125, + 0.06807036697864532, + 0.068791463971138, + 0.07244965434074402, + 0.07538589835166931, + 0.07316677272319794, + 0.07683851569890976, + 0.07536886632442474, + 0.03967692703008652, + 0.07682748138904572, + 0.07758543640375137, + 0.07536886632442474, + 0.07538589835166931, + 0.07023492455482483, + 0.06149441376328468, + 0.06441440433263779, + 0.06444696336984634, + 0.06007653847336769, + 0.05716010928153992, + 0.05352440103888512, + 0.051365748047828674, + 0.048466552048921585, + 0.044124942272901535, + 0.041213732212781906, + 0.03977389261126518, + 0.03325521573424339, + 0.03106989152729511, + 0.026744199916720387, + 0.024562584236264225, + 0.020942665636539456, + 0.01877793855965137, + 0.01660564355552196, + 0.01443432085216045, + 0.011540956795215603, + 0.009369996376335617, + 0.005752100143581626, + 0.00213341414928436, + -0.001494398573413494, + -0.0029283496551215675, + -0.002206292469054463, + -0.009449076838791372, + -0.013791702687740328, + -0.014518389478325846, + -0.019589539617300037, + -0.024677429348230365, + -0.03194354102015495, + -0.03413620963692665, + -0.03195731341838837, + -0.035607364028692245, + -0.03999132290482521, + -0.04002109169960022, + -0.04440205544233322, + -0.0465828999876976, + -0.04878642410039902, + -0.04583391547203064, + -0.04877159371972084, + -0.05024021863937378, + -0.04875854775309563, + -0.053205423057079315, + -0.05171165242791176, + -0.05170951411128044, + -0.04727037623524666, + -0.051708754152059555, + -0.05170927196741104, + -0.05171116814017296, + -0.050973523408174515, + -0.0487564280629158, + -0.050241343677043915, + -0.04581412300467491, + -0.04507901892066002, + -0.03994090482592583, + -0.0362812802195549, + -0.03409372642636299, + -0.03556165471673012, + -0.02462780103087425, + -0.023178732022643086, + -0.01954342424869537, + -0.016655145213007923, + -0.013759938068687914, + -0.00941876135766506, + -0.006526549346745012, + -0.003636318258941171, + -0.0014681138563901162, + -0.0007456306484527862, + 0.001421132707037034, + 0.0035886019468307517, + 0.0071936910971999194, + 0.012244410812854769, + 0.013685110956430437, + 0.015127782709896566, + 0.01873300224542618, + 0.020174730569124225, + 0.020895693451166156, + 0.025220382958650592, + 0.02305754274129868, + 0.02882444486021996, + 0.03242754563689232, + 0.03098579309880734, + 0.031703997403383255, + 0.03819819539785385, + 0.03819502517580986, + 0.04180324822664261, + 0.0425228625535965, + 0.041796423494815826, + 0.04613248258829117, + 0.049749620258808136, + 0.04974684864282608, + 0.05409429222345352, + 0.05481909587979317, + 0.05481960251927376, + 0.05917708948254585, + 0.05917803570628166, + 0.05918188765645027, + 0.061368659138679504, + 0.05918402224779129, + 0.06355956196784973, + 0.0657595694065094, + 0.06430590897798538, + 0.06577301025390625, + 0.06286491453647614, + 0.06360696256160736, + 0.06582769006490707, + 0.0658411905169487, + 0.06439933180809021, + 0.07023492455482483, + 0.06369437277317047, + 0.06370508670806885, + 0.06371614336967468, + 0.06299684941768646, + 0.05861785262823105, + 0.05717042088508606, + 0.05427713692188263, + 0.048471152782440186, + 0.044834427535533905, + 0.04266487434506416, + 0.03613303229212761, + 0.03106305748224258, + 0.028906960040330883, + 0.020940940827131268, + 0.018774660304188725, + 0.013712435029447075, + 0.007207852788269517, + 0.006468938197940585, + 0.002849841723218557, + -0.0007825340726412863, + -0.0022250968031585247, + null, + -0.00804059207439423, + -0.013837570324540142, + -0.016007455065846447, + -0.018218653276562694, + -0.020380040630698208, + -0.023294361308217052, + -0.027663484215736393, + -0.028440980240702633, + -0.03278075531125069, + -0.03350169584155083, + -0.03204704448580742, + -0.03276784345507622, + -0.03714299947023392, + -0.040074143558740616, + -0.04151670262217522, + -0.04446181282401085, + -0.04666086286306381, + -0.047366898506879807, + -0.05104022100567818, + -0.053253237158060074, + -0.05628768727183342, + -0.05769024044275284, + -0.05617613345384598, + -0.05617090314626694, + -0.053194012492895126, + -0.055421002209186554, + -0.05542059615254402, + -0.05097987502813339, + -0.05542583018541336, + -0.050250548869371414, + -0.04877905920147896, + -0.04582449048757553, + -0.041430842131376266, + -0.03630558028817177, + -0.03339560329914093, + -0.03267673775553703, + -0.028308836743235585, + -0.023945841938257214, + -0.02467461489140987, + -0.016691546887159344, + -0.01379098370671272, + -0.006558528169989583, + -0.0022073993459343884, + 0.0021277456544339683, + 0.005739727523177865, + 0.010789128951728347, + 0.015844210982322696, + 0.019452944397926334, + 0.023784916847944263, + 0.028118353337049488, + 0.031009845435619358, + 0.0360734760761261, + 0.037525009363889694, + 0.03969978168606758, + 0.04186566174030304, + 0.04259028658270836, + 0.04476217180490494, + 0.046935055404901505, + 0.048383209854364395, + 0.04982550069689751, + 0.05345063656568527, + 0.05562489479780197, + 0.058525074273347855, + 0.062150344252586365, + 0.0636020079255104, + 0.06432505697011948, + 0.0664968490600586, + 0.0679495707154274, + 0.07013498991727829, + 0.0686631128191948, + 0.07231435924768448, + 0.07157524675130844, + 0.0723041296005249, + null, + 0.07011095434427261, + 0.07158070802688599, + 0.0715872049331665, + 0.07086846232414246, + 0.07087909430265427, + 0.07162334024906158, + 0.07090538740158081, + 0.07092522084712982, + 0.07020174711942673, + 0.0680294930934906, + 0.06364183127880096, + 0.06294891238212585, + 0.05785005912184715, + 0.05349287390708923, + 0.05280157923698425, + 0.04699607938528061, + 0.041924335062503815, + 0.03975965455174446, + 0.03397703915834427, + 0.031074568629264828, + 0.02529395371675491, + 0.023117983713746067, + 0.018054036423563954, + 0.01515852008014917, + 0.010093694552779194, + 0.007198568899184463, + 0.005019911564886567, + 0.0006755375652573973, + -0.002214088803157213, + -0.00511808227747679, + -0.009459666907787326, + -0.011635019443929197, + -0.019589539617300037, + -0.018155122175812725, + -0.023952536284923557, + -0.024677429348230365, + -0.024677429348230365, + -0.029807263985276226, + -0.03123007714748383, + -0.03193916380405426, + -0.033386554569005966, + -0.03780015930533409, + -0.03702833130955696, + -0.04216945916414261, + -0.04436879605054855, + -0.04212803393602371, + -0.042856719344854355, + -0.04950006306171417, + -0.05022989585995674, + -0.05097560957074165, + -0.05097072571516037, + -0.04948917776346207, + -0.04948994517326355, + -0.04875804856419563, + -0.05097806453704834, + -0.049510445445775986, + -0.05543449893593788, + -0.05554813891649246, + -0.05175793915987015, + -0.048820264637470245, + -0.05030563473701477, + -0.04959029331803322, + -0.04443766549229622, + -0.04887240007519722, + -0.04152967035770416, + -0.03712800145149231, + -0.03422219678759575, + -0.0327618233859539, + -0.026925040408968922, + -0.024745278060436245, + -0.026930838823318478, + -0.018200276419520375, + -0.014567567035555836, + -0.011665420606732365, + -0.008036173880100247, + -0.00948336627334356, + -0.003686542622745034, + 0.0006528272060677442, + 0.0035478118807077443, + 0.007160948589444164, + 0.010777007788419727, + 0.013670790940523151, + 0.018007207661867145, + 0.020174928009510044, + 0.023786755278706554, + 0.02667525596916676 + ], + "y": [ + 0.011869406327605206, + 0.011869406327605206, + 0.011869406327605206, + 0.011158490553498226, + 0.011869406327605206, + 0.010447687469422776, + 0.011158004403114277, + 0.011158004403114277, + 0.010447687469422776, + 0.011158004403114277, + 0.011158004403114277, + 0.011158004403114277, + 0.010447687469422776, + 0.011157555505633313, + 0.012579059228301007, + 0.011158004403114277, + 0.009026895277202088, + 0.012579478323459584, + 0.011158004403114277, + 0.011159014888107735, + 0.011158004403114277, + 0.011157555505633313, + 0.011157555505633313, + 0.011158004403114277, + 0.011158004403114277, + 0.011157555505633313, + 0.011158004403114277, + 0.011867333203554112, + 0.011158004403114277, + 0.011157555505633313, + 0.011158004403114277, + 0.011158004403114277, + 0.011157555505633313, + 0.011157555505633313, + 0.012579478323459584, + 0.010447687469422776, + 0.011158004403114277, + 0.011157555505633313, + 0.013291086070239502, + 0.011158490553498226, + 0.01186891272664066, + 0.011157555505633313, + 0.011157555505633313, + 0.011867333203554112, + 0.011157145723700482, + 0.011157555505633313, + 0.011867037042975384, + 0.011157145723700482, + 0.011157145723700482, + 0.011868458241224247, + 0.011157555505633313, + 0.010447687469422776, + 0.011157555505633313, + 0.009026895277202088, + 0.011867333203554112, + 0.009026895277202088, + 0.011156437918543774, + 0.011157145723700482, + 0.009026895277202088, + 0.009026895277202088, + 0.011157145723700482, + 0.009026895277202088, + 0.011157145723700482, + 0.009026895277202088, + 0.011868043802678543, + 0.007607027888297992, + 0.009026397950947243, + 0.011868043802678543, + 0.00831590313464399, + 0.008315447717905003, + 0.010445657186210114, + 0.0033436592202633194, + -0.00020511637558233542, + 0.004762595985084729, + 0.00405146041885014, + 0.004761464893817858, + 0.006891792640089945, + 0.009023309685289816, + 0.008313769474625544, + 0.00902421027421947, + 0.012581483460962729, + 0.014719641767442183, + 0.01899545639753337, + 0.020425857976078942, + 0.02114423923194404, + 0.02471157163381572, + 0.02828522957861419, + 0.02973650582134719, + 0.032604623585939366, + 0.034746281802654225, + 0.03331923857331272, + 0.041928350925445515, + 0.041928350925445515, + 0.04480489343404766, + 0.04263557493686672, + 0.0476748906075954, + 0.0491629987955093, + 0.04912138357758518, + 0.04910639300942417, + 0.04982770979404445, + 0.05055212974548336, + 0.049103882163763005, + 0.04910571500658985, + 0.04694594070315357, + 0.046953141689300495, + 0.04480420053005214, + 0.044815897941589314, + 0.043379701673984486, + 0.04195918887853618, + 0.03909798339009281, + 0.03829905390739437, + 0.034830182790756184, + 0.03482561558485027, + 0.03327110782265659, + 0.030543385073542553, + 0.029825732111930806, + 0.026253197342157322, + 0.024116162210702854, + 0.02196778543293472, + 0.0205364096909761, + 0.016252601519226986, + 0.013391628861427267, + 0.011249640956520994, + 0.010528478771448095, + 0.006962433923035819, + 0.004111108370125253, + 0.001969308359548409, + 0.0005415381747297537, + 0.0005372796440496634, + -0.005154168698936742, + -0.008000535890460054, + -0.010845502838492433, + -0.01440028753131632, + -0.017952896654605907, + -0.01866537705063824, + -0.020795775577426, + -0.020793162286281627, + -0.02221430465579037, + -0.023635061457753223, + -0.02576829679310326, + -0.025765737518668216, + -0.025052873417735145, + -0.027898726984858558, + -0.027186730876565025, + -0.030034191906452224, + -0.029322449117898986, + -0.030035788193345115, + -0.027190357446670577, + -0.02576801367104058, + -0.025056147947907493, + -0.019378812983632133, + null, + -0.014410690404474779, + null, + -0.01725542545318608, + -0.012284193187952085, + -0.008735033683478876, + -0.006604176480323121, + -0.002340287202969238, + -0.00020704143389598285, + -0.0002053237403743419, + 0.004775862209498837, + 0.007625080645084336, + 0.011891080066561654, + 0.012608268298208668, + 0.017592798918485596, + 0.019727775827050164, + 0.02186985127627845, + 0.0254366528242826, + 0.021876597777008965, + 0.029721358790993645, + 0.032578852027654606, + 0.03472659736871715, + 0.034011147916316944, + 0.0369017124176025, + 0.0368709452450275, + 0.03902899473905559, + 0.04045401886105533, + 0.04189072921872135, + 0.04260949045419689, + 0.041887659579515416, + 0.04189046472311016, + 0.04189046472311016, + 0.04261704906821247, + 0.042633812874555546, + 0.041918326169252354, + 0.021833995357155755, + 0.0412180013954639, + 0.04052218422293659, + 0.03909006714820858, + 0.036263655871152836, + 0.034140091389417614, + 0.034155443310737575, + 0.0327329225838184, + 0.030619284138083416, + 0.029186969622969586, + 0.02849588170647617, + 0.02851908653974529, + 0.02634504623711105, + 0.026372866705059964, + 0.026361558586358982, + 0.02187538146972652, + 0.024935055524110752, + 0.02781744301319118, + 0.026361558586358982, + 0.02851908653974529, + 0.02632387913763519, + 0.030571864917874295, + 0.03059224784374233, + 0.03490812703967091, + 0.036314390599727596, + 0.03629311919212338, + 0.03698784112930294, + 0.040574245154857594, + 0.04199710115790363, + 0.04485663771629329, + 0.04339730739593502, + 0.04555479437112804, + 0.046970024704933125, + 0.04335440695285793, + 0.049841001629829365, + 0.04550066962838169, + 0.04333175718784328, + 0.0491043739020824, + 0.04693518579006191, + 0.0498266294598579, + 0.04621445387601848, + 0.046216722577810246, + 0.045500885695219, + 0.044787965714931446, + 0.0462437197566032, + 0.04191996157169338, + 0.04263808950781818, + 0.04050653427839275, + 0.037648383527994114, + 0.037652283906936604, + 0.03408450260758396, + 0.031959079205989796, + 0.0255412776023149, + 0.02483716793358321, + 0.0276953130960464, + 0.025564661249518346, + 0.022002654150128316, + 0.026314187794923734, + 0.02059450186789031, + 0.01486343611031766, + 0.01200401131063695, + 0.012707851827144576, + 0.008417787961661769, + 0.00483782868832345, + 0.004117414820939256, + 0.0048458990640937805, + -0.00017684837803249293, + -0.0023270207457244865, + -0.0037613655440509788, + -0.005193585529923487, + -0.006626809481531429, + -0.008776676841080236, + -0.010925374925136613, + -0.012353781610727357, + -0.014506602659821557, + -0.016642209142446567, + -0.01735571026802068, + -0.020914847031235743, + -0.02304542250931268, + -0.02518101967871194, + -0.02590317279100423, + -0.03014103509485726, + -0.03156380727887158, + -0.03154710680246357, + -0.035107877105474514, + -0.0365250334143639, + -0.037937048822641414, + -0.03864108771085743, + -0.03934609517455105, + -0.039339181035757106, + -0.0393370240926743, + -0.039331000298261684, + -0.03861094638705258, + -0.04003297910094265, + -0.03859642893075947, + -0.04002405330538754, + -0.039308276027441066, + -0.03787808865308766, + -0.03859211504459385, + -0.03859214112162594, + -0.03573794662952427, + -0.03502353280782704, + -0.03431385383009915, + -0.031465649604797405, + -0.03217682614922528, + -0.029327332973480266, + -0.02933568134903912, + -0.02719854936003689, + -0.025067472830414814, + -0.02293282374739651, + -0.01937462203204636, + -0.018667528405785602, + -0.017248122021555942, + -0.01369063463062052, + -0.012269716709852259, + -0.010134819895029108, + -0.006576541811227839, + -0.005862601101398509, + -0.00443833600729708, + -0.0008773865993135081, + 0.0019760688301175434, + 0.000547200615983416, + 0.004832679405808408, + 0.009120665490627249, + 0.01054355688393112, + 0.012691913172602614, + 0.014823302626609762, + 0.01768594793975349, + 0.02342538349330421, + 0.025576518848538357, + 0.028437400236725766, + 0.02632387913763519, + 0.03202454745769497, + 0.033462982624769176, + 0.03490238636732098, + 0.03633694723248478, + 0.036303590983152355, + 0.03773307800292965, + 0.04059452563524242, + 0.04271838441491123, + 0.04197508096694942, + 0.04340504854917522, + 0.04193207249045368, + 0.0411935448646545, + 0.04623309150338169, + 0.04189128428697582, + 0.04477132111787792, + 0.0433283187448978, + 0.04045401886105533, + 0.0491123646497726, + 0.0476748906075954, + 0.04985743016004558, + 0.04769212380051609, + null, + 0.049166899174451786, + 0.0455829836428165, + 0.043428968638181645, + 0.04706044495105739, + 0.04345943033695217, + 0.04275902360677715, + 0.04062695801258083, + 0.04569856822490688, + 0.039226792752742726, + 0.03778872266411777, + 0.039220184087753254, + 0.03778223320841785, + 0.03421271964907642, + 0.03279610723257061, + 0.02920472063124175, + 0.02850891649723048, + 0.026365878060460042, + 0.022052388638257932, + 0.017762262374162625, + 0.015618724748492194, + 0.023563168942928266, + 0.010608952492475463, + 0.004136310424655628, + 0.0019824812188744072, + -0.000891978677827912, + -0.002324411412701058, + -0.006628867238760042, + -0.013791909441351937, + -0.010933402925729798, + -0.017373563721776057, + -0.01951843500137334, + -0.01950659230351453, + -0.02521649934351449, + -0.028054039925336886, + -0.03161818161606793, + -0.0337632074952126, + -0.03660276159644131, + -0.03872621059417729, + -0.038730673491954845, + -0.04226849973201756, + -0.042969878762960476, + -0.04652139171957974, + -0.04435248672962193, + -0.04505516216158871, + -0.04504576697945599, + -0.04790363833308224, + -0.046463824808597606, + -0.04717928171157841, + -0.04789755493402485, + -0.047901812940835994, + -0.04862389713525776, + -0.04935320839285855, + -0.05079411342740063, + -0.05151995271444325, + -0.04937143251299862, + -0.04937408491969113, + -0.04866409301757817, + -0.04795478656888012, + -0.04724290221929554, + -0.04509592056274418, + -0.04367746785283093, + -0.04225326701998715, + -0.04011628404259685, + -0.03655086830258373, + -0.035125195980072056, + -0.033696517348289524, + -0.02941231615841393, + -0.02727223187685017, + -0.025134533643722576, + -0.021557345986366314, + -0.019422499462962192, + -0.015135486610233822, + -0.012280078604817429, + null, + -0.004429116379469673, + 0.0005693156854249141, + 0.0034256535582244, + 0.00770956464111801, + 0.010568411089479885, + 0.013432271778583488, + 0.016291353851556736, + 0.019872540608048397, + 0.02130162715911861, + 0.02487339265644546, + 0.024128941819071728, + 0.029863595962524372, + 0.030547956004738766, + 0.031956832855939823, + 0.03770274668931957, + 0.039106253534555394, + 0.04051845148205753, + 0.04266897588968273, + 0.04625057801604267, + 0.04479653015732761, + 0.04911410808563228, + 0.04694171994924541, + 0.049103882163763005, + 0.04693499580025669, + 0.046215854585170704, + 0.04622003063559528, + 0.049115601927041966, + 0.04768155515193935, + 0.0448021329939365, + 0.04553604871034618, + 0.042669299989938694, + 0.0419593974947929, + 0.03408450260758396, + 0.03767329454421993, + 0.032673291862010914, + 0.031959079205989796, + 0.031959079205989796, + 0.03415289521217342, + 0.028408870100974988, + 0.024823686107993077, + 0.021963344886898946, + 0.024142730981111478, + 0.01768261380493636, + 0.016992390155792188, + 0.014852200634777499, + 0.006964050699025346, + 0.00410403357818718, + 0.00483587617054577, + -0.00877494830638175, + 0.0026890693698077926, + -0.00017779308836911846, + -0.0080579044297338, + -0.008774089626967954, + -0.013069991953671025, + -0.013075213879346894, + -0.01737094484269624, + -0.014521293342113542, + -0.033932752907276195, + -0.0231188796460629, + -0.027409566566348124, + -0.0281372051686049, + -0.03172573819756512, + -0.03456233069300656, + -0.03459722548723225, + -0.039572644978761715, + -0.040974538773298305, + -0.04454799368977551, + -0.045255456119775814, + -0.04736703261733059, + -0.04878984019160275, + -0.04808713495731358, + -0.050901569426059765, + -0.05159723013639454, + -0.05229930207133297, + -0.05227875337004666, + -0.05156677216291432, + -0.05225743725895886, + -0.053679052740335506, + -0.053669001907110256, + -0.0550986118614674, + -0.055090688169002575, + -0.053646720945835155, + -0.052923966199159664, + -0.052204594016075176, + -0.05076870694756512, + -0.04933518916368489 + ] +} \ No newline at end of file