diff --git a/.python-version b/.python-version
index 24ee5b1be..2c0733315 100644
--- a/.python-version
+++ b/.python-version
@@ -1 +1 @@
-3.13
+3.11
diff --git a/deploy.py b/deploy.py
new file mode 100644
index 000000000..a1b1798a5
--- /dev/null
+++ b/deploy.py
@@ -0,0 +1,601 @@
+"""
+Humanoid Sim2Sim Deployment for mjlab-trained policies.
+
+This script:
+1. Loads an ONNX policy exported from mjlab
+2. Extracts KP/KD/action_scale from ONNX metadata
+3. Builds observations matching mjlab's velocity task
+4. Runs sim2sim in MuJoCo with video recording and analysis
+
+Observation tensor layout (47 dims - mjlab Humanoid with gait_clock):
+ 0-2: base_ang_vel (3) - IMU angular velocity in body frame
+ 3-5: projected_gravity (3) - Gravity projected into body frame
+ 6-8: command (3) - Velocity command (vx, vy, wz)
+ 9-20: joint_pos (12) - Joint positions relative to default
+ 21-32: joint_vel (12) - Joint velocities
+ 33-44: actions (12) - Last action sent
+ 45-46: gait_clock (2) - [cos(phase), sin(phase)] for gait timing
+"""
+
+import os
+os.environ["MUJOCO_GL"] = "egl"
+
+import argparse
+import csv
+import time
+from datetime import datetime
+
+import cv2
+import matplotlib.pyplot as plt
+import mujoco
+import numpy as np
+import onnx
+import onnxruntime as ort
+import pandas as pd
+
+
+# ============================================================================
+# Configuration
+# ============================================================================
+
+# Robot model (same XML used for training)
+XML_PATH = "src/mjlab/asset_zoo/robots/humanoid/xmls/humanoid.xml"
+
+# Simulation parameters
+SIMULATION_DURATION = 20.0 # seconds
+SIMULATION_DT = 0.005 # 200 Hz physics (matches mjlab)
+CONTROL_DECIMATION = 4 # Policy runs at 50 Hz
+
+# Video parameters
+VIDEO_WIDTH = 1280
+VIDEO_HEIGHT = 720
+VIDEO_FPS = 30
+
+# Number of observations and actions
+NUM_OBS = 47 # base_ang_vel(3) + projected_gravity(3) + command(3) + joint_pos(12) + joint_vel(12) + actions(12) + gait_clock(2)
+NUM_ACTIONS = 12
+
+# Gait clock frequency (Hz) - must match training config
+GAIT_FREQ = 1.25 # Matches mjlab training config
+
+# Joint limits for plotting
+JOINT_LIMITS = {
+ "L_hip_pitch": (-2.094, 1.000),
+ "L_hip_roll": (-0.785, 0.785),
+ "L_hip_yaw": (-0.785, 0.785),
+ "L_knee": (-1.5, 1.5),
+ "L_ankle_pitch": (-0.5, 0.5),
+ "L_ankle_roll": (-0.1, 0.1),
+ "R_hip_pitch": (-1.000, 2.094),
+ "R_hip_roll": (-0.785, 0.785),
+ "R_hip_yaw": (-0.785, 0.785),
+ "R_knee": (-1.5, 1.5),
+ "R_ankle_pitch": (-0.5, 0.5),
+ "R_ankle_roll": (-0.1, 0.1),
+}
+
+
+# ============================================================================
+# Helper Functions
+# ============================================================================
+
+def parse_csv_floats(s: str) -> list[float]:
+ """Parse comma-separated float string."""
+ return [float(x) for x in s.split(",")]
+
+
+def load_onnx_with_metadata(onnx_path: str) -> dict:
+ """Load ONNX model and extract metadata."""
+ model = onnx.load(onnx_path)
+ metadata = {}
+ for prop in model.metadata_props:
+ metadata[prop.key] = prop.value
+ return metadata
+
+
+def pd_control(target_q, q, kp, target_dq, dq, kd):
+ """PD controller for joint torques (used when actuators are motors)."""
+ return (target_q - q) * kp + (target_dq - dq) * kd
+
+
+def create_position_actuators(spec, joint_names, kps, kds, effort_limits, armatures):
+ """Modify existing actuators to be position actuators (matching mjlab training)."""
+ # Modify existing actuators to position type with KP/KD
+ for i, joint_name in enumerate(joint_names):
+ # Find the existing actuator for this joint
+ act_name = f"{joint_name}_ctrl"
+ act = None
+ for a in spec.actuators:
+ if a.name == act_name:
+ act = a
+ break
+
+ if act is None:
+ # Create new actuator if not found
+ act = spec.add_actuator()
+ act.name = f"{joint_name}_pos"
+ # Find joint by iterating through spec.joints
+ joint = None
+ for j in spec.joints:
+ if j.name == joint_name:
+ joint = j
+ break
+ if joint is not None:
+ act.target = joint.full_name
+ act.trntype = mujoco.mjtTrn.mjTRN_JOINT
+
+ # Configure as position actuator
+ act.gaintype = mujoco.mjtGain.mjGAIN_FIXED
+ act.biastype = mujoco.mjtBias.mjBIAS_AFFINE
+ act.gainprm[0] = kps[i] # kp gain
+ act.biasprm[0] = 0.0 # bias offset
+ act.biasprm[1] = -kps[i] # -kp (position bias)
+ act.biasprm[2] = -kds[i] # -kd (velocity bias)
+ if effort_limits is not None:
+ act.forcerange = (-effort_limits[i], effort_limits[i])
+
+ # Set armature on joint
+ joint = None
+ for j in spec.joints:
+ if j.name == joint_name:
+ joint = j
+ break
+ if joint is not None:
+ joint.armature = armatures[i]
+
+
+def get_projected_gravity(quat):
+ """
+ Get gravity vector projected into body frame.
+
+ MuJoCo quaternion format: (w, x, y, z)
+ Gravity in world frame: (0, 0, -1)
+
+ This computes: R^T @ [0, 0, -1] where R is rotation from body to world.
+ Uses the same formula as mjlab's quat_apply_inverse.
+ """
+ w, x, y, z = quat
+ # Rotate [0, 0, -1] by inverse quaternion (matching mjlab quat_apply_inverse)
+ gx = 2.0 * (w * y - x * z)
+ gy = -2.0 * (w * x + y * z)
+ gz = -1.0 + 2.0 * (x * x + y * y)
+ return np.array([gx, gy, gz], dtype=np.float32)
+
+
+def get_imu_data(data):
+ """Get IMU sensor data (velocimeter and gyro in body frame)."""
+ # MuJoCo velocimeter and gyro sensors output in body frame
+ lin_vel = data.sensor("imu_lin_vel").data.copy().astype(np.float32)
+ ang_vel = data.sensor("imu_ang_vel").data.copy().astype(np.float32)
+ return lin_vel, ang_vel
+
+
+def analyze_results(csv_path, joint_names, output_prefix):
+ """Analyze simulation results and generate plots."""
+ df = pd.read_csv(csv_path)
+ time_arr = df['time'].values
+
+ short_names = []
+ for name in joint_names:
+ short = name.replace("_joint", "").replace("left_", "L_").replace("right_", "R_")
+ short_names.append(short)
+
+ print("\n" + "=" * 70)
+ print("TRACKING ERROR ANALYSIS")
+ print("=" * 70)
+
+ print(f"\nStability Metrics:")
+ print(f" Pelvis height: {df['pelvis_z'].mean():.3f} +/- {df['pelvis_z'].std():.4f} m")
+ print(f" Gravity Z: {df['grav_z'].mean():.3f} +/- {df['grav_z'].std():.4f} (upright = -1.0)")
+
+ print(f"\n{'Joint':<14} {'RMS (rad)':<12} {'RMS (deg)':<12} {'Max (rad)':<12}")
+ print("-" * 50)
+
+ settled = df[df['time'] > 1.0]
+ for short in short_names:
+ if f"err_{short}" in df.columns:
+ err = settled[f"err_{short}"]
+ rms = np.sqrt(np.mean(err**2))
+ max_err = np.abs(err).max()
+ print(f"{short:<14} {rms:<12.4f} {np.degrees(rms):<12.2f} {max_err:<12.4f}")
+
+ # Plot 1: Target vs Actual Joint Positions
+ fig, axes = plt.subplots(4, 3, figsize=(14, 10))
+ axes = axes.flatten()
+ fig.suptitle("Target vs Actual Joint Positions", fontsize=14, fontweight='bold')
+
+ for i, (ax, short) in enumerate(zip(axes, short_names)):
+ if f"tgt_{short}" not in df.columns:
+ continue
+ tgt = df[f"tgt_{short}"].values
+ act = df[f"act_{short}"].values
+
+ ax.plot(time_arr, tgt, 'b-', linewidth=1.5, label='Target', alpha=0.8)
+ ax.plot(time_arr, act, 'g-', linewidth=1.5, label='Actual', alpha=0.8)
+ ax.axhline(y=0, color='gray', linestyle=':', alpha=0.5)
+
+ if short in JOINT_LIMITS:
+ lim_min, lim_max = JOINT_LIMITS[short]
+ ax.axhline(y=lim_min, color='r', linestyle='--', linewidth=1, alpha=0.7)
+ ax.axhline(y=lim_max, color='r', linestyle='--', linewidth=1, alpha=0.7)
+ ax.fill_between(time_arr, lim_min, lim_max, color='green', alpha=0.1)
+
+ ax.set_title(short, fontsize=11)
+ ax.set_xlabel("Time (s)", fontsize=9)
+ ax.set_ylabel("Angle (rad)", fontsize=9)
+ ax.grid(True, alpha=0.3)
+ ax.tick_params(labelsize=8)
+ if i == 0:
+ ax.legend(fontsize=8, loc='upper right')
+
+ plt.tight_layout()
+ plot1_path = f"{output_prefix}_joints.png"
+ plt.savefig(plot1_path, dpi=150, bbox_inches='tight')
+ plt.close()
+ print(f"\nSaved: {plot1_path}")
+
+ # Plot 2: Stability Metrics
+ fig2, (ax1, ax2) = plt.subplots(2, 1, figsize=(10, 6))
+ fig2.suptitle("Robot Stability Metrics", fontsize=14, fontweight='bold')
+
+ ax1.plot(time_arr, df['pelvis_z'].values, 'b-', linewidth=2)
+ ax1.axhline(y=0.75, color='r', linestyle='--', alpha=0.7, label='Target height')
+ ax1.set_ylabel("Pelvis Height (m)", fontsize=11)
+ ax1.set_xlabel("Time (s)", fontsize=11)
+ ax1.legend(fontsize=9)
+ ax1.grid(True, alpha=0.3)
+ ax1.set_ylim([0.3, 0.9])
+
+ ax2.plot(time_arr, df['grav_z'].values, 'g-', linewidth=2)
+ ax2.axhline(y=-1.0, color='r', linestyle='--', alpha=0.7, label='Upright (-1.0)')
+ ax2.set_ylabel("Gravity Z (body frame)", fontsize=11)
+ ax2.set_xlabel("Time (s)", fontsize=11)
+ ax2.legend(fontsize=9)
+ ax2.grid(True, alpha=0.3)
+ ax2.set_ylim([-1.1, 0.5])
+
+ plt.tight_layout()
+ plot2_path = f"{output_prefix}_stability.png"
+ plt.savefig(plot2_path, dpi=150, bbox_inches='tight')
+ plt.close()
+ print(f"Saved: {plot2_path}")
+
+ # Plot 3: IMU Data
+ fig3, axes3 = plt.subplots(3, 1, figsize=(12, 8))
+ fig3.suptitle("IMU Data", fontsize=14, fontweight='bold')
+
+ ax = axes3[0]
+ ax.plot(time_arr, df['quat_w'].values, 'b-', linewidth=1.5, label='w', alpha=0.8)
+ ax.plot(time_arr, df['quat_x'].values, 'r-', linewidth=1.5, label='x', alpha=0.8)
+ ax.plot(time_arr, df['quat_y'].values, 'g-', linewidth=1.5, label='y', alpha=0.8)
+ ax.plot(time_arr, df['quat_z'].values, 'm-', linewidth=1.5, label='z', alpha=0.8)
+ ax.set_ylabel("Quaternion", fontsize=11)
+ ax.set_xlabel("Time (s)", fontsize=11)
+ ax.legend(fontsize=9, loc='upper right', ncol=4)
+ ax.grid(True, alpha=0.3)
+ ax.set_ylim([-1.1, 1.1])
+
+ ax = axes3[1]
+ ax.plot(time_arr, df['lin_vel_x'].values, 'r-', linewidth=1.5, label='vx', alpha=0.8)
+ ax.plot(time_arr, df['lin_vel_y'].values, 'g-', linewidth=1.5, label='vy', alpha=0.8)
+ ax.plot(time_arr, df['lin_vel_z'].values, 'b-', linewidth=1.5, label='vz', alpha=0.8)
+ ax.axhline(y=0, color='gray', linestyle=':', alpha=0.5)
+ ax.set_ylabel("Linear Velocity (m/s)", fontsize=11)
+ ax.set_xlabel("Time (s)", fontsize=11)
+ ax.legend(fontsize=9, loc='upper right')
+ ax.grid(True, alpha=0.3)
+
+ ax = axes3[2]
+ ax.plot(time_arr, df['ang_vel_x'].values, 'r-', linewidth=1.5, label='wx', alpha=0.8)
+ ax.plot(time_arr, df['ang_vel_y'].values, 'g-', linewidth=1.5, label='wy', alpha=0.8)
+ ax.plot(time_arr, df['ang_vel_z'].values, 'b-', linewidth=1.5, label='wz', alpha=0.8)
+ ax.axhline(y=0, color='gray', linestyle=':', alpha=0.5)
+ ax.set_ylabel("Angular Velocity (rad/s)", fontsize=11)
+ ax.set_xlabel("Time (s)", fontsize=11)
+ ax.legend(fontsize=9, loc='upper right')
+ ax.grid(True, alpha=0.3)
+
+ plt.tight_layout()
+ plot3_path = f"{output_prefix}_imu.png"
+ plt.savefig(plot3_path, dpi=150, bbox_inches='tight')
+ plt.close()
+ print(f"Saved: {plot3_path}")
+
+
+# ============================================================================
+# Main Simulation
+# ============================================================================
+
+def main():
+ parser = argparse.ArgumentParser(description="Humanoid sim2sim deployment for mjlab policies")
+ parser.add_argument("--policy", type=str, required=True, help="Path to ONNX policy file")
+ parser.add_argument("--cmd_vx", type=float, default=0.5, help="X velocity command (m/s)")
+ parser.add_argument("--cmd_vy", type=float, default=0.0, help="Y velocity command (m/s)")
+ parser.add_argument("--cmd_wz", type=float, default=0.0, help="Yaw rate command (rad/s)")
+ parser.add_argument("--duration", type=float, default=SIMULATION_DURATION, help="Simulation duration (s)")
+ parser.add_argument("--push_force", type=float, default=0.0, help="Push force in N (applied at push_time)")
+ parser.add_argument("--push_time", type=float, default=2.0, help="Time to apply push (s)")
+ parser.add_argument("--push_duration", type=float, default=0.1, help="Duration of push (s)")
+ parser.add_argument("--push_dir", type=str, default="x", choices=["x", "y", "-x", "-y"], help="Push direction (x=forward, y=left, -x=back, -y=right)")
+ args = parser.parse_args()
+
+ timestamp = datetime.now().strftime('%Y-%m-%d_%H-%M-%S')
+
+ script_dir = os.path.dirname(os.path.abspath(__file__))
+ log_dir = os.path.join(script_dir, "logs", timestamp)
+ os.makedirs(log_dir, exist_ok=True)
+
+ video_output = os.path.join(log_dir, "sim2sim.mp4")
+ csv_output = os.path.join(log_dir, "sim2sim.csv")
+ output_prefix = os.path.join(log_dir, "sim2sim")
+
+ # Load ONNX metadata
+ print("=" * 60)
+ print("Humanoid Sim2Sim - mjlab Policy Deployment")
+ print("=" * 60)
+ print(f"Policy: {args.policy}")
+
+ metadata = load_onnx_with_metadata(args.policy)
+
+ joint_names = metadata["joint_names"].split(",")
+ kps = np.array(parse_csv_floats(metadata["joint_stiffness"]), dtype=np.float32)
+ kds = np.array(parse_csv_floats(metadata["joint_damping"]), dtype=np.float32)
+ default_joint_pos = np.array(parse_csv_floats(metadata["default_joint_pos"]), dtype=np.float32)
+ action_scale = np.array(parse_csv_floats(metadata["action_scale"]), dtype=np.float32)
+ observation_names = metadata["observation_names"].split(",")
+
+ print(f"\nExtracted from ONNX metadata:")
+ print(f" Joint names: {joint_names}")
+ print(f" KP: {kps}")
+ print(f" KD: {kds}")
+ print(f" Default pos: {default_joint_pos}")
+ print(f" Action scale: {action_scale}")
+ print(f" Observations: {observation_names}")
+
+ # Torque limits (from motor specs)
+ torque_limits = np.array([120, 90, 60, 75, 36, 36, 120, 90, 60, 75, 36, 36], dtype=np.float32)
+
+ # Velocity command
+ cmd = np.array([args.cmd_vx, args.cmd_vy, args.cmd_wz], dtype=np.float32)
+ print(f"\nVelocity command: vx={cmd[0]:.2f}, vy={cmd[1]:.2f}, wz={cmd[2]:.2f}")
+ if args.push_force > 0:
+ print(f"Push: {args.push_force:.0f}N at t={args.push_time:.1f}s for {args.push_duration:.2f}s")
+
+ # Load ONNX policy
+ print("\nLoading ONNX policy...")
+ ort_session = ort.InferenceSession(args.policy)
+ input_name = ort_session.get_inputs()[0].name
+ print(f" Input name: {input_name}")
+ print(f" Input shape: {ort_session.get_inputs()[0].shape}")
+
+ # Load MuJoCo model using MjSpec to create position actuators (matching mjlab training)
+ print("\nLoading MuJoCo model with position actuators...")
+ os.chdir(script_dir)
+ xml_path = os.path.join(script_dir, XML_PATH)
+
+ # Load XML into MjSpec so we can modify actuators
+ spec = mujoco.MjSpec.from_file(xml_path)
+
+ # Armature values from humanoid_constants.py (reflected inertia)
+ armatures = np.array([
+ 0.0652, 0.100, 0.0343, 0.0330, 0.0236, 0.0236, # left leg
+ 0.0652, 0.100, 0.0343, 0.0330, 0.0236, 0.0236, # right leg
+ ], dtype=np.float32)
+
+ # Create position actuators (replaces motor actuators from XML)
+ create_position_actuators(spec, joint_names, kps, kds, torque_limits, armatures)
+
+ # Compile the modified spec
+ m = spec.compile()
+ d = mujoco.MjData(m)
+ m.opt.timestep = SIMULATION_DT
+
+ # Get joint indices (actuators now match joint_names order)
+ actuated_joint_names = joint_names
+ print("\nActuated Joint Order (position actuators):")
+ for i, name in enumerate(actuated_joint_names):
+ print(f" {i:02d}: {name}")
+
+ # Find joint qpos/qvel indices
+ qpos_ids = []
+ qvel_ids = []
+ for jname in joint_names:
+ jid = mujoco.mj_name2id(m, mujoco.mjtObj.mjOBJ_JOINT, jname)
+ qpos_ids.append(m.jnt_qposadr[jid])
+ qvel_ids.append(m.jnt_dofadr[jid])
+ qpos_ids = np.array(qpos_ids)
+ qvel_ids = np.array(qvel_ids)
+
+ short_names = []
+ for name in actuated_joint_names:
+ short = name.replace("_joint", "").replace("left_", "L_").replace("right_", "R_")
+ short_names.append(short)
+
+ # Initialize robot state
+ d.qpos[7:7+NUM_ACTIONS] = default_joint_pos
+ d.qpos[2] = 0.75 # Starting height
+ d.qvel[:] = 0.0
+ mujoco.mj_forward(m, d)
+
+ # Get pelvis body id for applying push force
+ pelvis_body_id = mujoco.mj_name2id(m, mujoco.mjtObj.mjOBJ_BODY, "pelvis_link")
+ push_start_step = int(args.push_time / SIMULATION_DT)
+ push_end_step = int((args.push_time + args.push_duration) / SIMULATION_DT)
+
+ # Setup video recording
+ print(f"\nSetting up video recording ({VIDEO_WIDTH}x{VIDEO_HEIGHT} @ {VIDEO_FPS}fps)...")
+ renderer = mujoco.Renderer(m, VIDEO_HEIGHT, VIDEO_WIDTH)
+
+ fourcc = cv2.VideoWriter_fourcc(*'mp4v')
+ video_writer = cv2.VideoWriter(video_output, fourcc, VIDEO_FPS, (VIDEO_WIDTH, VIDEO_HEIGHT))
+
+ # Setup CSV logging
+ csv_file = open(csv_output, "w", newline="")
+ csv_writer = csv.writer(csv_file)
+
+ header = ["step", "time", "pelvis_x", "pelvis_y", "pelvis_z"]
+ header += ["quat_w", "quat_x", "quat_y", "quat_z"]
+ header += ["lin_vel_x", "lin_vel_y", "lin_vel_z"]
+ header += ["ang_vel_x", "ang_vel_y", "ang_vel_z"]
+ header += ["grav_x", "grav_y", "grav_z"]
+ for short in short_names:
+ header += [f"tgt_{short}", f"act_{short}", f"err_{short}"]
+ csv_writer.writerow(header)
+
+ # Initialize state variables
+ action = np.zeros(NUM_ACTIONS, dtype=np.float32)
+ target_dof_pos = default_joint_pos.copy()
+ obs = np.zeros(NUM_OBS, dtype=np.float32)
+
+ # Gait clock state - tracks phase in [0, 1) like mjlab
+ gait_phase = 0.0
+ control_dt = SIMULATION_DT * CONTROL_DECIMATION # 0.02s at 50Hz
+
+ counter = 0
+ frame_counter = 0
+ frames_per_video_frame = int(1.0 / (VIDEO_FPS * SIMULATION_DT))
+ total_steps = int(args.duration / SIMULATION_DT)
+
+ print(f"\nRunning simulation for {args.duration} seconds...")
+ print(f"Output: {log_dir}/")
+ start_time = time.time()
+
+ for step_idx in range(total_steps):
+ # Get current joint state
+ q = d.qpos[qpos_ids]
+ dq = d.qvel[qvel_ids]
+
+ # With position actuators, send position targets directly
+ # MuJoCo's built-in PD controller handles torque computation
+ d.ctrl[:] = target_dof_pos
+
+ # Apply external push force if within push window
+ if args.push_force > 0 and push_start_step <= step_idx < push_end_step:
+ # Apply force in specified direction
+ if args.push_dir == "x":
+ d.xfrc_applied[pelvis_body_id, 0] = args.push_force
+ elif args.push_dir == "-x":
+ d.xfrc_applied[pelvis_body_id, 0] = -args.push_force
+ elif args.push_dir == "y":
+ d.xfrc_applied[pelvis_body_id, 1] = args.push_force
+ elif args.push_dir == "-y":
+ d.xfrc_applied[pelvis_body_id, 1] = -args.push_force
+ else:
+ d.xfrc_applied[pelvis_body_id, :] = 0
+
+ mujoco.mj_step(m, d)
+
+ counter += 1
+
+ # Policy inference at control frequency
+ if counter % CONTROL_DECIMATION == 0:
+ # Get observations
+ qj = d.qpos[qpos_ids]
+ dqj = d.qvel[qvel_ids]
+ pelvis_quat = d.qpos[3:7] # (w, x, y, z)
+
+ # Get body frame velocities from MuJoCo sensors
+ lin_vel, ang_vel = get_imu_data(d)
+
+ # Projected gravity
+ grav = get_projected_gravity(pelvis_quat)
+
+ # Build observation vector (mjlab Humanoid order - 47 dims):
+ # [base_ang_vel(3), projected_gravity(3), command(3),
+ # joint_pos(12), joint_vel(12), actions(12), gait_clock(2)]
+
+ # Update gait phase - only advances when command is active (like mjlab)
+ cmd_magnitude = np.sqrt(cmd[0]**2 + cmd[1]**2) + abs(cmd[2])
+ if cmd_magnitude > 0.1: # command_threshold from training config
+ gait_phase = (gait_phase + control_dt * GAIT_FREQ) % 1.0
+
+ # Convert phase to cos/sin (phase is in [0,1), multiply by 2π)
+ phase_2pi = 2.0 * np.pi * gait_phase
+
+ obs[0:3] = ang_vel # base_ang_vel
+ obs[3:6] = grav # projected_gravity
+ obs[6:9] = cmd # command
+ obs[9:21] = qj - default_joint_pos # joint_pos (relative)
+ obs[21:33] = dqj # joint_vel
+ obs[33:45] = action # last action
+ obs[45:47] = [np.cos(phase_2pi), np.sin(phase_2pi)] # gait_clock [cos, sin]
+
+ # Run ONNX inference
+ obs_input = obs.reshape(1, -1).astype(np.float32)
+ action = ort_session.run(None, {input_name: obs_input})[0].squeeze()
+
+ # Compute target position
+ target_dof_pos = default_joint_pos + action * action_scale
+
+ # Log to CSV
+ sim_time = step_idx * SIMULATION_DT
+ pelvis_pos = d.qpos[0:3]
+
+ row = [counter, f"{sim_time:.3f}"]
+ row += [f"{pelvis_pos[0]:.4f}", f"{pelvis_pos[1]:.4f}", f"{pelvis_pos[2]:.4f}"]
+ row += [f"{pelvis_quat[0]:.4f}", f"{pelvis_quat[1]:.4f}", f"{pelvis_quat[2]:.4f}", f"{pelvis_quat[3]:.4f}"]
+ row += [f"{lin_vel[0]:.4f}", f"{lin_vel[1]:.4f}", f"{lin_vel[2]:.4f}"]
+ row += [f"{ang_vel[0]:.4f}", f"{ang_vel[1]:.4f}", f"{ang_vel[2]:.4f}"]
+ row += [f"{grav[0]:.4f}", f"{grav[1]:.4f}", f"{grav[2]:.4f}"]
+
+ for i in range(NUM_ACTIONS):
+ tgt = target_dof_pos[i]
+ act = qj[i]
+ err = tgt - act
+ row += [f"{tgt:.4f}", f"{act:.4f}", f"{err:.4f}"]
+ csv_writer.writerow(row)
+
+ # Record video frame
+ if counter % frames_per_video_frame == 0:
+ renderer.update_scene(d, camera="side_camera")
+ frame = renderer.render()
+ frame_bgr = cv2.cvtColor(frame, cv2.COLOR_RGB2BGR)
+
+ sim_time = step_idx * SIMULATION_DT
+ pelvis_z = d.qpos[2]
+ grav_z = get_projected_gravity(d.qpos[3:7])[2]
+ status = "STANDING" if (pelvis_z > 0.4 and grav_z < -0.5) else "FALLEN!"
+
+ cv2.putText(frame_bgr, f"Time: {sim_time:.2f}s", (10, 30),
+ cv2.FONT_HERSHEY_SIMPLEX, 1, (255, 255, 255), 2)
+ cv2.putText(frame_bgr, f"Cmd: vx={cmd[0]:.2f} vy={cmd[1]:.2f} wz={cmd[2]:.2f}",
+ (10, 70), cv2.FONT_HERSHEY_SIMPLEX, 0.7, (255, 255, 255), 2)
+ cv2.putText(frame_bgr, f"Height: {pelvis_z:.2f}m | {status}",
+ (10, 110), cv2.FONT_HERSHEY_SIMPLEX, 0.7, (255, 255, 255), 2)
+
+ video_writer.write(frame_bgr)
+ frame_counter += 1
+
+ # Progress update
+ if step_idx % int(0.5 / SIMULATION_DT) == 0:
+ sim_time = step_idx * SIMULATION_DT
+ pelvis_x, pelvis_y, pelvis_z = d.qpos[0:3]
+ grav = get_projected_gravity(d.qpos[3:7])
+ is_upright = grav[2] < -0.5
+ status = "STANDING" if (pelvis_z > 0.4 and is_upright) else "FALLEN!"
+ print(f" t={sim_time:5.1f}s | pos=({pelvis_x:5.2f},{pelvis_y:5.2f},{pelvis_z:.2f}) | {status}")
+
+ # Cleanup
+ video_writer.release()
+ renderer.close()
+ csv_file.close()
+
+ elapsed = time.time() - start_time
+ print(f"\nSimulation completed in {elapsed:.2f}s (real time)")
+
+ print(f"\n{'=' * 60}")
+ print(f"Simulation complete!")
+ print(f" Total frames: {frame_counter}")
+ print(f" Video saved: {video_output}")
+ print(f" CSV saved: {csv_output}")
+ print(f"{'=' * 60}")
+
+ # Generate analysis plots
+ print("\nGenerating analysis plots...")
+ analyze_results(csv_output, actuated_joint_names, output_prefix)
+
+ print("\nDone!")
+
+
+if __name__ == "__main__":
+ main()
diff --git a/docs/source/_static/content/humanoid.png b/docs/source/_static/content/humanoid.png
new file mode 100644
index 000000000..d471b1475
Binary files /dev/null and b/docs/source/_static/content/humanoid.png differ
diff --git a/docs/source/_static/content/humanoid_sim.gif b/docs/source/_static/content/humanoid_sim.gif
new file mode 100644
index 000000000..a3862153b
Binary files /dev/null and b/docs/source/_static/content/humanoid_sim.gif differ
diff --git a/motor_parameters.md b/motor_parameters.md
new file mode 100644
index 000000000..4ff825a03
--- /dev/null
+++ b/motor_parameters.md
@@ -0,0 +1,342 @@
+# Humanoid Motor Parameters Reference
+
+## Motor Assignments
+
+| Joint | Side | Motor ID | CAN ID | Actuator Model | Gear Ratio | Gear Type |
+|-------|------|----------|--------|----------------|------------|-----------|
+| hip_pitch | L | 0 | 0x01 | EC-A6416-P2-25 | 25:1 | Planetary (P2) |
+| hip_pitch | R | 6 | 0x07 | EC-A6416-P2-25 | 25:1 | Planetary (P2) |
+| hip_roll | L | 1 | 0x02 | EC-A5013-H17-100 | 100:1 | Harmonic (H17) |
+| hip_roll | R | 7 | 0x08 | EC-A5013-H17-100 | 100:1 | Harmonic (H17) |
+| hip_yaw | L | 2 | 0x03 | EC-A3814-H14-107 | 107:1 | Harmonic (H14) |
+| hip_yaw | R | 8 | 0x09 | EC-A3814-H14-107 | 107:1 | Harmonic (H14) |
+| knee | L | 3 | 0x04 | EC-A4315-P2-36 | 36:1 | Planetary (P2) |
+| knee | R | 9 | 0x0A | EC-A4315-P2-36 | 36:1 | Planetary (P2) |
+| ankle_pitch | L | 4 | 0x05 | EC-A4310-P2-36 | 36:1 | Planetary (P2) |
+| ankle_pitch | R | 10 | 0x0B | EC-A4310-P2-36 | 36:1 | Planetary (P2) |
+| ankle_roll | L | 5 | 0x06 | EC-A4310-P2-36 | 36:1 | Planetary (P2) |
+| ankle_roll | R | 11 | 0x0C | EC-A4310-P2-36 | 36:1 | Planetary (P2) |
+
+---
+
+## Complete Motor Specifications (from ENCOS Spec Sheets)
+
+### EC-A6416-P2-25 (Hip Pitch)
+
+| Parameter | Value | Unit |
+|-----------|-------|------|
+| Reduction Ratio | 25 | - |
+| Rated Voltage | 48 | V |
+| Rated Bus Current | 13 | A |
+| Rated Phase Current | 17.5 | A |
+| Rated Power | 624 | W |
+| Rated Speed | 107 | RPM |
+| Rated Torque | 40 | Nm |
+| Peak Speed | 120 | RPM |
+| Peak Phase Current | 60 | A |
+| Peak Torque | 120 | Nm |
+| Efficiency | 73 | % |
+| Torque Constant (KT) | 2.74 | Nm/A |
+| Weight | 803 | g |
+| Backlash | 15 | Arcmin |
+| Motor Size (OD × Thickness) | 88 × 67.5 | mm |
+| Communication | CAN | - |
+| Baud Rate | 1M | - |
+| Double Encoder | Yes | - |
+| Axial/Radial Load | 2.14 | kN |
+| Bending Moment Resistance | 40 | Nm |
+| Cross Roller Bearing Type | 4005 | - |
+| **Rotor Inertia** | **104.395** | **kg·mm²** |
+| Torque Density | 149.44 | Nm/kg |
+
+### EC-A5013-H17-100 (Hip Roll)
+
+| Parameter | Value | Unit |
+|-----------|-------|------|
+| Reduction Ratio | 100 | - |
+| Rated Voltage | 48 | V |
+| Rated Bus Current | 2.5 | A |
+| Rated Phase Current | 3.0 | A |
+| Rated Power | 120 | W |
+| Rated Speed | 33 | RPM |
+| Rated Torque | 30 | Nm |
+| Peak Speed | 38 | RPM |
+| Peak Phase Current | 20 | A |
+| Peak Torque | 90 | Nm |
+| Efficiency | 31 | % |
+| Torque Constant (KT) | 5.9 | Nm/A |
+| Weight | 640 | g |
+| Backlash | 10 | Arcsec |
+| Motor Size (OD × Thickness) | 63 × 81.5 | mm |
+| Communication | CAN | - |
+| Baud Rate | 1M | - |
+| Double Encoder | Yes | - |
+| Axial/Radial Load | 1.89 | kN |
+| Bending Moment Resistance | 28 | Nm |
+| Cross Roller Bearing Type | 3005 | - |
+| **Rotor Inertia** | **10** | **kg·mm²** |
+| Torque Density | 140.625 | Nm/kg |
+
+### EC-A3814-H14-107 (Hip Yaw)
+
+| Parameter | Value | Unit |
+|-----------|-------|------|
+| Reduction Ratio | 107 | - |
+| Rated Voltage | 48 | V |
+| Rated Bus Current | 2.8 | A |
+| Rated Phase Current | 4.0 | A |
+| Rated Power | 134.4 | W |
+| Rated Speed | 47 | RPM |
+| Rated Torque | 20 | Nm |
+| Peak Speed | 52 | RPM |
+| Peak Phase Current | 10 | A |
+| Peak Torque | 60 | Nm |
+| Efficiency | 51 | % |
+| Torque Constant (KT) | 4.2 | Nm/A |
+| Weight | 400 | g |
+| Backlash | 10 | Arcsec |
+| Motor Size (OD × Thickness) | 53 × 78.5 | mm |
+| Communication | CAN | - |
+| Baud Rate | 1M | - |
+| Double Encoder | Yes | - |
+| Axial/Radial Load | 1.89 | kN |
+| Bending Moment Resistance | 28 | Nm |
+| Cross Roller Bearing Type | 3005 | - |
+| **Rotor Inertia** | **3** | **kg·mm²** |
+| Torque Density | 150 | Nm/kg |
+
+### EC-A4315-P2-36 (Knee)
+
+| Parameter | Value | Unit |
+|-----------|-------|------|
+| Reduction Ratio | 36 | - |
+| Rated Voltage | 48 | V |
+| Rated Bus Current | 8.28 | A |
+| Rated Phase Current | 10.22 | A |
+| Rated Power | 397 | W |
+| Rated Speed | 109 | RPM |
+| Rated Torque | 25 | Nm |
+| Peak Speed | 117 | RPM |
+| Peak Phase Current | 30 | A |
+| Peak Torque | 75 | Nm |
+| Efficiency | 74 | % |
+| Torque Constant (KT) | 2.8 | Nm/A |
+| Weight | 455 | g |
+| Backlash | 10 | Arcmin |
+| Motor Size (OD × Thickness) | 56 × 69.5 | mm |
+| Communication | CAN | - |
+| Baud Rate | 1M | - |
+| Double Encoder | Yes | - |
+| Axial/Radial Load | 1.89 | kN |
+| Bending Moment Resistance | 28 | Nm |
+| Cross Roller Bearing Type | 3005 | - |
+| **Rotor Inertia** | **25.5** | **kg·mm²** |
+| Torque Density | 164.84 | Nm/kg |
+
+### EC-A4310-P2-36 (Ankle Pitch & Roll)
+
+| Parameter | Value | Unit |
+|-----------|-------|------|
+| Reduction Ratio | 36 | - |
+| Rated Voltage | 24 (supports 48V) | V |
+| Rated Bus Current | 6.5 | A |
+| Rated Phase Current | 7.8 | A |
+| Rated Power | 156 | W |
+| Rated Speed | 75 | RPM |
+| Rated Torque | 12 | Nm |
+| Peak Speed | 89 | RPM |
+| Peak Phase Current | 30 | A |
+| Peak Torque | 36 | Nm |
+| Efficiency | 71 | % |
+| Torque Constant (KT) | 1.4 | Nm/A |
+| Weight | 384 | g |
+| Backlash | 10 | Arcmin |
+| Motor Size (OD × Thickness) | 56 × 60.5 | mm |
+| Communication | CAN | - |
+| Baud Rate | 1M | - |
+| Double Encoder | Yes | - |
+| Axial/Radial Load | 1.89 | kN |
+| Bending Moment Resistance | TBD | Nm |
+| Cross Roller Bearing Type | TBD | - |
+| **Rotor Inertia** | **18.2** | **kg·mm²** |
+| Torque Density | TBD | Nm/kg |
+
+---
+
+## Summary Table
+
+| Motor | Joint | Gear Ratio | KT (Nm/A) | Rated Torque | Peak Torque | Weight | Rotor Inertia (kg·mm²) | Efficiency |
+|-------|-------|------------|-----------|--------------|-------------|--------|------------------------|------------|
+| EC-A6416-P2-25 | Hip Pitch | 25:1 | 2.74 | 40 Nm | 120 Nm | 803g | **104.395** | 73% |
+| EC-A5013-H17-100 | Hip Roll | 100:1 | 5.9 | 30 Nm | 90 Nm | 640g | **10** | 31% |
+| EC-A3814-H14-107 | Hip Yaw | 107:1 | 4.2 | 20 Nm | 60 Nm | 400g | **3** | 51% |
+| EC-A4315-P2-36 | Knee | 36:1 | 2.8 | 25 Nm | 75 Nm | 455g | **25.5** | 74% |
+| EC-A4310-P2-36 | Ankle | 36:1 | 1.4 | 12 Nm | 36 Nm | 384g | **18.2** | 71% |
+
+---
+
+## CAN Protocol Ranges (CRITICAL!)
+
+**EC系列力位混控协议范围 (EC Series Force/Position Mixed Control Protocol Range) - 2025.11.28**
+
+### Complete Protocol Specification
+
+| Motor Model | Gear Type | KP Range | KD Range | SPD Range (rad/s) | POS Range (rad) | Torque Range (Nm) | Current Range (A) | KT (Nm/A) |
+|-------------|-----------|----------|----------|-------------------|-----------------|-------------------|-------------------|-----------|
+| **EC-A2806-P2-36** | Planetary | 0~500 | 0~5 | -18~18 | -12.5~12.5 | -12~12 | -10~10 | 1.4 |
+| **EC-A4310-P2-36** | Planetary | 0~500 | 0~5 | -18~18 | -12.5~12.5 | -30~30 | -30~30 | 1.4 |
+| **EC-A4315-P2-36** | Planetary | 0~500 | 0~5 | -18~18 | -12.5~12.5 | -70~70 | -30~30 | 2.8 |
+| **EC-A6408-P2-25** | Planetary | 0~500 | 0~5 | -18~18 | -12.5~12.5 | -60~60 | -60~60 | 2.35 |
+| **EC-A6416-P2-25** | Planetary | 0~500 | 0~5 | -18~18 | -12.5~12.5 | -120~120 | -60~60 | 2.74 |
+| **EC-A8112-P1-18** | Planetary | 0~500 | 0~5 | -18~18 | -12.5~12.5 | -90~90 | -60~60 | 2.1 |
+| **EC-A8116-P1-18** | Planetary | 0~500 | 0~5 | -18~18 | -12.5~12.5 | -150~150 | -70~70 | 2.35 |
+| EC-A10020-P1-12/6 | Planetary | 0~500 | 0~5 | -18~18 | -12.5~12.5 | -150~150 | -70~70 | 2.5/1.7 |
+| EC-A13720-P1-11.4 | Planetary | 0~500 | 0~50 | -18~18 | -12.5~12.5 | -400~400 | -220~220 | 2.5 |
+| EC-A10020-P2-24 | Planetary | 0~500 | 0~50 | -18~18 | -12.5~12.5 | -300~300 | -140~140 | 2.6 |
+| EC-A13715-P1-12.67 | Planetary | 0~500 | 0~50 | -18~18 | -12.5~12.5 | -320~320 | -220~220 | 2.5 |
+| **EC-A3814-H14-107** | Harmonic | 0~500 | 0~5 | -18~18 | -12.5~12.5 | -60~60 | -20~20 | 4.2 |
+| **EC-A5013-H17-100** | Harmonic | 0~500 | 0~5 | -18~18 | -12.5~12.5 | -90~90 | -30~30 | 5.9 |
+| **EC-A6013-H20-100** | Harmonic | 0~500 | 0~5 | -18~18 | -12.5~12.5 | -130~130 | -35~35 | 5.6 |
+
+**Note:** From 2025/1/15, motors in red (larger models) have default KD range changed from 0~5 to 0~50.
+
+### Humanoid Motor CAN Ranges (Extracted)
+
+| Joint | Motor Model | KP Range | KD Range | Torque (Nm) | Current (A) | KT (Nm/A) |
+|-------|-------------|----------|----------|-------------|-------------|-----------|
+| **hip_pitch** | EC-A6416-P2-25 | 0~500 | 0~5 | ±120 | ±60 | 2.74 |
+| **hip_roll** | EC-A5013-H17-100 | 0~500 | 0~5 | ±90 | ±30 | 5.9 |
+| **hip_yaw** | EC-A3814-H14-107 | 0~500 | 0~5 | ±60 | ±20 | 4.2 |
+| **knee** | EC-A4315-P2-36 | 0~500 | 0~5 | ±70 | ±30 | 2.8 |
+| **ankle** | EC-A4310-P2-36 | 0~500 | 0~5 | ±30 | ±30 | 1.4 |
+
+---
+
+## CAN Current Feedback Scaling
+
+The CAN protocol reports current as 12-bit value (0-4095). The mapping to Amps depends on the actuator model:
+
+| Actuator Model | Current Range (A) | Scale Factor |
+|----------------|-------------------|--------------|
+| EC-A2806-P2-36 | -10 ~ +10 | 20.0/4095 |
+| EC-A4310-P2-36 | -30 ~ +30 | 60.0/4095 |
+| EC-A4315-P2-36 | -30 ~ +30 | 60.0/4095 |
+| EC-A6408-P2-25 | -60 ~ +60 | 120.0/4095 |
+| EC-A6416-P2-25 | -60 ~ +60 | 120.0/4095 |
+| EC-A8112-P1-18 | -60 ~ +60 | 120.0/4095 |
+| EC-A8116-P1-18 | -70 ~ +70 | 140.0/4095 |
+| EC-A10020-P1-12/6 | -70 ~ +70 | 140.0/4095 |
+| EC-A10020-P2-24 | -140 ~ +140 | 280.0/4095 |
+| EC-A13720-P1-11.4 | -220 ~ +220 | 440.0/4095 |
+| EC-A13715-P1-12.67 | -220 ~ +220 | 440.0/4095 |
+| EC-A3814-H14-107 | -20 ~ +20 | 40.0/4095 |
+| EC-A5013-H17-100 | -30 ~ +30 | 60.0/4095 |
+| EC-A6013-H20-100 | -35 ~ +35 | 70.0/4095 |
+
+**Verified Current Ranges for Humanoid Motors (from 2025.11.28 protocol table):**
+
+| Joint | Actuator | CAN Current Range | Notes |
+|-------|----------|-------------------|-------|
+| hip_pitch | EC-A6416-P2-25 | ±60 A | Confirmed |
+| hip_roll | EC-A5013-H17-100 | ±30 A | Confirmed (was 20A in old spec) |
+| hip_yaw | EC-A3814-H14-107 | ±20 A | Confirmed |
+| knee | EC-A4315-P2-36 | ±30 A | Confirmed |
+| ankle | EC-A4310-P2-36 | ±30 A | Confirmed |
+
+**Note:** The 2025.11.28 protocol table supersedes earlier spec sheets. Hip Roll is ±30A (not ±20A).
+
+## Current Decoding Formula
+
+```python
+# Generic formula
+current_a = (cur_raw * (2 * MAX_CURRENT / 4095.0)) - MAX_CURRENT
+
+# Per-joint MAX_CURRENT values (from 2025.11.28 protocol table):
+CURRENT_RANGE = {
+ "hip_pitch": 60.0, # EC-A6416-P2-25
+ "hip_roll": 30.0, # EC-A5013-H17-100
+ "hip_yaw": 20.0, # EC-A3814-H14-107
+ "knee": 30.0, # EC-A4315-P2-36
+ "ankle_pitch": 30.0, # EC-A4310-P2-36
+ "ankle_roll": 30.0, # EC-A4310-P2-36
+}
+```
+
+---
+
+## PD Gains (Firmware)
+
+**Current RL-trained gains:**
+
+| Joint | KP | KD |
+|-------|-----|-----|
+| hip_pitch | 12.8 | 0.8 |
+| hip_roll | 328.0 | 5.0 |
+| hip_yaw | 212.2 | 5.0 |
+| knee | 64.2 | 2.7 |
+| ankle_pitch | 19.3 | 3.3 |
+| ankle_roll | 18.1 | 0.9 |
+
+**CAN Protocol Gain Ranges:**
+- KP: 0-4095 -> 0-500 (12-bit)
+- KD: 0-511 -> 0-5.0 (9-bit) or 0-50 (depends on motor, see Table 9-1)
+
+---
+
+## Gain Identification Results
+
+**Comparison: Identified vs Firmware Gains (with corrected current scaling):**
+
+| Joint | Identified KP | Firmware KP | Ratio | Status |
+|-------|--------------|-------------|-------|--------|
+| hip_pitch | 14.3 | 12.8 | 1.12x | OK |
+| hip_roll | 316.0 | 328.0 | 0.96x | OK |
+| hip_yaw | 217.6 | 212.2 | 1.03x | OK |
+| knee | 59.2 | 64.2 | 0.92x | OK |
+| ankle_pitch | 15.0 | 19.3 | 0.78x | ~OK |
+| ankle_roll | 16.4 | 18.1 | 0.91x | OK |
+
+---
+
+## Reflected Inertia Calculations
+
+For physics-based gain tuning, reflected inertia at joint output:
+
+```
+J_reflected = J_rotor * gear_ratio^2
+```
+
+| Joint | J_rotor (kg·mm²) | Gear Ratio | J_reflected (kg·m²) |
+|-------|------------------|------------|---------------------|
+| hip_pitch | 104.395 | 25 | 0.0652 |
+| hip_roll | 10 | 100 | 0.100 |
+| hip_yaw | 3 | 107 | 0.0343 |
+| knee | 25.5 | 36 | 0.0330 |
+| ankle | 18.2 | 36 | 0.0236 |
+
+---
+
+## Important Notes
+
+1. **Current scaling mismatch**: The DBC parser currently uses fixed -30~+30A range for all motors. The `analyze_motor_dynamics.py` script rescales currents to the correct per-motor ranges.
+
+2. **Hip Yaw anomaly**: The empirically verified current range (+/-40A) differs significantly from the spec sheet (+/-10A). This requires further investigation with the motor manufacturer.
+
+3. **Harmonic vs Planetary drives**: Hip Roll (H17) and Hip Yaw (H14) use harmonic drives with very low backlash (10 arcsec). The planetary motors (P2) have higher backlash (10-15 arcmin).
+
+4. **Efficiency impact**: Motor efficiency varies significantly (31% for hip_roll, 73-74% for hip_pitch/knee). This affects the relationship between electrical current and mechanical torque.
+
+5. **Rotor inertia**: All motors now have rotor inertia values. Harmonic drives from ENCOS team (EC-5013=10, EC-3814=3 kg·mm²), ankle EC-4310=18.2 kg·mm².
+
+---
+
+## References
+
+- ENCOS Protocol V1.9 Manual
+- Motor spec sheets:
+ - EC-A6416-P2-25 (Hip Pitch)
+ - EC-A5013-H17-100 (Hip Roll)
+ - EC-A3814-H14-107 (Hip Yaw)
+ - EC-A4315-P2-36 (Knee)
+ - EC-A4310-P2-36 (Ankle)
+- Table 9-1: EC Series Force/Position Mixed Control Protocol Range (2025.01.15)
\ No newline at end of file
diff --git a/new_imitation_data_walking_1.25Hz_50Hz.csv b/new_imitation_data_walking_1.25Hz_50Hz.csv
new file mode 100644
index 000000000..071e62153
--- /dev/null
+++ b/new_imitation_data_walking_1.25Hz_50Hz.csv
@@ -0,0 +1,1001 @@
+left_hip_pitch_joint,right_hip_pitch_joint,left_hip_roll_joint,right_hip_roll_joint,left_hip_yaw_joint,right_hip_yaw_joint,left_knee_joint,right_knee_joint,left_ankle_pitch_joint,right_ankle_pitch_joint,left_ankle_roll_joint,right_ankle_roll_joint,rf_x,rf_y,rf_z,lf_x,lf_y,lf_z,rk_x,rk_y,rk_z,lk_x,lk_y,lk_z
+5.602507000000014198e-02,5.602506999999995463e-02,-5.157214446073606247e-03,-1.269866956932745594e-02,-2.722713500000002035e-02,-2.722713500000006892e-02,5.707226499999992070e-02,5.511812794373183166e-17,-3.078187931361825447e-02,1.946735226135323793e-02,-2.896235082470085057e-03,-5.917990493522699846e-03,1.000000000000000056e-01,-1.100000000000000006e-01,-6.800000000000000488e-01,-1.000000000000000056e-01,1.100000000000000006e-01,-6.800000000000000488e-01,1.073201893475363572e-01,-1.195885107720840584e-01,-3.847760103330669645e-01,-7.320189347536358582e-03,1.004114892279159427e-01,-3.552239896669330266e-01
+8.753369844508290809e-02,2.801253499999997176e-01,-9.957874353573004447e-03,1.125797115913970171e-02,-5.123196893686413761e-02,-1.361356750000001503e-01,1.827582554784296931e-01,-4.946236946381838556e-02,-1.878615193136183026e-01,-1.376122877386468657e-01,-7.795323038457310956e-03,1.751293386431226982e-03,9.876883405951378259e-02,-1.100000000000000006e-01,-6.909504125528161955e-01,-9.876883405951378259e-02,1.100000000000000006e-01,-6.690495874471839022e-01,1.038407099730085659e-01,-1.222161434652174195e-01,-3.920664707569723739e-01,-3.840709973008581135e-03,9.778385653478258166e-02,-3.479335292430276727e-01
+3.051326668233094591e-02,4.714795584776262372e-01,-1.221691509308706937e-02,3.049770740420318024e-02,-3.583999201970701487e-03,-2.450442150000001207e-01,2.624772222420786449e-01,-2.777514294638183667e-01,-2.777025112762258052e-01,-6.178866892043738401e-02,-1.186514301381990689e-02,3.591078237585633177e-03,9.510565162951535589e-02,-1.100000000000000006e-01,-7.016311896062463749e-01,-9.510565162951535589e-02,1.100000000000000006e-01,-6.583688103937537228e-01,9.903549363187347243e-02,-1.245429741631813997e-01,-3.988135814364233145e-01,9.645063681265192423e-04,9.545702583681860143e-02,-3.411864185635766766e-01
+-3.182469956706904246e-02,4.825571319194982833e-01,-1.631095271017334730e-02,3.601757114369692064e-02,4.760978460578088600e-02,-3.105462817464516578e-01,3.318310762431904704e-01,-3.294623627136656907e-01,-3.038980738253910796e-01,-1.403693783257806485e-02,-1.497537073616356934e-02,-1.394415733613900595e-02,8.910065241883680098e-02,-1.100000000000000006e-01,-7.117793349817683746e-01,-8.910065241883680098e-02,1.100000000000000006e-01,-6.482206650182317231e-01,9.302286069804854840e-02,-1.265117085718837631e-01,-4.048512061141152918e-01,6.977139301951450212e-03,9.348829142811622417e-02,-3.351487938858846993e-01
+-1.095440164439476227e-01,4.378327646745294732e-01,-2.363093911888411794e-02,2.442752559808833088e-02,1.102303298053239483e-01,-2.808766207310248175e-01,4.144670040180250536e-01,-2.956844342744054388e-01,-3.318606399744239988e-01,-1.181950594165438392e-02,-1.744834195797069151e-02,-1.581220011883726836e-02,8.090169943749475623e-02,-1.100000000000000006e-01,-7.211449676604732018e-01,-8.090169943749475623e-02,1.100000000000000006e-01,-6.388550323395268959e-01,8.595086214914918199e-02,-1.280738699163274097e-01,-4.100306784327559795e-01,1.404913785085080274e-02,9.192613008367259142e-02,-3.299693215672440116e-01
+-1.980252584674868921e-01,3.907770910612053394e-01,-3.546130828707411836e-02,1.395745068170946637e-02,1.798054270238229058e-01,-2.498681753094914582e-01,5.040400623752555598e-01,-2.652652872371172310e-01,-3.478084868835236154e-01,-5.665135707424489610e-03,-1.886179359351085674e-02,-1.743836433997831767e-02,7.071067811865475172e-02,-1.100000000000000006e-01,-7.294974746830583667e-01,-7.071067811865475172e-02,1.100000000000000006e-01,-6.305025253169417310e-01,7.799363406006687427e-02,-1.291909925996957975e-01,-4.142244625941773895e-01,2.200636593993310700e-02,9.080900740030418972e-02,-3.257755374058226017e-01
+-2.895442438271156882e-01,3.420655580669864082e-01,-5.160185761764786438e-02,4.841596800707925405e-03,2.492728236117782159e-01,-2.178979181573513224e-01,5.905772754060474306e-01,-2.382376076122401654e-01,-3.489874054302202211e-01,3.968751634423122940e-03,-1.860051705329296770e-02,-1.872202141505543982e-02,5.877852522924729289e-02,-1.100000000000000006e-01,-7.366311896062464060e-01,-5.877852522924729289e-02,1.100000000000000006e-01,-6.233688103937536917e-01,6.934710979488076243e-02,-1.298355693540068356e-01,-4.173292937139536085e-01,3.065289020511920842e-02,9.016443064599316548e-02,-3.226707062860464381e-01
+-3.793666186176564148e-01,2.922088815107674042e-01,-7.120691218717950521e-02,-2.782043068536598808e-03,3.145830763653503781e-01,-1.851921758786875261e-01,6.714022972977710113e-01,-2.142641032439309701e-01,-3.490610878393887728e-01,1.639386155130752656e-02,-1.703940650099482548e-02,-1.958198324617076852e-02,4.539904997395466379e-02,-1.100000000000000006e-01,-7.423704566931857984e-01,-4.539904997395466379e-02,1.100000000000000006e-01,-6.176295433068142993e-01,6.022419547716856975e-02,-1.299917285603417461e-01,-4.192687205455720156e-01,3.977580452283140111e-02,9.000827143965824118e-02,-3.207312794544279755e-01
+-4.622966700845650978e-01,2.418044428697327664e-01,-9.227356484349842625e-02,-8.810760645499160146e-03,3.717175436341771388e-01,-1.520718893937039184e-01,7.407176957583163635e-01,-1.930679167300501653e-01,-3.490656929899617622e-01,3.098756273245661941e-02,-1.457753667466899980e-02,-1.996643096951366755e-02,3.090169943749470835e-02,-1.100000000000000006e-01,-7.465739561406607994e-01,-3.090169943749470835e-02,1.100000000000000006e-01,-6.134260438593392983e-01,5.084952753464909436e-02,-1.296556250607778793e-01,-4.199949879638495975e-01,4.915047246535086262e-02,9.034437493922210793e-02,-3.200050120361503936e-01
+-5.348385334435549199e-01,1.915338529941716106e-01,-1.124415214035179716e-01,-1.318858593751950394e-02,4.184620240836821048e-01,-1.189504629203667341e-01,7.942577162456431195e-01,-1.744406738135728940e-01,-3.490659808118725671e-01,4.719277263854528698e-02,-1.166413895973206910e-02,-1.985221780112788117e-02,1.564344650402302653e-02,-1.100000000000000006e-01,-7.491381838416597549e-01,-1.564344650402302653e-02,1.100000000000000006e-01,-6.108618161583403428e-01,4.145394140480631456e-02,-1.288355348389380872e-01,-4.194902128546049713e-01,5.854605859519368405e-02,9.116446516106190001e-02,-3.205097871453950198e-01
+-5.953693400277120240e-01,1.421519329442039181e-01,-1.297194457234341902e-01,-1.591602986310407253e-02,4.543397535386456410e-01,-8.632316183585744818e-02,8.301158477188431695e-01,-1.582451059998832010e-01,-3.490659988007420167e-01,6.451373185727184156e-02,-8.703821904345057647e-03,-1.924197278445294659e-02,-6.049014748177262516e-17,-1.100000000000000006e-01,-7.500000000000000000e-01,6.049014748177262516e-17,1.100000000000000006e-01,-6.100000000000000977e-01,3.226878760031959281e-02,-1.275516512378074285e-01,-4.177668244562802724e-01,6.773121239968041274e-02,9.244834876219255870e-02,-3.222331755437197187e-01
+-6.433256773732739520e-01,9.447163462308569293e-02,-1.426945809658447806e-01,-1.705646484154004633e-02,4.797609735116997176e-01,-5.475217720651166797e-02,8.476869101482797930e-01,-1.444180509879905983e-01,-3.459210837708766029e-01,8.251230611392636194e-02,-5.985677071238547191e-03,-1.815963020595996735e-02,-1.564344650402316877e-02,-1.100000000000000006e-01,-7.491381838416596439e-01,1.564344650402316877e-02,1.100000000000000006e-01,-6.108618161583404538e-01,2.352023509163313902e-02,-1.258355877326111649e-01,-4.148672583108404810e-01,7.647976490836685959e-02,9.416441226738882231e-02,-3.251327416891595101e-01
+-6.773332858454161887e-01,4.934908311154045935e-02,-1.498575406396811804e-01,-1.673834903915330866e-02,4.945905135244951234e-01,-2.485129274913383535e-02,8.412338040720603871e-01,-1.329767390242877767e-01,-3.118859117682075688e-01,1.008067836223735664e-01,-3.185372749501552518e-03,-1.664499566594017377e-02,-3.090169943749484019e-02,-1.100000000000000006e-01,-7.465739561406607994e-01,3.090169943749484019e-02,1.100000000000000006e-01,-6.134260438593392983e-01,1.542370227629193818e-02,-1.237295995021354400e-01,-4.108629113598945004e-01,8.457629772370803267e-02,9.627040049786456111e-02,-3.291370886401054352e-01
+-6.991592328519465882e-01,7.673188385068724360e-03,-1.516888329904853006e-01,-1.515302578485590128e-02,5.007475828906751136e-01,2.725583435155475194e-03,8.177541401319972092e-01,-1.240306783858064754e-01,-2.714130818281367818e-01,1.190744289966147312e-01,-7.917428048742213183e-04,-1.474786567659235222e-02,-4.539904997395475400e-02,-1.100000000000000006e-01,-7.423704566931857984e-01,4.539904997395475400e-02,1.100000000000000006e-01,-6.176295433068142993e-01,8.178552663061597339e-03,-1.212855429659887990e-01,-4.058523839150404156e-01,9.182144733693839433e-02,9.871445703401120209e-02,-3.341476160849595756e-01
+-7.098632864869179881e-01,-2.963590179868032248e-02,-1.487310921673608288e-01,-1.254818146290644608e-02,4.994660274918542031e-01,2.728787781475124768e-02,7.809684223236670331e-01,-1.178014005988052421e-01,-2.278042664174830811e-01,1.370588412565316161e-01,1.026656369146151720e-03,-1.252216408640710078e-02,-5.877852522924738310e-02,-1.100000000000000006e-01,-7.366311896062462949e-01,5.877852522924738310e-02,1.100000000000000006e-01,-6.233688103937538028e-01,1.963185880692774887e-03,-1.185635989074497743e-01,-3.999590517909576426e-01,9.803681411930723066e-02,1.014364010925502269e-01,-3.400409482090423485e-01
+-7.103901144865863992e-01,-6.161585822202381157e-02,-1.416878746226356012e-01,-9.217067175084128414e-03,4.917885642703429538e-01,4.810022722830212261e-02,7.340487569097743359e-01,-1.146525911131218711e-01,-1.832300851382932805e-01,1.545832616036533491e-01,2.367965080447129514e-03,-1.002054977263937968e-02,-7.071067811865483499e-02,-1.100000000000000006e-01,-7.294974746830583667e-01,7.071067811865483499e-02,1.100000000000000006e-01,-6.305025253169417310e-01,-3.069355113012879610e-03,-1.156307906228539878e-01,-3.933280283833890389e-01,1.030693551130128643e-01,1.043692093771460133e-01,-3.466719716166109522e-01
+-7.018536152211377610e-01,-8.723604095433563910e-02,-1.314589164207803085e-01,-5.483080761084494457e-03,4.787833981384959081e-01,6.436012173376959300e-02,6.803817301685676222e-01,-1.151334353455742976e-01,-1.398613826580417108e-01,1.715712081079120432e-01,3.411449538235400685e-03,-7.290000459073281598e-03,-8.090169943749481174e-02,-1.100000000000000006e-01,-7.211449676604730907e-01,8.090169943749481174e-02,1.100000000000000006e-01,-6.388550323395270070e-01,-6.795152456744314728e-03,-1.125593335856008709e-01,-3.861225914957339134e-01,1.067951524567443272e-01,1.074406664143991302e-01,-3.538774085042660777e-01
+-6.854951399744154683e-01,-1.053548694613058723e-01,-1.190053900479061955e-01,-1.678016517595795707e-03,4.615221586756775296e-01,7.516005639098449764e-02,6.233272708742090273e-01,-1.200377521513185664e-01,-9.974724695718600875e-02,1.880758526936278374e-01,4.366040839594529169e-03,-4.369022085685891725e-03,-8.910065241883685649e-02,-1.100000000000000006e-01,-7.117793349817682635e-01,8.910065241883685649e-02,1.100000000000000006e-01,-6.482206650182318342e-01,-9.122464654686433805e-03,-1.094248572615290765e-01,-3.785201628976403998e-01,1.091224646546864324e-01,1.105751427384709246e-01,-3.614798371023595358e-01
+-6.625800878602539079e-01,-1.146620808150949494e-01,-1.052190971445144813e-01,1.890103040922490622e-03,4.410041489838750217e-01,7.943570573496931686e-02,5.658964679615169358e-01,-1.304791654639686771e-01,-6.461523056271081811e-02,2.043186048997174264e-01,5.419406970885471721e-03,-1.287435098138836002e-03,-9.510565162951541140e-02,-1.100000000000000006e-01,-7.016311896062462639e-01,9.510565162951541140e-02,1.100000000000000006e-01,-6.583688103937538338e-01,-9.993985556619532085e-03,-1.063045428604677267e-01,-3.707079396122074932e-01,1.099939855566195446e-01,1.136954571395322744e-01,-3.692920603877924424e-01
+-6.342675291553241390e-01,-1.136141537208966573e-01,-9.083235139046834383e-02,4.987495030836736586e-03,4.180607698341252121e-01,7.590858215729683056e-02,5.104581687392747424e-01,-1.479745070381374705e-01,-3.567820158592337199e-02,2.207334564717600978e-01,6.698175941162815873e-03,1.929766589103305277e-03,-9.876883405951381034e-02,-1.100000000000000006e-01,-6.909504125528160845e-01,9.876883405951381034e-02,1.100000000000000006e-01,-6.690495874471840132e-01,-9.388255425525966757e-03,-1.032752228787007787e-01,-3.628782845040052218e-01,1.093882554255259792e-01,1.167247771212992224e-01,-3.771217154959947693e-01
+-6.015091030975102671e-01,-1.003892154377639123e-01,-7.639017381996821010e-02,7.536003586177915554e-03,3.932898026092219168e-01,6.304935679354962963e-02,4.585879697260595855e-01,-1.745055716380496114e-01,-1.353823766722605897e-02,2.380022910156923965e-01,8.248665217435283831e-03,5.252174634723136108e-03,-1.000000000000000056e-01,-1.100000000000000006e-01,-6.799999999999999378e-01,1.000000000000000056e-01,1.100000000000000006e-01,-6.800000000000001599e-01,-7.320189347536323887e-03,-1.004114892279159149e-01,-3.552239896669329711e-01,1.073201893475363433e-01,1.195885107720840862e-01,-3.847760103330670201e-01
+-5.650199172974630368e-01,-7.293045398958258874e-02,-6.227748628619048099e-02,9.739606996816566400e-03,3.670525667964050776e-01,3.912876259703153975e-02,4.111058022735862294e-01,-2.124776593391359547e-01,1.772078937307007464e-03,2.570391413965393279e-01,1.003981562873104694e-02,8.624325639697246956e-03,-9.876883405951375483e-02,-1.100000000000000006e-01,-6.690495874471837912e-01,9.876883405951375483e-02,1.100000000000000006e-01,-6.909504125528163065e-01,-3.840709973008518685e-03,-9.778385653478254003e-02,-3.479335292430275617e-01,1.038407099730085104e-01,1.222161434652174611e-01,-3.920664707569724294e-01
+-5.253190287860454166e-01,-2.922878092779745973e-02,-4.877165008302346977e-02,1.225311428518251894e-02,3.395273341131277434e-01,2.497974193336654006e-03,3.682489008908342298e-01,-2.643954788338016559e-01,1.064761765343798412e-02,2.788295816935766336e-01,1.198181587144528035e-02,1.193481551187437588e-02,-9.510565162951530038e-02,-1.100000000000000006e-01,-6.583688103937536118e-01,9.510565162951530038e-02,1.100000000000000006e-01,-7.016311896062464859e-01,9.645063681265955702e-04,-9.545702583681857367e-02,-3.411864185635765656e-01,9.903549363187341692e-02,1.245429741631814274e-01,-3.988135814364233700e-01
+-4.828051591284734378e-01,3.191699582457466211e-02,-3.609134982022588894e-02,1.631742097927817853e-02,3.107876914953954239e-01,-4.768801171439085440e-02,3.298837045299223281e-01,-3.319682847512092083e-01,1.374068819078487318e-02,3.039753575647544670e-01,1.395079121639661822e-02,1.498012027513438357e-02,-8.910065241883668996e-02,-1.100000000000000006e-01,-6.482206650182316121e-01,8.910065241883668996e-02,1.100000000000000006e-01,-7.117793349817684856e-01,6.977139301951540418e-03,-9.348829142811619641e-02,-3.351487938858845883e-01,9.302286069804845126e-02,1.265117085718837908e-01,-4.048512061141154028e-01
+-4.378336598935969048e-01,1.095522403410317952e-01,-2.442778464480697617e-02,2.363195766968288758e-02,2.808774127907529561e-01,-1.102372783054975242e-01,2.956860640216290026e-01,-4.144794111096802292e-01,1.181813277407200817e-02,3.318676187596107940e-01,1.581207081670505180e-02,1.744878856003457754e-02,-8.090169943749458970e-02,-1.100000000000000006e-01,-6.388550323395267849e-01,8.090169943749458970e-02,1.100000000000000006e-01,-7.211449676604733128e-01,1.404913785085092764e-02,-9.192613008367257754e-02,-3.299693215672439006e-01,8.595086214914908485e-02,1.280738699163274097e-01,-4.100306784327560905e-01
+-3.907770986531016733e-01,1.980260120085579889e-01,-1.395745259037265047e-02,3.546144753777927261e-02,2.498681818960181711e-01,-1.798060562167369814e-01,2.652653009987172017e-01,-5.040411986082643514e-01,5.665123502613173510e-03,3.478089728115839052e-01,1.743836329118129969e-02,1.886183327923159417e-02,-7.071067811865458519e-02,-1.100000000000000006e-01,-6.305025253169416199e-01,7.071067811865458519e-02,1.100000000000000006e-01,-7.294974746830584778e-01,2.200636593993325271e-02,-9.080900740030417584e-02,-3.257755374058225462e-01,7.799363406006676325e-02,1.291909925996958253e-01,-4.142244625941774450e-01
+-3.420655581767043096e-01,2.895443046004826382e-01,-4.841596824616781203e-03,5.160187264023942399e-02,2.178979182516651847e-01,-2.492728734053705208e-01,2.382376078105574446e-01,-5.905773675887979746e-01,-3.968751817805749732e-03,3.489874358007239441e-01,1.872202140058424821e-02,1.860051970969217594e-02,-5.877852522924711942e-02,-1.100000000000000006e-01,-6.233688103937535807e-01,5.877852522924711942e-02,1.100000000000000006e-01,-7.366311896062465170e-01,3.065289020511936108e-02,-9.016443064599315160e-02,-3.226707062860463826e-01,6.934710979488065141e-02,1.298355693540068356e-01,-4.173292937139536085e-01
+-2.922088815129862405e-01,3.793666227249834488e-01,2.782043068119715266e-03,7.120691345996339738e-02,1.851921758805900320e-01,-3.145830796547740005e-01,2.142641032479473129e-01,-6.714023036868007610e-01,-1.639386155517306640e-02,3.490610897375452382e-01,1.958198324588381750e-02,1.703940665430503376e-02,-4.539904997395446257e-02,-1.100000000000000006e-01,-6.176295433068141882e-01,4.539904997395446257e-02,1.100000000000000006e-01,-7.423704566931859095e-01,3.977580452283156071e-02,-9.000827143965824118e-02,-3.207312794544279200e-01,6.022419547716845178e-02,1.299917285603417461e-01,-4.192687205455720156e-01
+-2.418044428697857240e-01,4.622966703091827556e-01,8.810760645490696430e-03,9.227356492626355433e-02,1.520718893937495209e-01,-3.717175438095703388e-01,1.930679167301475596e-01,-7.407176961220552913e-01,-3.098756273255560273e-02,3.490656931085965309e-01,1.996643096950706867e-02,1.457753668247959052e-02,-3.090169943749450712e-02,-1.100000000000000006e-01,-6.134260438593392983e-01,3.090169943749450712e-02,1.100000000000000006e-01,-7.465739561406607994e-01,4.915047246535102221e-02,-9.034437493922210793e-02,-3.200050120361503936e-01,5.084952753464899028e-02,1.296556250607778793e-01,-4.199949879638495975e-01
+-1.915338529941721657e-01,5.348385334533621860e-01,1.318858593751935995e-02,1.124415214076295716e-01,1.189504629203675529e-01,-4.184620240911391953e-01,1.744406738135752533e-01,-7.942577162624687714e-01,-4.719277263855028992e-02,3.490659808192872471e-01,1.985221780112821771e-02,1.166413896012097329e-02,-1.564344650402275591e-02,-1.100000000000000006e-01,-6.108618161583403428e-01,1.564344650402275591e-02,1.100000000000000006e-01,-7.491381838416597549e-01,5.854605859519383670e-02,-9.116446516106192777e-02,-3.205097871453950198e-01,4.145394140480616885e-02,1.288355348389380595e-01,-4.194902128546049713e-01
+-1.421519329442031687e-01,5.953693400280625214e-01,1.591602986310408641e-02,1.297194457235953113e-01,8.632316183585715674e-02,-4.543397535389044339e-01,1.582451059998832565e-01,-8.301158477194996443e-01,-6.451373185727488080e-02,3.490659988012054238e-01,1.924197278445378967e-02,8.703821904366268111e-03,3.369016658928397813e-16,-1.100000000000000006e-01,-6.100000000000000977e-01,-3.369016658928397813e-16,1.100000000000000006e-01,-7.500000000000000000e-01,6.773121239968055152e-02,-9.244834876219258646e-02,-3.222331755437197187e-01,3.226878760031939852e-02,1.275516512378074008e-01,-4.177668244562802169e-01
+-9.447163462308494353e-02,6.433256773732851652e-01,1.705646484154001857e-02,1.426945809658502484e-01,5.475217720651126552e-02,-4.797609735117076557e-01,1.444180509879904040e-01,-8.476869101483023305e-01,-8.251230611392669501e-02,3.459210837708924791e-01,1.815963020595990837e-02,5.985677071239758895e-03,1.564344650402342204e-02,-1.100000000000000006e-01,-6.108618161583404538e-01,-1.564344650402342204e-02,1.100000000000000006e-01,-7.491381838416596439e-01,7.647976490836699837e-02,-9.416441226738886394e-02,-3.251327416891595656e-01,2.352023509163301065e-02,1.258355877326111372e-01,-4.148672583108404255e-01
+-4.934908311153971688e-02,6.773332858454165217e-01,1.673834903915331559e-02,1.498575406396812915e-01,2.485129274913332881e-02,-4.945905135244952344e-01,1.329767390242875547e-01,-8.412338040720602761e-01,-1.008067836223738439e-01,3.118859117682070692e-01,1.664499566594015642e-02,3.185372749501416342e-03,3.090169943749506223e-02,-1.100000000000000006e-01,-6.134260438593394094e-01,-3.090169943749506223e-02,1.100000000000000006e-01,-7.465739561406606883e-01,8.457629772370817145e-02,-9.627040049786458886e-02,-3.291370886401054907e-01,1.542370227629179941e-02,1.237295995021354122e-01,-4.108629113598944449e-01
+-7.673188385067707812e-03,6.991592328519469213e-01,1.515302578485581454e-02,1.516888329904853283e-01,-2.725583435156156940e-03,-5.007475828906752247e-01,1.240306783858059342e-01,-8.177541401319967651e-01,-1.190744289966149533e-01,2.714130818281362267e-01,1.474786567659221344e-02,7.917428048741948637e-04,4.539904997395498298e-02,-1.100000000000000006e-01,-6.176295433068144103e-01,-4.539904997395498298e-02,1.100000000000000006e-01,-7.423704566931856874e-01,9.182144733693851923e-02,-9.871445703401124372e-02,-3.341476160849596311e-01,8.178552663061416927e-03,1.212855429659887574e-01,-4.058523839150403045e-01
+2.963590179868103025e-02,7.098632864869179881e-01,1.254818146290644088e-02,1.487310921673606623e-01,-2.728787781475172994e-02,-4.994660274918540366e-01,1.178014005988049784e-01,-7.809684223236663669e-01,-1.370588412565317826e-01,2.278042664174821930e-01,1.252216408640713548e-02,-1.026656369146222627e-03,5.877852522924758433e-02,-1.100000000000000006e-01,-6.233688103937539138e-01,-5.877852522924758433e-02,1.100000000000000006e-01,-7.366311896062461839e-01,9.803681411930731393e-02,-1.014364010925502685e-01,-3.400409482090424595e-01,1.963185880692656926e-03,1.185635989074497326e-01,-3.999590517909574761e-01
+6.161585822202452628e-02,7.103901144865861772e-01,9.217067175084088515e-03,1.416878746226353514e-01,-4.810022722830257363e-02,-4.917885642703426763e-01,1.146525911131217046e-01,-7.340487569097732257e-01,-1.545832616036535434e-01,1.832300851382928364e-01,1.002054977263934325e-02,-2.367965080447272195e-03,7.071067811865504316e-02,-1.100000000000000006e-01,-6.305025253169419530e-01,-7.071067811865504316e-02,1.100000000000000006e-01,-7.294974746830581447e-01,1.030693551130129615e-01,-1.043692093771460688e-01,-3.466719716166111187e-01,-3.069355113012990632e-03,1.156307906228539323e-01,-3.933280283833888724e-01
+8.723604095433604155e-02,7.018536152211375390e-01,5.483080761084398180e-03,1.314589164207800864e-01,-6.436012173376982892e-02,-4.787833981384956861e-01,1.151334353455743253e-01,-6.803817301685667340e-01,-1.715712081079123486e-01,1.398613826580408226e-01,7.290000459073186188e-03,-3.411449538235425405e-03,8.090169943749499215e-02,-1.100000000000000006e-01,-6.388550323395271180e-01,-8.090169943749499215e-02,1.100000000000000006e-01,-7.211449676604729797e-01,1.067951524567443827e-01,-1.074406664143991857e-01,-3.538774085042661888e-01,-6.795152456744370240e-03,1.125593335856008154e-01,-3.861225914957338023e-01
+1.053548694613061776e-01,6.854951399744149132e-01,1.678016517595699864e-03,1.190053900479058069e-01,-7.516005639098467805e-02,-4.615221586756769190e-01,1.200377521513185664e-01,-6.233272708742073620e-01,-1.880758526936279762e-01,9.974724695718492629e-02,4.369022085685802387e-03,-4.366040839594581210e-03,8.910065241883698139e-02,-1.100000000000000006e-01,-6.482206650182320562e-01,-8.910065241883698139e-02,1.100000000000000006e-01,-7.117793349817680415e-01,1.091224646546864741e-01,-1.105751427384709801e-01,-3.614798371023597023e-01,-9.122464654686468499e-03,1.094248572615290210e-01,-3.785201628976402333e-01
+1.146620808150949633e-01,6.625800878602534638e-01,-1.890103040922567167e-03,1.052190971445142592e-01,-7.943570573496930298e-02,-4.410041489838746331e-01,1.304791654639689824e-01,-5.658964679615160476e-01,-2.043186048997176762e-01,6.461523056271030463e-02,1.287435098138715872e-03,-5.419406970885515089e-03,9.510565162951549467e-02,-1.100000000000000006e-01,-6.583688103937540559e-01,-9.510565162951549467e-02,1.100000000000000006e-01,-7.016311896062460418e-01,1.099939855566195446e-01,-1.136954571395323160e-01,-3.692920603877926089e-01,-9.993985556619532085e-03,1.063045428604676851e-01,-3.707079396122073267e-01
+1.136141537208965185e-01,6.342675291553234729e-01,-4.987495030836829393e-03,9.083235139046799689e-02,-7.590858215729666403e-02,-4.180607698341247125e-01,1.479745070381378313e-01,-5.104581687392736322e-01,-2.207334564717602365e-01,3.567820158592304586e-02,-1.929766589103403505e-03,-6.698175941162876589e-03,9.876883405951385198e-02,-1.100000000000000006e-01,-6.690495874471841242e-01,-9.876883405951385198e-02,1.100000000000000006e-01,-6.909504125528159735e-01,1.093882554255259515e-01,-1.167247771212992780e-01,-3.771217154959948803e-01,-9.388255425525939002e-03,1.032752228787007232e-01,-3.628782845040050553e-01
+1.003892154377636348e-01,6.015091030975094899e-01,-7.536003586177937238e-03,7.639017381996787703e-02,-6.304935679354936595e-02,-3.932898026092213617e-01,1.745055716380500832e-01,-4.585879697260585863e-01,-2.380022910156926741e-01,1.353823766722573804e-02,-5.252174634723183813e-03,-8.248665217435339342e-03,1.000000000000000056e-01,-1.100000000000000006e-01,-6.800000000000003819e-01,-1.000000000000000056e-01,1.100000000000000006e-01,-6.799999999999997158e-01,1.073201893475362878e-01,-1.195885107720841417e-01,-3.847760103330671866e-01,-7.320189347536289193e-03,1.004114892279158594e-01,-3.552239896669328045e-01
+7.293045398958185321e-02,5.650199172974628148e-01,-9.739606996816555992e-03,6.227748628619044630e-02,-3.912876259703094300e-02,-3.670525667964049110e-01,2.124776593391369539e-01,-4.111058022735860629e-01,-2.570391413965397720e-01,-1.772078937307037388e-03,-8.624325639697274712e-03,-1.003981562873102439e-02,9.876883405951371320e-02,-1.100000000000000006e-01,-6.909504125528165286e-01,-9.876883405951371320e-02,1.100000000000000006e-01,-6.690495874471835691e-01,1.038407099730084548e-01,-1.222161434652174888e-01,-3.920664707569725405e-01,-3.840709973008435418e-03,9.778385653478251227e-02,-3.479335292430274507e-01
+2.922878092779616216e-02,5.253190287860446395e-01,-1.225311428518259700e-02,4.877165008302328242e-02,-2.497974193335484802e-03,-3.395273341131271883e-01,2.643954788338029882e-01,-3.682489008908335082e-01,-2.788295816935770222e-01,-1.064761765343807780e-02,-1.193481551187447302e-02,-1.198181587144525086e-02,9.510565162951520324e-02,-1.100000000000000006e-01,-7.016311896062467079e-01,-9.510565162951520324e-02,1.100000000000000006e-01,-6.583688103937533898e-01,9.903549363187330590e-02,-1.245429741631814829e-01,-3.988135814364235365e-01,9.645063681267274092e-04,9.545702583681851816e-02,-3.411864185635763991e-01
+-3.191699582457624418e-02,4.828051591284728827e-01,-1.631742097927832771e-02,3.609134982022569466e-02,4.768801171439197850e-02,-3.107876914953950909e-01,3.319682847512109292e-01,-3.298837045299219395e-01,-3.039753575647541339e-01,-1.374068819078476562e-02,-1.498012027513419796e-02,-1.395079121639667546e-02,8.910065241883656506e-02,-1.100000000000000006e-01,-7.117793349817685966e-01,-8.910065241883656506e-02,1.100000000000000006e-01,-6.482206650182315011e-01,9.302286069804834023e-02,-1.265117085718838463e-01,-4.048512061141155138e-01,6.977139301951741646e-03,9.348829142811615478e-02,-3.351487938858844218e-01
+-1.095522403410333773e-01,4.378336598935960722e-01,-2.363195766968305064e-02,2.442778464480680964e-02,1.102372783054987315e-01,-2.808774127907524010e-01,4.144794111096820610e-01,-2.956860640216284475e-01,-3.318676187596114602e-01,-1.181813277407194052e-02,-1.744878856003457407e-02,-1.581207081670502751e-02,8.090169943749445092e-02,-1.100000000000000006e-01,-7.211449676604734238e-01,-8.090169943749445092e-02,1.100000000000000006e-01,-6.388550323395266739e-01,8.595086214914895995e-02,-1.280738699163274374e-01,-4.100306784327561460e-01,1.404913785085108724e-02,9.192613008367254979e-02,-3.299693215672437896e-01
+-1.980260120085595155e-01,3.907770986531011181e-01,-3.546144753777952241e-02,1.395745259037253425e-02,1.798060562167381471e-01,-2.498681818960178935e-01,5.040411986082657947e-01,-2.652653009987172017e-01,-3.478089728115840717e-01,-5.665123502612390283e-03,-1.886183327923155253e-02,-1.743836329118136907e-02,7.071067811865439090e-02,-1.100000000000000006e-01,-7.294974746830585888e-01,-7.071067811865439090e-02,1.100000000000000006e-01,-6.305025253169415089e-01,7.799363406006662447e-02,-1.291909925996958253e-01,-4.142244625941775005e-01,2.200636593993337761e-02,9.080900740030416196e-02,-3.257755374058224906e-01
+-2.895443046004846366e-01,3.420655581767035880e-01,-5.160187264023975706e-02,4.841596824616658037e-03,2.492728734053717976e-01,-2.178979182516646851e-01,5.905773675887997509e-01,-2.382376078105572226e-01,-3.489874358007239441e-01,3.968751817806016879e-03,-1.860051970969219329e-02,-1.872202140058423087e-02,5.877852522924690432e-02,-1.100000000000000006e-01,-7.366311896062466280e-01,-5.877852522924690432e-02,1.100000000000000006e-01,-6.233688103937534697e-01,6.934710979488049876e-02,-1.298355693540068356e-01,-4.173292937139536640e-01,3.065289020511954843e-02,9.016443064599315160e-02,-3.226707062860463271e-01
+-3.793666227249855027e-01,2.922088815129855743e-01,-7.120691345996382760e-02,-2.782043068119822819e-03,3.145830796547754438e-01,-1.851921758805894214e-01,6.714023036868026484e-01,-2.142641032479471463e-01,-3.490610897375452382e-01,1.639386155517340293e-02,-1.703940665430501988e-02,-1.958198324588377240e-02,4.539904997395423358e-02,-1.100000000000000006e-01,-7.423704566931859095e-01,-4.539904997395423358e-02,1.100000000000000006e-01,-6.176295433068141882e-01,6.022419547716829219e-02,-1.299917285603417461e-01,-4.192687205455720711e-01,3.977580452283181051e-02,9.000827143965824118e-02,-3.207312794544279200e-01
+-4.622966703091846430e-01,2.418044428697844195e-01,-9.227356492626397066e-02,-8.810760645490784901e-03,3.717175438095716156e-01,-1.520718893937487715e-01,7.407176961220566236e-01,-1.930679167301468935e-01,-3.490656931085965309e-01,3.098756273255595661e-02,-1.457753668247953847e-02,-1.996643096950697499e-02,3.090169943749418099e-02,-1.100000000000000006e-01,-7.465739561406609104e-01,-3.090169943749418099e-02,1.100000000000000006e-01,-6.134260438593391873e-01,5.084952753464877517e-02,-1.296556250607778793e-01,-4.199949879638495975e-01,4.915047246535132752e-02,9.034437493922212181e-02,-3.200050120361503936e-01
+-5.348385334533635183e-01,1.915338529941713608e-01,-1.124415214076299740e-01,-1.318858593751941373e-02,4.184620240911399169e-01,-1.189504629203668451e-01,7.942577162624701037e-01,-1.744406738135748647e-01,-3.490659808192872471e-01,4.719277263854849969e-02,-1.166413896012097329e-02,-1.985221780112766954e-02,1.564344650402250264e-02,-1.100000000000000006e-01,-7.491381838416597549e-01,-1.564344650402250264e-02,1.100000000000000006e-01,-6.108618161583403428e-01,4.145394140480601619e-02,-1.288355348389380595e-01,-4.194902128546049713e-01,5.854605859519403793e-02,9.116446516106194164e-02,-3.205097871453950198e-01
+-5.953693400280631876e-01,1.421519329442025581e-01,-1.297194457235955056e-01,-1.591602986310409334e-02,4.543397535389048225e-01,-8.632316183585650449e-02,8.301158477195001995e-01,-1.582451059998826459e-01,-3.490659988012054793e-01,6.451373185727206361e-02,-8.703821904366287193e-03,-1.924197278445290843e-02,-5.022908818413913326e-16,-1.100000000000000006e-01,-7.500000000000000000e-01,5.022908818413913326e-16,1.100000000000000006e-01,-6.100000000000000977e-01,3.226878760031930138e-02,-1.275516512378074008e-01,-4.177668244562802169e-01,6.773121239968069029e-02,9.244834876219258646e-02,-3.222331755437197742e-01
+-6.433256773732847211e-01,9.447163462308498516e-02,-1.426945809658501096e-01,-1.705646484154001857e-02,4.797609735117074892e-01,-5.475217720651131409e-02,8.476869101483021085e-01,-1.444180509879902097e-01,-3.459210837708926456e-01,8.251230611392644521e-02,-5.985677071239882928e-03,-1.815963020595992919e-02,-1.564344650402332143e-02,-1.100000000000000006e-01,-7.491381838416596439e-01,1.564344650402332143e-02,1.100000000000000006e-01,-6.108618161583404538e-01,2.352023509163301065e-02,-1.258355877326111372e-01,-4.148672583108404255e-01,7.647976490836698449e-02,9.416441226738885006e-02,-3.251327416891595656e-01
+-6.773332858454160776e-01,4.934908311154126426e-02,-1.498575406396812359e-01,-1.673834903915327396e-02,4.945905135244952344e-01,-2.485129274913438352e-02,8.412338040720612753e-01,-1.329767390242878877e-01,-3.118859117682084015e-01,1.008067836223729002e-01,-3.185372749501663540e-03,-1.664499566594012520e-02,-3.090169943749454529e-02,-1.100000000000000006e-01,-7.465739561406607994e-01,3.090169943749454529e-02,1.100000000000000006e-01,-6.134260438593392983e-01,1.542370227629206308e-02,-1.237295995021354816e-01,-4.108629113598946114e-01,8.457629772370793553e-02,9.627040049786451947e-02,-3.291370886401053797e-01
+-6.991592328519459221e-01,7.673188385069985504e-03,-1.516888329904853283e-01,-1.515302578485588914e-02,5.007475828906751136e-01,2.725583435154652935e-03,8.177541401319980974e-01,-1.240306783858066142e-01,-2.714130818281383362e-01,1.190744289966142039e-01,-7.917428048742612169e-04,-1.474786567659226548e-02,-4.539904997395425440e-02,-1.100000000000000006e-01,-7.423704566931859095e-01,4.539904997395425440e-02,1.100000000000000006e-01,-6.176295433068141882e-01,8.178552663061805506e-03,-1.212855429659888962e-01,-4.058523839150405821e-01,9.182144733693820005e-02,9.871445703401110494e-02,-3.341476160849594090e-01
+-7.098632864869175441e-01,-2.963590179867830326e-02,-1.487310921673611619e-01,-1.254818146290670976e-02,4.994660274918545362e-01,2.728787781474991195e-02,7.809684223236696976e-01,-1.178014005988052282e-01,-2.278042664174857457e-01,1.370588412565302006e-01,1.026656369146077561e-03,-1.252216408640736620e-02,-5.877852522924657125e-02,-1.100000000000000006e-01,-7.366311896062467390e-01,5.877852522924657125e-02,1.100000000000000006e-01,-6.233688103937533587e-01,1.963185880693101015e-03,-1.185635989074499547e-01,-3.999590517909579757e-01,9.803681411930689760e-02,1.014364010925500464e-01,-3.400409482090420155e-01
+-7.103901144865863992e-01,-6.161585822202159113e-02,-1.416878746226362396e-01,-9.217067175084411174e-03,4.917885642703436200e-01,4.810022722830067932e-02,7.340487569097779996e-01,-1.146525911131218156e-01,-1.832300851382965556e-01,1.545832616036517670e-01,2.367965080447127346e-03,-1.002054977263958091e-02,-7.071067811865391906e-02,-1.100000000000000006e-01,-7.294974746830589218e-01,7.071067811865391906e-02,1.100000000000000006e-01,-6.305025253169411759e-01,-3.069355113012532665e-03,-1.156307906228542376e-01,-3.933280283833895385e-01,1.030693551130125452e-01,1.043692093771457635e-01,-3.466719716166104526e-01
+-7.018536152211387602e-01,-8.723604095433357131e-02,-1.314589164207813632e-01,-5.483080761084902985e-03,4.787833981384972959e-01,6.436012173376857992e-02,6.803817301685729513e-01,-1.151334353455739229e-01,-1.398613826580457908e-01,1.715712081079108775e-01,3.411449538235374664e-03,-7.290000459072902561e-03,-8.090169943749389581e-02,-1.100000000000000006e-01,-7.211449676604739789e-01,8.090169943749389581e-02,1.100000000000000006e-01,-6.388550323395261188e-01,-6.795152456744030234e-03,-1.125593335856011901e-01,-3.861225914957346350e-01,1.067951524567440358e-01,1.074406664143988110e-01,-3.538774085042653561e-01
+-6.854951399744176888e-01,-1.053548694613041098e-01,-1.190053900479076943e-01,-1.678016517596243266e-03,4.615221586756797501e-01,7.516005639098354008e-02,6.233272708742156887e-01,-1.200377521513175116e-01,-9.974724695719047740e-02,1.880758526936256447e-01,4.366040839594431157e-03,-4.369022085686248211e-03,-8.910065241883592668e-02,-1.100000000000000006e-01,-7.117793349817694848e-01,8.910065241883592668e-02,1.100000000000000006e-01,-6.482206650182306129e-01,-9.122464654686232577e-03,-1.094248572615294790e-01,-3.785201628976413990e-01,1.091224646546862381e-01,1.105751427384705221e-01,-3.614798371023585921e-01
+-6.625800878602576827e-01,-1.146620808150941584e-01,-1.052190971445165629e-01,1.890103040921932692e-03,4.410041489838781859e-01,7.943570573496915033e-02,5.658964679615252624e-01,-1.304791654639668175e-01,-6.461523056271577248e-02,2.043186048997150950e-01,5.419406970885391056e-03,-1.287435098139310882e-03,-9.510565162951468976e-02,-1.100000000000000006e-01,-7.016311896062478182e-01,9.510565162951468976e-02,1.100000000000000006e-01,-6.583688103937522795e-01,-9.993985556619511268e-03,-1.063045428604681986e-01,-3.707079396122086590e-01,1.099939855566195168e-01,1.136954571395318025e-01,-3.692920603877913321e-01
+-6.342675291553294681e-01,-1.136141537208977675e-01,-9.083235139047086959e-02,4.987495030836240455e-03,4.180607698341293754e-01,7.590858215729816283e-02,5.104581687392841793e-01,-1.479745070381338345e-01,-3.567820158592807656e-02,2.207334564717572112e-01,6.698175941162554797e-03,1.929766589102734553e-03,-9.876883405951336625e-02,-1.100000000000000006e-01,-6.909504125528179719e-01,9.876883405951336625e-02,1.100000000000000006e-01,-6.690495874471821258e-01,-9.388255425526195741e-03,-1.032752228787013060e-01,-3.628782845040065541e-01,1.093882554255262013e-01,1.167247771212986951e-01,-3.771217154959934370e-01
+-6.015091030975170394e-01,-1.003892154377676316e-01,-7.639017381997097178e-02,7.536003586177513966e-03,3.932898026092268018e-01,6.304935679355301581e-02,4.585879697260693555e-01,-1.745055716380437549e-01,-1.353823766722974352e-02,2.380022910156891769e-01,8.248665217434964642e-03,5.252174634722533292e-03,-1.000000000000000056e-01,-1.100000000000000006e-01,-6.800000000000020473e-01,1.000000000000000056e-01,1.100000000000000006e-01,-6.799999999999980504e-01,-7.320189347536851243e-03,-1.004114892279164423e-01,-3.552239896669343588e-01,1.073201893475368568e-01,1.195885107720835588e-01,-3.847760103330656323e-01
+-5.650199172974711415e-01,-7.293045398958994396e-02,-6.227748628619344390e-02,9.739606996816111903e-03,3.670525667964107397e-01,3.912876259703791659e-02,4.111058022735957773e-01,-2.124776593391266288e-01,1.772078937304499054e-03,2.570391413965343874e-01,1.003981562873062887e-02,8.624325639696266838e-03,-9.876883405951426831e-02,-1.100000000000000006e-01,-6.690495874471860116e-01,9.876883405951426831e-02,1.100000000000000006e-01,-6.909504125528140861e-01,-3.840709973009386047e-03,-9.778385653478308126e-02,-3.479335292430290050e-01,1.038407099730093985e-01,1.222161434652169199e-01,-3.920664707569709861e-01
+-5.253190287860551866e-01,-2.922878092780955769e-02,-4.877165008302666166e-02,1.225311428518180597e-02,3.395273341131346267e-01,2.497974193346715402e-03,3.682489008908438888e-01,-2.643954788337878892e-01,1.064761765343659981e-02,2.788295816935719706e-01,1.198181587144482411e-02,1.193481551187385893e-02,-9.510565162951646612e-02,-1.100000000000000006e-01,-6.583688103937561653e-01,9.510565162951646612e-02,1.100000000000000006e-01,-7.016311896062439324e-01,9.645063681253118748e-04,-9.545702583681908715e-02,-3.411864185635781199e-01,9.903549363187469368e-02,1.245429741631809140e-01,-3.988135814364218712e-01
+-4.828051591284849287e-01,3.191699582455723855e-02,-3.609134982022911553e-02,1.631742097927686014e-02,3.107876914954030845e-01,-4.768801171437657416e-02,3.298837045299318205e-01,-3.319682847511906676e-01,1.374068819078472052e-02,3.039753575647480277e-01,1.395079121639606137e-02,1.498012027513368448e-02,-8.910065241883853571e-02,-1.100000000000000006e-01,-6.482206650182341656e-01,8.910065241883853571e-02,1.100000000000000006e-01,-7.117793349817659321e-01,6.977139301949882022e-03,-9.348829142811665438e-02,-3.351487938858860316e-01,9.302286069805013047e-02,1.265117085718833467e-01,-4.048512061141139595e-01
+-4.378336598936094504e-01,1.095522403410087026e-01,-2.442778464480995296e-02,2.363195766968030631e-02,2.808774127907612828e-01,-1.102372783054791222e-01,2.956860640216377178e-01,-4.144794111096563594e-01,1.181813277407321033e-02,3.318676187596025229e-01,1.581207081670462158e-02,1.744878856003393916e-02,-8.090169943749717096e-02,-1.100000000000000006e-01,-6.388550323395292274e-01,8.090169943749717096e-02,1.100000000000000006e-01,-7.211449676604708703e-01,1.404913785084886679e-02,-9.192613008367295224e-02,-3.299693215672452329e-01,8.595086214915115264e-02,1.280738699163270489e-01,-4.100306784327547582e-01
+-3.907770986531162727e-01,1.980260120085310105e-01,-1.395745259037556481e-02,3.546144753777509540e-02,2.498681818960277745e-01,-1.798060562167161369e-01,2.652653009987259725e-01,-5.040411986082383722e-01,5.665123502615655032e-03,3.478089728115829060e-01,1.743836329118097356e-02,1.886183327923145539e-02,-7.071067811865798525e-02,-1.100000000000000006e-01,-6.305025253169439514e-01,7.071067811865798525e-02,1.100000000000000006e-01,-7.294974746830561463e-01,2.200636593993074083e-02,-9.080900740030445339e-02,-3.257755374058236564e-01,7.799363406006927513e-02,1.291909925996955477e-01,-4.142244625941763347e-01
+-3.420655581767201858e-01,2.895443046004537169e-01,-4.841596824619466555e-03,5.160187264023382431e-02,2.178979182516756485e-01,-2.492728734053492878e-01,2.382376078105655215e-01,-5.905773675887713292e-01,-3.968751817802099874e-03,3.489874358007238886e-01,1.872202140058393943e-02,1.860051970969261656e-02,-5.877852522925122725e-02,-1.100000000000000006e-01,-6.233688103937556901e-01,5.877852522925122725e-02,1.100000000000000006e-01,-7.366311896062444076e-01,3.065289020511651960e-02,-9.016443064599329038e-02,-3.226707062860471598e-01,6.934710979488349636e-02,1.298355693540066969e-01,-4.173292937139528314e-01
+-2.922088815130038930e-01,3.793666227249538614e-01,2.782043068117297062e-03,7.120691345995634747e-02,1.851921758806016616e-01,-3.145830796547526287e-01,2.142641032479552510e-01,-6.714023036867757810e-01,-1.639386155516828203e-02,3.490610897375452382e-01,1.958198324588357117e-02,1.703940665430567214e-02,-4.539904997395938224e-02,-1.100000000000000006e-01,-6.176295433068159646e-01,4.539904997395938224e-02,1.100000000000000006e-01,-7.423704566931841331e-01,3.977580452282834800e-02,-9.000827143965821342e-02,-3.207312794544284196e-01,6.022419547717167143e-02,1.299917285603417738e-01,-4.192687205455715715e-01
+-2.418044428698038484e-01,4.622966703091544449e-01,8.810760645488767417e-03,9.227356492625601869e-02,1.520718893937613170e-01,-3.717175438095515760e-01,1.930679167301541654e-01,-7.407176961220334199e-01,-3.098756273254842444e-02,3.490656931085965309e-01,1.996643096950664539e-02,1.457753668248059666e-02,-3.090169943750002007e-02,-1.100000000000000006e-01,-6.134260438593405196e-01,3.090169943750002007e-02,1.100000000000000006e-01,-7.465739561406595781e-01,4.915047246534760134e-02,-9.034437493922188589e-02,-3.200050120361503936e-01,5.084952753465241115e-02,1.296556250607781013e-01,-4.199949879638495975e-01
+-1.915338529941915113e-01,5.348385334533364288e-01,1.318858593751798605e-02,1.124415214076223829e-01,1.189504629203800845e-01,-4.184620240911235967e-01,1.744406738135817481e-01,-7.942577162624518960e-01,-4.719277263854158855e-02,3.490659808192872471e-01,1.985221780112778056e-02,1.166413896012226045e-02,-1.564344650402883091e-02,-1.100000000000000006e-01,-6.108618161583410089e-01,1.564344650402883091e-02,1.100000000000000006e-01,-7.491381838416590888e-01,5.854605859519024236e-02,-9.116446516106151143e-02,-3.205097871453945757e-01,4.145394140480977707e-02,1.288355348389384758e-01,-4.194902128546054154e-01
+-1.421519329442235136e-01,5.953693400280399839e-01,1.591602986310332313e-02,1.297194457235890108e-01,8.632316183587065983e-02,-4.543397535388919439e-01,1.582451059998894460e-01,-8.301158477194888752e-01,-6.451373185726730353e-02,3.490659988012054238e-01,1.924197278445424764e-02,8.703821904367520582e-03,-6.260111575871034559e-15,-1.100000000000000006e-01,-6.100000000000000977e-01,6.260111575871034559e-15,1.100000000000000006e-01,-7.500000000000000000e-01,6.773121239967683227e-02,-9.244834876219194808e-02,-3.222331755437187750e-01,3.226878760032318716e-02,1.275516512378080392e-01,-4.177668244562812161e-01
+-9.447163462310503856e-02,6.433256773732678457e-01,1.705646484153986939e-02,1.426945809658461128e-01,5.475217720652465064e-02,-4.797609735116993290e-01,1.444180509879956498e-01,-8.476869101483007762e-01,-8.251230611391859038e-02,3.459210837709046360e-01,1.815963020596051553e-02,5.985677071240950650e-03,1.564344650401663928e-02,-1.100000000000000006e-01,-6.108618161583396766e-01,-1.564344650401663928e-02,1.100000000000000006e-01,-7.491381838416604211e-01,7.647976490836336239e-02,-9.416441226738801740e-02,-3.251327416891580668e-01,2.352023509163665704e-02,1.258355877326119698e-01,-4.148672583108419243e-01
+-4.934908311156002703e-02,6.773332858454039762e-01,1.673834903915368336e-02,1.498575406396794318e-01,2.485129274914682496e-02,-4.945905135244906825e-01,1.329767390242922176e-01,-8.412338040720682697e-01,-1.008067836223634217e-01,3.118859117682249438e-01,1.664499566593993091e-02,3.185372749502723890e-03,3.090169943748811293e-02,-1.100000000000000006e-01,-6.134260438593377440e-01,-3.090169943748811293e-02,1.100000000000000006e-01,-7.465739561406623537e-01,8.457629772370461874e-02,-9.627040049786353415e-02,-3.291370886401034368e-01,1.542370227629537988e-02,1.237295995021364670e-01,-4.108629113598965543e-01
+-7.673188385087046509e-03,6.991592328519391497e-01,1.515302578485679466e-02,1.516888329904855781e-01,-2.725583435143097075e-03,-5.007475828906742255e-01,1.240306783858097645e-01,-8.177541401320115311e-01,-1.190744289966060160e-01,2.714130818281562663e-01,1.474786567659315366e-02,7.917428048751622973e-04,4.539904997394823144e-02,-1.100000000000000006e-01,-6.176295433068119678e-01,-4.539904997394823144e-02,1.100000000000000006e-01,-7.423704566931881299e-01,9.182144733693529959e-02,-9.871445703400999472e-02,-3.341476160849570221e-01,8.178552663064712902e-03,1.212855429659900064e-01,-4.058523839150429691e-01
+2.963590179866361363e-02,7.098632864869155457e-01,1.254818146290801947e-02,1.487310921673633546e-01,-2.728787781474028423e-02,-4.994660274918566456e-01,1.178014005988074486e-01,-7.809684223236877942e-01,-1.370588412565231506e-01,2.278042664175044807e-01,1.252216408640839315e-02,-1.026656369145422919e-03,5.877852522924124218e-02,-1.100000000000000006e-01,-6.233688103937506941e-01,-5.877852522924124218e-02,1.100000000000000006e-01,-7.366311896062494036e-01,9.803681411930453837e-02,-1.014364010925488530e-01,-3.400409482090393509e-01,1.963185880695474117e-03,1.185635989074511482e-01,-3.999590517909606402e-01
+6.161585822200917051e-02,7.103901144865885087e-01,9.217067175085904771e-03,1.416878746226401253e-01,-4.810022722829268571e-02,-4.917885642703484494e-01,1.146525911131223568e-01,-7.340487569098003151e-01,-1.545832616036442175e-01,1.832300851383162343e-01,1.002054977264062174e-02,-2.367965080446603025e-03,7.071067811864913122e-02,-1.100000000000000006e-01,-6.305025253169377342e-01,-7.071067811864913122e-02,1.100000000000000006e-01,-7.294974746830623635e-01,1.030693551130106578e-01,-1.043692093771444590e-01,-3.466719716166074550e-01,-3.069355113010645286e-03,1.156307906228555421e-01,-3.933280283833925361e-01
+8.723604095432400951e-02,7.018536152211444223e-01,5.483080761086547503e-03,1.314589164207864147e-01,-6.436012173376237655e-02,-4.787833981385040127e-01,1.151334353455727710e-01,-6.803817301685969321e-01,-1.715712081079029949e-01,1.398613826580638042e-01,7.290000459074804685e-03,-3.411449538234939249e-03,8.090169943748992676e-02,-1.100000000000000006e-01,-6.388550323395222330e-01,-8.090169943748992676e-02,1.100000000000000006e-01,-7.211449676604778647e-01,1.067951524567427313e-01,-1.074406664143974649e-01,-3.538774085042621365e-01,-6.795152456742718783e-03,1.125593335856025362e-01,-3.861225914957378547e-01
+1.053548694612982811e-01,6.854951399744261265e-01,1.678016517597847885e-03,1.190053900479133286e-01,-7.516005639098032043e-02,-4.615221586756878547e-01,1.200377521513143753e-01,-6.233272708742401136e-01,-1.880758526936187891e-01,9.974724695720654788e-02,4.369022085687550121e-03,-4.366040839594068600e-03,8.910065241883294296e-02,-1.100000000000000006e-01,-6.482206650182265051e-01,-8.910065241883294296e-02,1.100000000000000006e-01,-7.117793349817735926e-01,1.091224646546855581e-01,-1.105751427384692037e-01,-3.614798371023553725e-01,-9.122464654685559504e-03,1.094248572615307974e-01,-3.785201628976446186e-01
+1.146620808150923126e-01,6.625800878602685628e-01,-1.890103040920541010e-03,1.052190971445225720e-01,-7.943570573496891440e-02,-4.410041489838875117e-01,1.304791654639608500e-01,-5.658964679615493543e-01,-2.043186048997079896e-01,6.461523056272922005e-02,1.287435098140614744e-03,-5.419406970884879313e-03,9.510565162951260809e-02,-1.100000000000000006e-01,-6.583688103937477276e-01,-9.510565162951260809e-02,1.100000000000000006e-01,-7.016311896062523701e-01,1.099939855566194613e-01,-1.136954571395304842e-01,-3.692920603877879460e-01,-9.993985556619448818e-03,1.063045428604695170e-01,-3.707079396122120452e-01
+1.136141537209006541e-01,6.342675291553423467e-01,-4.987495030835020944e-03,9.083235139047694806e-02,-7.590858215730149350e-02,-4.180607698341393119e-01,1.479745070381247030e-01,-5.104581687393067169e-01,-2.207334564717498282e-01,3.567820158593869306e-02,-1.929766589101245509e-03,-6.698175941161954583e-03,9.876883405951233930e-02,-1.100000000000000006e-01,-6.690495874471775739e-01,-9.876883405951233930e-02,1.100000000000000006e-01,-6.909504125528225238e-01,1.093882554255267703e-01,-1.167247771212974600e-01,-3.771217154959901618e-01,-9.388255425526764730e-03,1.032752228787025411e-01,-3.628782845040098293e-01
+1.003892154377763191e-01,6.015091030975321384e-01,-7.536003586176390732e-03,7.639017381997706413e-02,-6.304935679356102329e-02,-3.932898026092379040e-01,1.745055716380299049e-01,-4.585879697260906718e-01,-2.380022910156822380e-01,1.353823766723776835e-02,-5.252174634721214035e-03,-8.248665217434315855e-03,1.000000000000000056e-01,-1.100000000000000006e-01,-6.799999999999932765e-01,-1.000000000000000056e-01,1.100000000000000006e-01,-6.800000000000068212e-01,1.073201893475380642e-01,-1.195885107720823654e-01,-3.847760103330624126e-01,-7.320189347538051672e-03,1.004114892279176358e-01,-3.552239896669375785e-01
+7.293045398960505687e-02,5.650199172974877948e-01,-9.739606996815088416e-03,6.227748628619958482e-02,-3.912876259705071885e-02,-3.670525667964225636e-01,2.124776593391075608e-01,-4.111058022736156503e-01,-2.570391413965264493e-01,-1.772078937299221158e-03,-8.624325639695062939e-03,-1.003981562872977018e-02,9.876883405951532302e-02,-1.100000000000000006e-01,-6.909504125528093121e-01,-9.876883405951532302e-02,1.100000000000000006e-01,-6.690495874471907856e-01,1.038407099730111749e-01,-1.222161434652158513e-01,-3.920664707569679330e-01,-3.840709973011176281e-03,9.778385653478414985e-02,-3.479335292430320581e-01
+2.922878092783194603e-02,5.253190287860721730e-01,-1.225311428518051707e-02,4.877165008303208094e-02,-2.497974193365190207e-03,-3.395273341131461731e-01,2.643954788337621875e-01,-3.682489008908605976e-01,-2.788295816935609239e-01,-1.064761765343423018e-02,-1.193481551187225605e-02,-1.198181587144398971e-02,9.510565162951850615e-02,-1.100000000000000006e-01,-7.016311896062396025e-01,-9.510565162951850615e-02,1.100000000000000006e-01,-6.583688103937604952e-01,9.903549363187696963e-02,-1.245429741631800119e-01,-3.988135814364192067e-01,9.645063681230289787e-04,9.545702583681998921e-02,-3.411864185635807845e-01
+-3.191699582452676986e-02,4.828051591285035804e-01,-1.631742097927451826e-02,3.609134982023427113e-02,4.768801171435196884e-02,-3.107876914954156855e-01,3.319682847511575274e-01,-3.298837045299472526e-01,-3.039753575647363149e-01,-1.374068819078455919e-02,-1.498012027513247538e-02,-1.395079121639530156e-02,8.910065241884161658e-02,-1.100000000000000006e-01,-7.117793349817617132e-01,-8.910065241884161658e-02,1.100000000000000006e-01,-6.482206650182383845e-01,9.302286069805296154e-02,-1.265117085718825696e-01,-4.048512061141115170e-01,6.977139301946967687e-03,9.348829142811741766e-02,-3.351487938858885296e-01
+-1.095522403409726897e-01,4.378336598936292123e-01,-2.363195766967624359e-02,2.442778464481466794e-02,1.102372783054503674e-01,-2.808774127907742169e-01,4.144794111096185008e-01,-2.956860640216514291e-01,-3.318676187595909766e-01,-1.181813277407502485e-02,-1.744878856003312731e-02,-1.581207081670387565e-02,8.090169943750114001e-02,-1.100000000000000006e-01,-7.211449676604669845e-01,-8.090169943750114001e-02,1.100000000000000006e-01,-6.388550323395331132e-01,8.595086214915438616e-02,-1.280738699163264660e-01,-4.100306784327527598e-01,1.404913785084569572e-02,9.192613008367352123e-02,-3.299693215672471758e-01
+-1.980260120084920139e-01,3.907770986531367008e-01,-3.546144753776911407e-02,1.395745259037980621e-02,1.798060562166859666e-01,-2.498681818960411805e-01,5.040411986082005136e-01,-2.652653009987379629e-01,-3.478089728115813517e-01,-5.665123502618842587e-03,-1.886183327923120559e-02,-1.743836329118026579e-02,7.071067811866275921e-02,-1.100000000000000006e-01,-7.294974746830528156e-01,-7.071067811866275921e-02,1.100000000000000006e-01,-6.305025253169472821e-01,7.799363406007285560e-02,-1.291909925996951591e-01,-4.142244625941747804e-01,2.200636593992714302e-02,9.080900740030482809e-02,-3.257755374058252107e-01
+-2.895443046004144705e-01,3.420655581767414466e-01,-5.160187264022592091e-02,4.841596824623070443e-03,2.492728734053199224e-01,-2.178979182516895818e-01,5.905773675887351359e-01,-2.382376078105765960e-01,-3.489874358007238331e-01,3.968751817797350201e-03,-1.860051970969292187e-02,-1.872202140058348147e-02,5.877852522925669509e-02,-1.100000000000000006e-01,-7.366311896062416320e-01,-5.877852522925669509e-02,1.100000000000000006e-01,-6.233688103937584657e-01,6.934710979488732663e-02,-1.298355693540065303e-01,-4.173292937139517211e-01,3.065289020511267545e-02,9.016443064599345691e-02,-3.226707062860482700e-01
+-3.793666227249171130e-01,2.922088815130248207e-01,-7.120691345994749344e-02,-2.782043068114437370e-03,3.145830796547265384e-01,-1.851921758806154006e-01,6.714023036867432515e-01,-2.142641032479645768e-01,-3.490610897375452382e-01,1.639386155516255744e-02,-1.703940665430660542e-02,-1.958198324588327627e-02,4.539904997396525255e-02,-1.100000000000000006e-01,-7.423704566931820237e-01,-4.539904997396525255e-02,1.100000000000000006e-01,-6.176295433068180740e-01,6.022419547717555721e-02,-1.299917285603418016e-01,-4.192687205455710164e-01,3.977580452282444140e-02,9.000827143965818566e-02,-3.207312794544289747e-01
+-4.622966703091204166e-01,2.418044428698255532e-01,-9.227356492624677609e-02,-8.810760645486527889e-03,3.717175438095288165e-01,-1.520718893937756111e-01,7.407176961220061084e-01,-1.930679167301627419e-01,-3.490656931085965309e-01,3.098756273254180127e-02,-1.457753668248182310e-02,-1.996643096950657600e-02,3.090169943750645243e-02,-1.100000000000000006e-01,-7.465739561406581348e-01,-3.090169943750645243e-02,1.100000000000000006e-01,-6.134260438593419629e-01,5.084952753465646347e-02,-1.296556250607783511e-01,-4.199949879638495420e-01,4.915047246534343106e-02,9.034437493922164997e-02,-3.200050120361504491e-01
+-5.348385334533082291e-01,1.915338529942131052e-01,-1.124415214076143199e-01,-1.318858593751649246e-02,4.184620240911059996e-01,-1.189504629203942676e-01,7.942577162624331333e-01,-1.744406738135892143e-01,-3.490659808192872471e-01,4.719277263853401128e-02,-1.166413896012355803e-02,-1.985221780112803036e-02,1.564344650403550960e-02,-1.100000000000000006e-01,-7.491381838416583117e-01,-1.564344650403550960e-02,1.100000000000000006e-01,-6.108618161583417860e-01,4.145394140481378081e-02,-1.288355348389389476e-01,-4.194902128546058595e-01,5.854605859518632188e-02,9.116446516106105347e-02,-3.205097871453941316e-01
+-5.953693400280170023e-01,1.421519329442438861e-01,-1.297194457235825438e-01,-1.591602986310255985e-02,4.543397535388788988e-01,-8.632316183588412128e-02,8.301158477194773289e-01,-1.582451059998958021e-01,-3.490659988012054793e-01,6.451373185726017034e-02,-8.703821904368795603e-03,-1.924197278445464315e-02,1.284487834964343574e-14,-1.100000000000000006e-01,-7.500000000000000000e-01,-1.284487834964343574e-14,1.100000000000000006e-01,-6.100000000000000977e-01,3.226878760032694804e-02,-1.275516512378086775e-01,-4.177668244562822153e-01,6.773121239967294649e-02,9.244834876219130970e-02,-3.222331755437177758e-01
+-6.433256773732501932e-01,9.447163462312514748e-02,-1.426945809658415887e-01,-1.705646484153968551e-02,4.797609735116907248e-01,-5.475217720653794556e-02,8.476869101482981117e-01,-1.444180509880011731e-01,-3.459210837709160158e-01,8.251230611391059677e-02,-5.985677071241947249e-03,-1.815963020596107064e-02,-1.564344650400996059e-02,-1.100000000000000006e-01,-7.491381838416611982e-01,1.564344650400996059e-02,1.100000000000000006e-01,-6.108618161583388995e-01,2.352023509164028955e-02,-1.258355877326128025e-01,-4.148672583108433676e-01,7.647976490835971253e-02,9.416441226738719861e-02,-3.251327416891566235e-01
+-6.773332858453924299e-01,4.934908311157820693e-02,-1.498575406396774889e-01,-1.673834903915413092e-02,4.945905135244864637e-01,-2.485129274915886047e-02,8.412338040720747090e-01,-1.329767390242964087e-01,-3.118859117682410975e-01,1.008067836223558583e-01,-3.185372749503888323e-03,-1.664499566594069072e-02,-3.090169943748185058e-02,-1.100000000000000006e-01,-7.465739561406636859e-01,3.090169943748185058e-02,1.100000000000000006e-01,-6.134260438593364118e-01,1.542370227629859952e-02,-1.237295995021374245e-01,-4.108629113598984417e-01,8.457629772370139909e-02,9.627040049786257658e-02,-3.291370886401015494e-01
+-6.991592328519322663e-01,7.673188385104133535e-03,-1.516888329904858834e-01,-1.515302578485772100e-02,5.007475828906733373e-01,2.725583435131811831e-03,8.177541401320245207e-01,-1.240306783858131368e-01,-2.714130818281747515e-01,1.190744289965983277e-01,-7.917428048760402843e-04,-1.474786567659410429e-02,-4.539904997394220154e-02,-1.100000000000000006e-01,-7.423704566931902393e-01,4.539904997394220154e-02,1.100000000000000006e-01,-6.176295433068098584e-01,8.178552663067620299e-03,-1.212855429659911305e-01,-4.058523839150453005e-01,9.182144733693231586e-02,9.871445703400887062e-02,-3.341476160849546351e-01
+-7.098632864869131032e-01,-2.963590179864867766e-02,-1.487310921673655473e-01,-1.254818146290918868e-02,4.994660274918585330e-01,2.728787781473050039e-02,7.809684223237061129e-01,-1.178014005988093360e-01,-2.278042664175237431e-01,1.370588412565152403e-01,1.026656369144780638e-03,-1.252216408640926051e-02,-5.877852522923576739e-02,-1.100000000000000006e-01,-7.366311896062522901e-01,5.877852522923576739e-02,1.100000000000000006e-01,-6.233688103937478076e-01,1.963185880697902730e-03,-1.185635989074523694e-01,-3.999590517909633602e-01,9.803681411930216527e-02,1.014364010925476317e-01,-3.400409482090367419e-01
+-7.103901144865900630e-01,-6.161585822199702051e-02,-1.416878746226436780e-01,-9.217067175087446940e-03,4.917885642703526683e-01,4.810022722828419250e-02,7.340487569098212983e-01,-1.146525911131229397e-01,-1.832300851383349416e-01,1.545832616036366403e-01,2.367965080446166742e-03,-1.002054977264322730e-02,-7.071067811864448216e-02,-1.100000000000000006e-01,-7.294974746830655832e-01,7.071067811864448216e-02,1.100000000000000006e-01,-6.305025253169345145e-01,-3.069355113008799540e-03,-1.156307906228568050e-01,-3.933280283833954782e-01,1.030693551130087426e-01,1.043692093771431961e-01,-3.466719716166044574e-01
+-7.018536152211497514e-01,-8.723604095431450323e-02,-1.314589164207913552e-01,-5.483080761088218041e-03,4.787833981385106741e-01,6.436012173375646461e-02,6.803817301686214680e-01,-1.151334353455718412e-01,-1.398613826580820396e-01,1.715712081078959172e-01,3.411449538234514675e-03,-7.290000459076057156e-03,-8.090169943748594383e-02,-1.100000000000000006e-01,-7.211449676604816394e-01,8.090169943748594383e-02,1.100000000000000006e-01,-6.388550323395184583e-01,-6.795152456741414271e-03,-1.125593335856038685e-01,-3.861225914957410188e-01,1.067951524567414268e-01,1.074406664143961326e-01,-3.538774085042589723e-01
+-6.854951399744347862e-01,-1.053548694612922998e-01,-1.190053900479190463e-01,-1.678016517599429953e-03,4.615221586756960148e-01,7.516005639097697588e-02,6.233272708742650936e-01,-1.200377521513110585e-01,-9.974724695722292367e-02,1.880758526936116837e-01,4.366040839593610633e-03,-4.369022085688818204e-03,-8.910065241882986209e-02,-1.100000000000000006e-01,-7.117793349817778115e-01,8.910065241882986209e-02,1.100000000000000006e-01,-6.482206650182222862e-01,-9.122464654684865615e-03,-1.094248572615321435e-01,-3.785201628976479493e-01,1.091224646546848642e-01,1.105751427384678576e-01,-3.614798371023520418e-01
+-6.625800878602801092e-01,-1.146620808150905640e-01,-1.052190971445289280e-01,1.890103040919052617e-03,4.410041489838970596e-01,7.943570573496878950e-02,5.658964679615743343e-01,-1.304791654639547716e-01,-6.461523056274336152e-02,2.043186048997010507e-01,5.419406970884293843e-03,-1.287435098142067358e-03,-9.510565162951051255e-02,-1.100000000000000006e-01,-7.016311896062568110e-01,9.510565162951051255e-02,1.100000000000000006e-01,-6.583688103937432867e-01,-9.993985556619393307e-03,-1.063045428604708492e-01,-3.707079396122153758e-01,1.099939855566194058e-01,1.136954571395291519e-01,-3.692920603877845043e-01
+-6.342675291553551142e-01,-1.136141537209036240e-01,-9.083235139048308204e-02,4.987495030833784954e-03,4.180607698341495260e-01,7.590858215730496295e-02,5.104581687393295875e-01,-1.479745070381152938e-01,-3.567820158594965652e-02,2.207334564717429171e-01,6.698175941161378655e-03,1.929766589099895027e-03,-9.876883405951128458e-02,-1.100000000000000006e-01,-6.909504125528272978e-01,9.876883405951128458e-02,1.100000000000000006e-01,-6.690495874471727999e-01,-9.388255425527340658e-03,-1.032752228787038457e-01,-3.628782845040131599e-01,1.093882554255273254e-01,1.167247771212961555e-01,-3.771217154959869422e-01
+-6.015091030975466824e-01,-1.003892154377848400e-01,-7.639017381998311484e-02,7.536003586175508626e-03,3.932898026092485622e-01,6.304935679356851730e-02,4.585879697261115995e-01,-1.745055716380163602e-01,-1.353823766724561797e-02,2.380022910156736893e-01,8.248665217433578598e-03,5.252174634719638038e-03,-1.000000000000000056e-01,-1.100000000000000006e-01,-6.800000000000113731e-01,1.000000000000000056e-01,1.100000000000000006e-01,-6.799999999999887246e-01,-7.320189347539252100e-03,-1.004114892279187599e-01,-3.552239896669407981e-01,1.073201893475392577e-01,1.195885107720812413e-01,-3.847760103330591930e-01
+-5.650199172975034489e-01,-7.293045398962005876e-02,-6.227748628620528165e-02,9.739606996814169013e-03,3.670525667964336103e-01,3.912876259706342397e-02,4.111058022736340800e-01,-2.124776593390886870e-01,1.772078937294409035e-03,2.570391413965179006e-01,1.003981562872895313e-02,8.624325639693633527e-03,-9.876883405951636385e-02,-1.100000000000000006e-01,-6.690495874471953375e-01,9.876883405951636385e-02,1.100000000000000006e-01,-6.909504125528047602e-01,-3.840709973012959577e-03,-9.778385653478521844e-02,-3.479335292430351112e-01,1.038407099730128819e-01,1.222161434652147827e-01,-3.920664707569650465e-01
+-5.253190287860901586e-01,-2.922878092785392151e-02,-4.877165008303781246e-02,1.225311428517925766e-02,3.395273341131585521e-01,2.497974193383429090e-03,3.682489008908785277e-01,-2.643954788337374850e-01,1.064761765343158473e-02,2.788295816935514315e-01,1.198181587144313449e-02,1.193481551187093592e-02,-9.510565162952060170e-02,-1.100000000000000006e-01,-6.583688103937650471e-01,9.510565162952060170e-02,1.100000000000000006e-01,-7.016311896062350506e-01,9.645063681206975104e-04,-9.545702583682091902e-02,-3.411864185635835600e-01,9.903549363187931498e-02,1.245429741631790821e-01,-3.988135814364164311e-01
+-4.828051591285218991e-01,3.191699582449800815e-02,-3.609134982023941285e-02,1.631742097927225271e-02,3.107876914954278980e-01,-4.768801171432852232e-02,3.298837045299622961e-01,-3.319682847511264412e-01,1.374068819078447766e-02,3.039753575647252681e-01,1.395079121639443594e-02,1.498012027513129577e-02,-8.910065241884460030e-02,-1.100000000000000006e-01,-6.482206650182424923e-01,8.910065241884460030e-02,1.100000000000000006e-01,-7.117793349817576054e-01,6.977139301944296212e-03,-9.348829142811815318e-02,-3.351487938858908056e-01,9.302286069805570934e-02,1.265117085718818479e-01,-4.048512061141091856e-01
+-4.378336598936486412e-01,1.095522403409370654e-01,-2.442778464481942455e-02,2.363195766967221556e-02,2.808774127907871510e-01,-1.102372783054219735e-01,2.956860640216650293e-01,-4.144794111095814748e-01,1.181813277407688968e-02,3.318676187595787641e-01,1.581207081670307421e-02,1.744878856003222872e-02,-8.090169943750502579e-02,-1.100000000000000006e-01,-6.388550323395367769e-01,8.090169943750502579e-02,1.100000000000000006e-01,-7.211449676604633208e-01,1.404913785084245526e-02,-9.192613008367409022e-02,-3.299693215672492297e-01,8.595086214915756417e-02,1.280738699163259109e-01,-4.100306784327507614e-01
+-3.907770986531567403e-01,1.980260120084546827e-01,-1.395745259038389668e-02,3.546144753776335479e-02,2.498681818960543921e-01,-1.798060562166572396e-01,2.652653009987502308e-01,-5.040411986081640983e-01,5.665123502622359739e-03,3.478089728115799084e-01,1.743836329117966211e-02,1.886183327923107375e-02,-7.071067811866729724e-02,-1.100000000000000006e-01,-6.305025253169505017e-01,7.071067811866729724e-02,1.100000000000000006e-01,-7.294974746830495960e-01,2.200636593992374990e-02,-9.080900740030518892e-02,-3.257755374058267650e-01,7.799363406007625565e-02,1.291909925996947983e-01,-4.142244625941732261e-01
+-3.420655581767615416e-01,2.895443046003762788e-01,-4.841596824626471368e-03,5.160187264021838527e-02,2.178979182517026547e-01,-2.492728734052915007e-01,2.382376078105868655e-01,-5.905773675886994978e-01,-3.968751817792913646e-03,3.489874358007237221e-01,1.872202140058304431e-02,1.860051970969342841e-02,-5.877852522926188539e-02,-1.100000000000000006e-01,-6.233688103937611302e-01,5.877852522926188539e-02,1.100000000000000006e-01,-7.366311896062389675e-01,3.065289020510904294e-02,-9.016443064599362345e-02,-3.226707062860493247e-01,6.934710979489097649e-02,1.298355693540063638e-01,-4.173292937139506664e-01
+-2.922088815130464701e-01,3.793666227248798095e-01,2.782043068111437166e-03,7.120691345993869492e-02,1.851921758806297502e-01,-3.145830796547002262e-01,2.142641032479743191e-01,-6.714023036867110550e-01,-1.639386155515655877e-02,3.490610897375452382e-01,1.958198324588299177e-02,1.703940665430748666e-02,-4.539904997397128245e-02,-1.100000000000000006e-01,-6.176295433068201834e-01,4.539904997397128245e-02,1.100000000000000006e-01,-7.423704566931799143e-01,3.977580452282045154e-02,-9.000827143965813015e-02,-3.207312794544295853e-01,6.022419547717956095e-02,1.299917285603418571e-01,-4.192687205455704058e-01
+-2.418044428698468140e-01,4.622966703090880536e-01,8.810760645484368159e-03,9.227356492623807471e-02,1.520718893937896277e-01,-3.717175438095071671e-01,1.930679167301711519e-01,-7.407176961219804623e-01,-3.098756273253523708e-02,3.490656931085965309e-01,1.996643096950659682e-02,1.457753668248283271e-02,-3.090169943751271478e-02,-1.100000000000000006e-01,-6.134260438593434062e-01,3.090169943751271478e-02,1.100000000000000006e-01,-7.465739561406566915e-01,4.915047246533959385e-02,-9.034437493922140017e-02,-3.200050120361505046e-01,5.084952753466041864e-02,1.296556250607786009e-01,-4.199949879638494865e-01
+-1.915338529942339496e-01,5.348385334532802515e-01,1.318858593751501274e-02,1.124415214076062985e-01,1.189504629204086589e-01,-4.184620240910886801e-01,1.744406738135967083e-01,-7.942577162624144815e-01,-4.719277263853006305e-02,3.490659808192872471e-01,1.985221780112902262e-02,1.166413896012477754e-02,-1.564344650404201481e-02,-1.100000000000000006e-01,-6.108618161583424522e-01,1.564344650404201481e-02,1.100000000000000006e-01,-7.491381838416576455e-01,5.854605859518231120e-02,-9.116446516106060938e-02,-3.205097871453936320e-01,4.145394140481770129e-02,1.288355348389393917e-01,-4.194902128546063591e-01
+-1.421519329442645363e-01,5.953693400279942427e-01,1.591602986310167167e-02,1.297194457235760767e-01,8.632316183589773539e-02,-4.543397535388660202e-01,1.582451059999022691e-01,-8.301158477194660046e-01,-6.451373185725246817e-02,3.490659988012054793e-01,1.924197278445486520e-02,8.703821904369879806e-03,-1.942964512341583692e-14,-1.100000000000000006e-01,-6.100000000000000977e-01,1.942964512341583692e-14,1.100000000000000006e-01,-7.500000000000000000e-01,6.773121239966928275e-02,-9.244834876219068520e-02,-3.222331755437168321e-01,3.226878760033073668e-02,1.275516512378093159e-01,-4.177668244562831590e-01
+-9.447163462314410454e-02,6.433256773732333178e-01,1.705646484153946346e-02,1.426945809658374809e-01,5.475217720655051884e-02,-4.797609735116825647e-01,1.444180509880062524e-01,-8.476869101482960023e-01,-8.251230611390304726e-02,3.459210837709269515e-01,1.815963020596144534e-02,5.985677071242929102e-03,1.564344650400363232e-02,-1.100000000000000006e-01,-6.108618161583382333e-01,-1.564344650400363232e-02,1.100000000000000006e-01,-7.491381838416618644e-01,7.647976490835625696e-02,-9.416441226738640757e-02,-3.251327416891551803e-01,2.352023509164374859e-02,1.258355877326135797e-01,-4.148672583108448109e-01
+-4.934908311159591499e-02,6.773332858453808836e-01,1.673834903915456113e-02,1.498575406396756016e-01,2.485129274917056985e-02,-4.945905135244821893e-01,1.329767390243006553e-01,-8.412338040720808152e-01,-1.008067836223503488e-01,3.118859117682568072e-01,1.664499566594231789e-02,3.185372749504993342e-03,3.090169943747575476e-02,-1.100000000000000006e-01,-6.134260438593349685e-01,-3.090169943747575476e-02,1.100000000000000006e-01,-7.465739561406651292e-01,8.457629772369826271e-02,-9.627040049786164677e-02,-3.291370886400997176e-01,1.542370227630175672e-02,1.237295995021383543e-01,-4.108629113599002736e-01
+-7.673188385120785146e-03,6.991592328519256050e-01,1.515302578485863694e-02,1.516888329904862442e-01,-2.725583435120806745e-03,-5.007475828906723381e-01,1.240306783858163980e-01,-8.177541401320376213e-01,-1.190744289965907643e-01,2.714130818281924040e-01,1.474786567659499593e-02,7.917428048769810465e-04,4.539904997393633818e-02,-1.100000000000000006e-01,-6.176295433068077489e-01,-4.539904997393633818e-02,1.100000000000000006e-01,-7.423704566931923488e-01,9.182144733692955418e-02,-9.871445703400778815e-02,-3.341476160849524146e-01,8.178552663070458306e-03,1.212855429659922130e-01,-4.058523839150475765e-01
+2.963590179863408169e-02,7.098632864869104386e-01,1.254818146291054350e-02,1.487310921673676289e-01,-2.728787781472114676e-02,-4.994660274918603649e-01,1.178014005988113622e-01,-7.809684223237234324e-01,-1.370588412565077463e-01,2.278042664175420062e-01,1.252216408641142198e-02,-1.026656369144098675e-03,5.877852522923043832e-02,-1.100000000000000006e-01,-6.233688103937451430e-01,-5.877852522923043832e-02,1.100000000000000006e-01,-7.366311896062549547e-01,9.803681411929973666e-02,-1.014364010925464382e-01,-3.400409482090340219e-01,1.963185880700268893e-03,1.185635989074535629e-01,-3.999590517909659693e-01
+6.161585822198485662e-02,7.103901144865919504e-01,9.217067175088990844e-03,1.416878746226475083e-01,-4.810022722827701769e-02,-4.917885642703571647e-01,1.146525911131236058e-01,-7.340487569098429477e-01,-1.545832616036298401e-01,1.832300851383533713e-01,1.002054977264293240e-02,-2.367965080445635050e-03,7.071067811863981922e-02,-1.100000000000000006e-01,-6.305025253169312949e-01,-7.071067811863981922e-02,1.100000000000000006e-01,-7.294974746830688028e-01,1.030693551130069663e-01,-1.043692093771419332e-01,-3.466719716166016263e-01,-3.069355113006953795e-03,1.156307906228580679e-01,-3.933280283833983648e-01
+8.723604095430555205e-02,7.018536152211548584e-01,5.483080761089785364e-03,1.314589164207961292e-01,-6.436012173375094125e-02,-4.787833981385171134e-01,1.151334353455706477e-01,-6.803817301686437835e-01,-1.715712081078890339e-01,1.398613826580997199e-01,7.290000459077237635e-03,-3.411449538234194619e-03,8.090169943748216907e-02,-1.100000000000000006e-01,-6.388550323395147945e-01,-8.090169943748216907e-02,1.100000000000000006e-01,-7.211449676604853032e-01,1.067951524567401778e-01,-1.074406664143948559e-01,-3.538774085042559192e-01,-6.795152456740172209e-03,1.125593335856051452e-01,-3.861225914957440719e-01
+1.053548694612866238e-01,6.854951399744427798e-01,1.678016517600974290e-03,1.190053900479247084e-01,-7.516005639097386726e-02,-4.615221586757046190e-01,1.200377521513081303e-01,-6.233272708742887414e-01,-1.880758526936057162e-01,9.974724695724029866e-02,4.369022085689924957e-03,-4.366040839593520427e-03,8.910065241882696163e-02,-1.100000000000000006e-01,-6.482206650182182894e-01,-8.910065241882696163e-02,1.100000000000000006e-01,-7.117793349817818083e-01,1.091224646546842258e-01,-1.105751427384665669e-01,-3.614798371023488777e-01,-9.122464654684213359e-03,1.094248572615334342e-01,-3.785201628976511135e-01
+1.146620808150886073e-01,6.625800878602907673e-01,-1.890103040917698232e-03,1.052190971445348261e-01,-7.943570573496844256e-02,-4.410041489839062190e-01,1.304791654639491094e-01,-5.658964679615980931e-01,-2.043186048996942505e-01,6.461523056275679522e-02,1.287435098143326333e-03,-5.419406970883803784e-03,9.510565162950847251e-02,-1.100000000000000006e-01,-6.583688103937388458e-01,-9.510565162950847251e-02,1.100000000000000006e-01,-7.016311896062612519e-01,1.099939855566193503e-01,-1.136954571395278613e-01,-3.692920603877812846e-01,-9.993985556619337796e-03,1.063045428604721399e-01,-3.707079396122187065e-01
+1.136141537209065105e-01,6.342675291553685479e-01,-4.987495030832691210e-03,9.083235139048934093e-02,-7.590858215730814096e-02,-4.180607698341597955e-01,1.479745070381059402e-01,-5.104581687393529021e-01,-2.207334564717348679e-01,3.567820158596059915e-02,-1.929766589098558423e-03,-6.698175941160747215e-03,9.876883405951025763e-02,-1.100000000000000006e-01,-6.690495874471682480e-01,-9.876883405951025763e-02,1.100000000000000006e-01,-6.909504125528318497e-01,1.093882554255279083e-01,-1.167247771212949481e-01,-3.771217154959835560e-01,-9.388255425527902709e-03,1.032752228787050530e-01,-3.628782845040164351e-01
+1.003892154377930557e-01,6.015091030975613373e-01,-7.536003586174463455e-03,7.639017381998923495e-02,-6.304935679357617784e-02,-3.932898026092593868e-01,1.745055716380032040e-01,-4.585879697261325827e-01,-2.380022910156672777e-01,1.353823766725345892e-02,-5.252174634718398578e-03,-8.248665217432818789e-03,1.000000000000000056e-01,-1.100000000000000006e-01,-6.799999999999840616e-01,-1.000000000000000056e-01,1.100000000000000006e-01,-6.800000000000160361e-01,1.073201893475403956e-01,-1.195885107720800616e-01,-3.847760103330560844e-01,-7.320189347540390079e-03,1.004114892279199395e-01,-3.552239896669439068e-01
+7.293045398963464432e-02,5.650199172975198803e-01,-9.739606996813230527e-03,6.227748628621111032e-02,-3.912876259707585153e-02,-3.670525667964451566e-01,2.124776593390700907e-01,-4.111058022736537865e-01,-2.570391413965093519e-01,-1.772078937289009275e-03,-8.624325639692238810e-03,-1.003981562872823322e-02,9.876883405951739081e-02,-1.100000000000000006e-01,-6.909504125528002083e-01,-9.876883405951739081e-02,1.100000000000000006e-01,-6.690495874471998894e-01,1.038407099730146721e-01,-1.222161434652137696e-01,-3.920664707569620488e-01,-3.840709973014659606e-03,9.778385653478623152e-02,-3.479335292430379423e-01
+2.922878092787579984e-02,5.253190287861065899e-01,-1.225311428517797223e-02,4.877165008304305827e-02,-2.497974193401534398e-03,-3.395273341131697098e-01,2.643954788337123385e-01,-3.682489008908944594e-01,-2.788295816935415505e-01,-1.064761765342937816e-02,-1.193481551186951345e-02,-1.198181587144232438e-02,9.510565162952257234e-02,-1.100000000000000006e-01,-7.016311896062308318e-01,-9.510565162952257234e-02,1.100000000000000006e-01,-6.583688103937692659e-01,9.903549363188152155e-02,-1.245429741631782078e-01,-3.988135814364138221e-01,9.645063681184770643e-04,9.545702583682179332e-02,-3.411864185635861690e-01
+-3.191699582446819172e-02,4.828051591285408839e-01,-1.631742097926995247e-02,3.609134982024463090e-02,4.768801171430429170e-02,-3.107876914954406655e-01,3.319682847510944668e-01,-3.298837045299780613e-01,-3.039753575647139439e-01,-1.374068819078400755e-02,-1.498012027513006585e-02,-1.395079121639368827e-02,8.910065241884768117e-02,-1.100000000000000006e-01,-7.117793349817533866e-01,-8.910065241884768117e-02,1.100000000000000006e-01,-6.482206650182467111e-01,9.302286069805854041e-02,-1.265117085718810708e-01,-4.048512061141067431e-01,6.977139301941465144e-03,9.348829142811891646e-02,-3.351487938858932480e-01
+-1.095522403409007473e-01,4.378336598936686253e-01,-2.363195766966819447e-02,2.442778464482415340e-02,1.102372783053931354e-01,-2.808774127908004181e-01,4.144794111095434497e-01,-2.956860640216791847e-01,-3.318676187595665517e-01,-1.181813277407864522e-02,-1.744878856003129197e-02,-1.581207081670240461e-02,8.090169943750899484e-02,-1.100000000000000006e-01,-7.211449676604594350e-01,-8.090169943750899484e-02,1.100000000000000006e-01,-6.388550323395406627e-01,8.595086214916079770e-02,-1.280738699163253280e-01,-4.100306784327487630e-01,1.404913785083920091e-02,9.192613008367467309e-02,-3.299693215672512281e-01
+-1.980260120084159081e-01,3.907770986531770019e-01,-3.546144753775735264e-02,1.395745259038811206e-02,1.798060562166273191e-01,-2.498681818960677981e-01,5.040411986081267948e-01,-2.652653009987621657e-01,-3.478089728115784096e-01,-5.665123502625916789e-03,-1.886183327923073721e-02,-1.743836329117897516e-02,7.071067811867208508e-02,-1.100000000000000006e-01,-7.294974746830462653e-01,-7.071067811867208508e-02,1.100000000000000006e-01,-6.305025253169538324e-01,7.799363406007983612e-02,-1.291909925996944097e-01,-4.142244625941716718e-01,2.200636593992015555e-02,9.080900740030557750e-02,-3.257755374058283193e-01
+-2.895443046003376431e-01,3.420655581767829134e-01,-5.160187264021075942e-02,4.841596824630113420e-03,2.492728734052627182e-01,-2.178979182517167823e-01,5.905773675886641927e-01,-2.382376078105978290e-01,-3.489874358007236665e-01,3.968751817787797079e-03,-1.860051970969371984e-02,-1.872202140058256553e-02,5.877852522926735324e-02,-1.100000000000000006e-01,-7.366311896062361919e-01,-5.877852522926735324e-02,1.100000000000000006e-01,-6.233688103937639058e-01,6.934710979489480676e-02,-1.298355693540061973e-01,-4.173292937139496117e-01,3.065289020510519186e-02,9.016443064599378998e-02,-3.226707062860503794e-01
+-3.793666227248435052e-01,2.922088815130668982e-01,-7.120691345992999355e-02,-2.782043068108675486e-03,3.145830796546745245e-01,-1.851921758806431562e-01,6.714023036866786365e-01,-2.142641032479834229e-01,-3.490610897375452382e-01,1.639386155515126439e-02,-1.703940665430836443e-02,-1.958198324588279748e-02,4.539904997397698622e-02,-1.100000000000000006e-01,-7.423704566931778048e-01,-4.539904997397698622e-02,1.100000000000000006e-01,-6.176295433068222929e-01,6.022419547718334265e-02,-1.299917285603418848e-01,-4.192687205455699062e-01,3.977580452281665596e-02,9.000827143965810240e-02,-3.207312794544300849e-01
+-4.622966703090545804e-01,2.418044428698686021e-01,-9.227356492622917905e-02,-8.810760645482119957e-03,3.717175438094850737e-01,-1.520718893938039773e-01,7.407176961219539280e-01,-1.930679167301798949e-01,-3.490656931085965309e-01,3.098756273252977270e-02,-1.457753668248413723e-02,-1.996643096950673907e-02,3.090169943751914367e-02,-1.100000000000000006e-01,-7.465739561406552482e-01,-3.090169943751914367e-02,1.100000000000000006e-01,-6.134260438593448495e-01,5.084952753466447095e-02,-1.296556250607788507e-01,-4.199949879638494310e-01,4.915047246533552766e-02,9.034437493922115037e-02,-3.200050120361505601e-01
+-5.348385334532514968e-01,1.915338529942555157e-01,-1.124415214075981523e-01,-1.318858593751348444e-02,4.184620240910709166e-01,-1.189504629204222730e-01,7.942577162623950526e-01,-1.744406738136041468e-01,-3.490659808192872471e-01,4.719277263852002247e-02,-1.166413896012612889e-02,-1.985221780112836690e-02,1.564344650404869350e-02,-1.100000000000000006e-01,-7.491381838416568684e-01,-1.564344650404869350e-02,1.100000000000000006e-01,-6.108618161583432293e-01,4.145394140482171197e-02,-1.288355348389398358e-01,-4.194902128546068587e-01,5.854605859517829358e-02,9.116446516106015141e-02,-3.205097871453931324e-01
+-5.953693400279708170e-01,1.421519329442854362e-01,-1.297194457235694987e-01,-1.591602986310085982e-02,4.543397535388528641e-01,-8.632316183591137726e-02,8.301158477194543472e-01,-1.582451059999085141e-01,-3.490659988012054793e-01,6.451373185724229575e-02,-8.703821904371128806e-03,-1.924197278445442458e-02,2.619204758112826094e-14,-1.100000000000000006e-01,-7.500000000000000000e-01,-2.619204758112826094e-14,1.100000000000000006e-01,-6.100000000000000977e-01,3.226878760033460164e-02,-1.275516512378099543e-01,-4.177668244562841582e-01,6.773121239966539697e-02,9.244834876219003295e-02,-3.222331755437158329e-01
+-6.433256773732158873e-01,9.447163462316408855e-02,-1.426945809658330955e-01,-1.705646484153932815e-02,4.797609735116739604e-01,-5.475217720656434806e-02,8.476869101482936708e-01,-1.444180509880116092e-01,-3.459210837709386088e-01,8.251230611389492875e-02,-5.985677071244059275e-03,-1.815963020596218780e-02,-1.564344650399695363e-02,-1.100000000000000006e-01,-7.491381838416626415e-01,1.564344650399695363e-02,1.100000000000000006e-01,-6.108618161583374562e-01,2.352023509164738110e-02,-1.258355877326144123e-01,-4.148672583108463097e-01,7.647976490835262098e-02,9.416441226738558878e-02,-3.251327416891536815e-01
+-6.773332858453691152e-01,4.934908311161471245e-02,-1.498575406396738252e-01,-1.673834903915496705e-02,4.945905135244778039e-01,-2.485129274918312925e-02,8.412338040720879206e-01,-1.329767390243051239e-01,-3.118859117682731830e-01,1.008067836223416058e-01,-3.185372749506258823e-03,-1.664499566594256769e-02,-3.090169943746932935e-02,-1.100000000000000006e-01,-7.465739561406665725e-01,3.090169943746932935e-02,1.100000000000000006e-01,-6.134260438593335252e-01,1.542370227630506657e-02,-1.237295995021393397e-01,-4.108629113599022720e-01,8.457629772369493204e-02,9.627040049786066145e-02,-3.291370886400977191e-01
+-6.991592328519181665e-01,7.673188385137736864e-03,-1.516888329904863275e-01,-1.515302578485955981e-02,5.007475828906711168e-01,2.725583435109616912e-03,8.177541401320499448e-01,-1.240306783858195622e-01,-2.714130818282102231e-01,1.190744289965829650e-01,-7.917428048778378915e-04,-1.474786567659589973e-02,-4.539904997393031522e-02,-1.100000000000000006e-01,-7.423704566931944582e-01,4.539904997393031522e-02,1.100000000000000006e-01,-6.176295433068056395e-01,8.178552663073358764e-03,-1.212855429659933232e-01,-4.058523839150499635e-01,9.182144733692663985e-02,9.871445703400667793e-02,-3.341476160849500276e-01
+-7.098632864869083292e-01,-2.963590179861904511e-02,-1.487310921673699049e-01,-1.254818146291180637e-02,4.994660274918624743e-01,2.728787781471107843e-02,7.809684223237418621e-01,-1.178014005988135132e-01,-2.278042664175612408e-01,1.370588412565001135e-01,1.026656369143432758e-03,-1.252216408641135433e-02,-5.877852522922497741e-02,-1.100000000000000006e-01,-7.366311896062577302e-01,5.877852522922497741e-02,1.100000000000000006e-01,-6.233688103937423675e-01,1.963185880702704444e-03,-1.185635989074547841e-01,-3.999590517909686893e-01,9.803681411929729417e-02,1.014364010925452170e-01,-3.400409482090313018e-01
+-7.103901144865936157e-01,-6.161585822197235274e-02,-1.416878746226510888e-01,-9.217067175090513931e-03,4.917885642703616056e-01,4.810022722826896163e-02,7.340487569098642640e-01,-1.146525911131243136e-01,-1.832300851383722451e-01,1.545832616036224294e-01,2.367965080445167108e-03,-1.002054977264402180e-02,-7.071067811863504526e-02,-1.100000000000000006e-01,-7.294974746830721335e-01,7.071067811863504526e-02,1.100000000000000006e-01,-6.305025253169279642e-01,-3.069355113005066416e-03,-1.156307906228593724e-01,-3.933280283834013624e-01,1.030693551130050650e-01,1.043692093771406287e-01,-3.466719716165986287e-01
+-7.018536152211604096e-01,-8.723604095429604577e-02,-1.314589164208010696e-01,-5.483080761091383912e-03,4.787833981385238302e-01,6.436012173374502932e-02,6.803817301686680974e-01,-1.151334353455695930e-01,-1.398613826581178166e-01,1.715712081078817897e-01,3.411449538233787826e-03,-7.290000459078385155e-03,-8.090169943747820003e-02,-1.100000000000000006e-01,-7.211449676604890779e-01,8.090169943747820003e-02,1.100000000000000006e-01,-6.388550323395110198e-01,-6.795152456738867697e-03,-1.125593335856064775e-01,-3.861225914957472360e-01,1.067951524567388732e-01,1.074406664143935236e-01,-3.538774085042526996e-01
+-6.854951399744512175e-01,-1.053548694612806425e-01,-1.190053900479301485e-01,-1.678016517602570670e-03,4.615221586757118910e-01,7.516005639097053659e-02,6.233272708743130552e-01,-1.200377521513048829e-01,-9.974724695725448176e-02,1.880758526935980279e-01,4.366040839592776231e-03,-4.369022085691361308e-03,-8.910065241882389464e-02,-1.100000000000000006e-01,-7.117793349817860271e-01,8.910065241882389464e-02,1.100000000000000006e-01,-6.482206650182140706e-01,-9.122464654683519469e-03,-1.094248572615347803e-01,-3.785201628976544441e-01,1.091224646546835320e-01,1.105751427384652208e-01,-3.614798371023455470e-01
+-6.625800878603012034e-01,-1.146620808150867754e-01,-1.052190971445405576e-01,1.890103040916255375e-03,4.410041489839151008e-01,7.943570573496816500e-02,5.658964679616209636e-01,-1.304791654639436693e-01,-6.461523056276984034e-02,2.043186048996876170e-01,5.419406970883337143e-03,-1.287435098144639085e-03,-9.510565162950650187e-02,-1.100000000000000006e-01,-7.016311896062654707e-01,9.510565162950650187e-02,1.100000000000000006e-01,-6.583688103937346270e-01,-9.993985556619282284e-03,-1.063045428604734027e-01,-3.707079396122219261e-01,1.099939855566192948e-01,1.136954571395265984e-01,-3.692920603877780650e-01
+-6.342675291553813155e-01,-1.136141537209093832e-01,-9.083235139049536389e-02,4.987495030831437873e-03,4.180607698341698431e-01,7.590858215731162428e-02,5.104581687393753286e-01,-1.479745070380969751e-01,-3.567820158597133362e-02,2.207334564717287617e-01,6.698175941160224196e-03,1.929766589097161103e-03,-9.876883405950920292e-02,-1.100000000000000006e-01,-6.909504125528365126e-01,9.876883405950920292e-02,1.100000000000000006e-01,-6.690495874471635851e-01,-9.388255425528478637e-03,-1.032752228787063298e-01,-3.628782845040197658e-01,1.093882554255284911e-01,1.167247771212936713e-01,-3.771217154959802254e-01
+-6.015091030975761033e-01,-1.003892154378016460e-01,-7.639017381999534118e-02,7.536003586173499816e-03,3.932898026092702670e-01,6.304935679358389389e-02,4.585879697261538990e-01,-1.745055716379895205e-01,-1.353823766726153580e-02,2.380022910156594229e-01,8.248665217432112756e-03,5.252174634716979575e-03,-1.000000000000000056e-01,-1.100000000000000006e-01,-6.800000000000206990e-01,1.000000000000000056e-01,1.100000000000000006e-01,-6.799999999999793987e-01,-7.320189347541590508e-03,-1.004114892279211330e-01,-3.552239896669471264e-01,1.073201893475415891e-01,1.195885107720788681e-01,-3.847760103330528647e-01
+-5.650199172975358675e-01,-7.293045398964975723e-02,-6.227748628621704308e-02,9.739606996812297246e-03,3.670525667964564809e-01,3.912876259708880644e-02,4.111058022736725492e-01,-2.124776593390510504e-01,1.772078937284119957e-03,2.570391413964999705e-01,1.003981562872737453e-02,8.624325639690538781e-03,-9.876883405951844552e-02,-1.100000000000000006e-01,-6.690495874472045523e-01,9.876883405951844552e-02,1.100000000000000006e-01,-6.909504125527955454e-01,-3.840709973016449841e-03,-9.778385653478730011e-02,-3.479335292430409954e-01,1.038407099730164485e-01,1.222161434652127010e-01,-3.920664707569589957e-01
+-5.253190287861245755e-01,-2.922878092789798349e-02,-4.877165008304876204e-02,1.225311428517667292e-02,3.395273341131819778e-01,2.497974193419925937e-03,3.682489008909122230e-01,-2.643954788336873030e-01,1.064761765342675526e-02,2.788295816935316696e-01,1.198181587144149345e-02,1.193481551186817771e-02,-9.510565162952466789e-02,-1.100000000000000006e-01,-6.583688103937738179e-01,9.510565162952466789e-02,1.100000000000000006e-01,-7.016311896062262798e-01,9.645063681161455960e-04,-9.545702583682272313e-02,-3.411864185635889446e-01,9.903549363188386689e-02,1.245429741631772780e-01,-3.988135814364110465e-01
+-4.828051591285583699e-01,3.191699582443896510e-02,-3.609134982024953670e-02,1.631742097926772161e-02,3.107876914954522674e-01,-4.768801171428039415e-02,3.298837045299923831e-01,-3.319682847510624923e-01,1.374068819078410990e-02,3.039753575647026751e-01,1.395079121639287469e-02,1.498012027512890532e-02,-8.910065241885058163e-02,-1.100000000000000006e-01,-6.482206650182507079e-01,8.910065241885058163e-02,1.100000000000000006e-01,-7.117793349817493898e-01,6.977139301938793670e-03,-9.348829142811963810e-02,-3.351487938858955240e-01,9.302286069806121882e-02,1.265117085718803491e-01,-4.048512061141044671e-01
+-4.378336598936883872e-01,1.095522403408642764e-01,-2.442778464482897594e-02,2.363195766966411787e-02,2.808774127908133522e-01,-1.102372783053638949e-01,2.956860640216927849e-01,-4.144794111095052580e-01,1.181813277408055862e-02,3.318676187595542837e-01,1.581207081670154765e-02,1.744878856003050441e-02,-8.090169943751296389e-02,-1.100000000000000006e-01,-6.388550323395444375e-01,8.090169943751296389e-02,1.100000000000000006e-01,-7.211449676604556602e-01,1.404913785083596045e-02,-9.192613008367524208e-02,-3.299693215672532265e-01,8.595086214916405898e-02,1.280738699163247452e-01,-4.100306784327467646e-01
+-3.907770986531978186e-01,1.980260120083771058e-01,-1.395745259039229622e-02,3.546144753775136438e-02,2.498681818960813983e-01,-1.798060562165971210e-01,2.652653009987746557e-01,-5.040411986080890472e-01,5.665123502629241387e-03,3.478089728115769108e-01,1.743836329117845821e-02,1.886183327923054293e-02,-7.071067811867685904e-02,-1.100000000000000006e-01,-6.305025253169571631e-01,7.071067811867685904e-02,1.100000000000000006e-01,-7.294974746830429346e-01,2.200636593991657161e-02,-9.080900740030595220e-02,-3.257755374058298736e-01,7.799363406008344435e-02,1.291909925996940489e-01,-4.142244625941701175e-01
+-3.420655581768040077e-01,2.895443046002983967e-01,-4.841596824633727716e-03,5.160187264020295317e-02,2.178979182517306601e-01,-2.492728734052334083e-01,2.382376078106088479e-01,-5.905773675886283325e-01,-3.968751817783134142e-03,3.489874358007235000e-01,1.872202140058208675e-02,1.860051970969418822e-02,-5.877852522927282802e-02,-1.100000000000000006e-01,-6.233688103937666813e-01,5.877852522927282802e-02,1.100000000000000006e-01,-7.366311896062334164e-01,3.065289020510135812e-02,-9.016443064599397039e-02,-3.226707062860514896e-01,6.934710979489865090e-02,1.298355693540060307e-01,-4.173292937139485015e-01
+-2.922088815130887696e-01,3.793666227248064793e-01,2.782043068105750742e-03,7.120691345992122279e-02,1.851921758806572005e-01,-3.145830796546483787e-01,2.142641032479934704e-01,-6.714023036866471061e-01,-1.639386155514536980e-02,3.490610897375452382e-01,1.958198324588249564e-02,1.703940665430921098e-02,-4.539904997398301612e-02,-1.100000000000000006e-01,-6.176295433068244023e-01,4.539904997398301612e-02,1.100000000000000006e-01,-7.423704566931756954e-01,3.977580452281266610e-02,-9.000827143965806076e-02,-3.207312794544306955e-01,6.022419547718734639e-02,1.299917285603419403e-01,-4.192687205455692956e-01
+-2.418044428698889192e-01,4.622966703090218288e-01,8.810760645480005329e-03,9.227356492622026951e-02,1.520718893938173832e-01,-3.717175438094631468e-01,1.930679167301876664e-01,-7.407176961219276157e-01,-3.098756273252262217e-02,3.490656931085965309e-01,1.996643096950646498e-02,1.457753668248524571e-02,-3.090169943752523948e-02,-1.100000000000000006e-01,-6.134260438593461817e-01,3.090169943752523948e-02,1.100000000000000006e-01,-7.465739561406539160e-01,4.915047246533169045e-02,-9.034437493922091444e-02,-3.200050120361506156e-01,5.084952753466832204e-02,1.296556250607790728e-01,-4.199949879638493755e-01
+-1.915338529942771095e-01,5.348385334532227420e-01,1.318858593751194574e-02,1.124415214075900199e-01,1.189504629204365532e-01,-4.184620240910532640e-01,1.744406738136116131e-01,-7.942577162623759568e-01,-4.719277263851255622e-02,3.490659808192872471e-01,1.985221780112850568e-02,1.166413896012727901e-02,-1.564344650405537218e-02,-1.100000000000000006e-01,-6.108618161583440065e-01,1.564344650405537218e-02,1.100000000000000006e-01,-7.491381838416560912e-01,5.854605859517428290e-02,-9.116446516105970732e-02,-3.205097871453926883e-01,4.145394140482573653e-02,1.288355348389402799e-01,-4.194902128546073028e-01
+-1.421519329443062529e-01,5.953693400279473913e-01,1.591602986310003756e-02,1.297194457235627818e-01,8.632316183592507464e-02,-4.543397535388397634e-01,1.582451059999148146e-01,-8.301158477194426899e-01,-6.451373185723456583e-02,3.490659988012054238e-01,1.924197278445476805e-02,8.703821904372310153e-03,-3.295445003884068496e-14,-1.100000000000000006e-01,-6.100000000000000977e-01,3.295445003884068496e-14,1.100000000000000006e-01,-7.500000000000000000e-01,6.773121239966152507e-02,-9.244834876218938069e-02,-3.222331755437148337e-01,3.226878760033848048e-02,1.275516512378106204e-01,-4.177668244562851574e-01
+-9.447163462318428073e-02,6.433256773731986788e-01,1.705646484153923101e-02,1.426945809658288766e-01,5.475217720657707399e-02,-4.797609735116656893e-01,1.444180509880172991e-01,-8.476869101482918945e-01,-8.251230611388760128e-02,3.459210837709501551e-01,1.815963020596279148e-02,5.985677071245128732e-03,1.564344650399027495e-02,-1.100000000000000006e-01,-6.108618161583367900e-01,-1.564344650399027495e-02,1.100000000000000006e-01,-7.491381838416633077e-01,7.647976490834898500e-02,-9.416441226738476999e-02,-3.251327416891521827e-01,2.352023509165102749e-02,1.258355877326152172e-01,-4.148672583108478085e-01
+-4.934908311163352379e-02,6.773332858453570138e-01,1.673834903915537298e-02,1.498575406396718546e-01,2.485129274919562620e-02,-4.945905135244733075e-01,1.329767390243094816e-01,-8.412338040720945820e-01,-1.008067836223331404e-01,3.118859117682892812e-01,1.664499566594332056e-02,3.185372749507320040e-03,3.090169943746289352e-02,-1.100000000000000006e-01,-6.134260438593320819e-01,-3.090169943746289352e-02,1.100000000000000006e-01,-7.465739561406680158e-01,8.457629772369162913e-02,-9.627040049785967613e-02,-3.291370886400958318e-01,1.542370227630838336e-02,1.237295995021403250e-01,-4.108629113599042149e-01
+-7.673188385153970406e-03,6.991592328519120603e-01,1.515302578486044799e-02,1.516888329904867161e-01,-2.725583435098910198e-03,-5.007475828906705617e-01,1.240306783858227679e-01,-8.177541401320632675e-01,-1.190744289965759567e-01,2.714130818282285418e-01,1.474786567659671158e-02,7.917428048787631496e-04,4.539904997392460451e-02,-1.100000000000000006e-01,-6.176295433068035301e-01,-4.539904997392460451e-02,1.100000000000000006e-01,-7.423704566931965676e-01,9.182144733692387817e-02,-9.871445703400560934e-02,-3.341476160849478072e-01,8.178552663076127383e-03,1.212855429659943918e-01,-4.058523839150521839e-01
+2.963590179860411261e-02,7.098632864869061088e-01,1.254818146291314385e-02,1.487310921673720698e-01,-2.728787781470151663e-02,-4.994660274918645837e-01,1.178014005988154284e-01,-7.809684223237601808e-01,-1.370588412564922864e-01,2.278042664175804755e-01,1.252216408641349844e-02,-1.026656369142738869e-03,5.877852522921950262e-02,-1.100000000000000006e-01,-6.233688103937395919e-01,-5.877852522921950262e-02,1.100000000000000006e-01,-7.366311896062605058e-01,9.803681411929487943e-02,-1.014364010925439957e-01,-3.400409482090285818e-01,1.963185880705133057e-03,1.185635989074560054e-01,-3.999590517909714094e-01
+6.161585822195991130e-02,7.103901144865956141e-01,9.217067175092064774e-03,1.416878746226550578e-01,-4.810022722826095415e-02,-4.917885642703662130e-01,1.146525911131247855e-01,-7.340487569098868015e-01,-1.545832616036148521e-01,1.832300851383915630e-01,1.002054977264515631e-02,-2.367965080444672712e-03,7.071067811863025743e-02,-1.100000000000000006e-01,-6.305025253169245225e-01,-7.071067811863025743e-02,1.100000000000000006e-01,-7.294974746830755752e-01,1.030693551130031776e-01,-1.043692093771393381e-01,-3.466719716165956311e-01,-3.069355113003172097e-03,1.156307906228606630e-01,-3.933280283834043600e-01
+8.723604095428656724e-02,7.018536152211658496e-01,5.483080761093052716e-03,1.314589164208061489e-01,-6.436012173373915901e-02,-4.787833981385306026e-01,1.151334353455683579e-01,-6.803817301686923003e-01,-1.715712081078745177e-01,1.398613826581358577e-01,7.290000459079631553e-03,-3.411449538233397513e-03,8.090169943747421710e-02,-1.100000000000000006e-01,-6.388550323395071340e-01,-8.090169943747421710e-02,1.100000000000000006e-01,-7.211449676604929637e-01,1.067951524567375687e-01,-1.074406664143921775e-01,-3.538774085042495354e-01,-6.795152456737556246e-03,1.125593335856078236e-01,-3.861225914957504557e-01
+1.053548694612746195e-01,6.854951399744597662e-01,1.678016517604169000e-03,1.190053900479358384e-01,-7.516005639096720592e-02,-4.615221586757199956e-01,1.200377521513016771e-01,-6.233272708743379242e-01,-1.880758526935910613e-01,9.974724695727078816e-02,4.369022085692636330e-03,-4.366040839592325203e-03,8.910065241882081377e-02,-1.100000000000000006e-01,-6.482206650182098517e-01,-8.910065241882081377e-02,1.100000000000000006e-01,-7.117793349817902460e-01,1.091224646546828381e-01,-1.105751427384638746e-01,-3.614798371023422163e-01,-9.122464654682825580e-03,1.094248572615361265e-01,-3.785201628976577748e-01
+1.146620808150848742e-01,6.625800878603123056e-01,-1.890103040914804496e-03,1.052190971445465667e-01,-7.943570573496790133e-02,-4.410041489839244822e-01,1.304791654639377296e-01,-5.658964679616454996e-01,-2.043186048996807058e-01,6.461523056278378752e-02,1.287435098146047030e-03,-5.419406970882917340e-03,9.510565162950440632e-02,-1.100000000000000006e-01,-6.583688103937301861e-01,-9.510565162950440632e-02,1.100000000000000006e-01,-7.016311896062699116e-01,1.099939855566192393e-01,-1.136954571395252661e-01,-3.692920603877747343e-01,-9.993985556619226773e-03,1.063045428604747350e-01,-3.707079396122253123e-01
+1.136141537209122698e-01,6.342675291553948602e-01,-4.987495030830260863e-03,9.083235139050174767e-02,-7.590858215731498271e-02,-4.180607698341803347e-01,1.479745070380876215e-01,-5.104581687393989764e-01,-2.207334564717215175e-01,3.567820158598251218e-02,-1.929766589095800646e-03,-6.698175941159552858e-03,9.876883405950813433e-02,-1.100000000000000006e-01,-6.690495874471589222e-01,-9.876883405950813433e-02,1.100000000000000006e-01,-6.909504125528411755e-01,1.093882554255290601e-01,-1.167247771212923946e-01,-3.771217154959768947e-01,-9.388255425529054565e-03,1.032752228787076065e-01,-3.628782845040230964e-01
+1.003892154378102364e-01,6.015091030975910913e-01,-7.536003586172558728e-03,7.639017382000141965e-02,-6.304935679359152667e-02,-3.932898026092811472e-01,1.745055716379758370e-01,-4.585879697261751597e-01,-2.380022910156507077e-01,1.353823766726950512e-02,-5.252174634715348067e-03,-8.248665217431406724e-03,1.000000000000000056e-01,-1.100000000000000006e-01,-6.799999999999746247e-01,-1.000000000000000056e-01,1.100000000000000006e-01,-6.800000000000254730e-01,1.073201893475427965e-01,-1.195885107720776885e-01,-3.847760103330496451e-01,-7.320189347542790936e-03,1.004114892279223126e-01,-3.552239896669503461e-01
+7.293045398966487014e-02,5.650199172975525208e-01,-9.739606996811363965e-03,6.227748628622298971e-02,-3.912876259710192095e-02,-3.670525667964681382e-01,2.124776593390320378e-01,-4.111058022736923112e-01,-2.570391413964916993e-01,-1.772078937278787850e-03,-8.624325639689066000e-03,-1.003981562872657482e-02,9.876883405951950023e-02,-1.100000000000000006e-01,-6.909504125527908824e-01,-9.876883405951950023e-02,1.100000000000000006e-01,-6.690495874472092153e-01,1.038407099730182526e-01,-1.222161434652116324e-01,-3.920664707569559426e-01,-3.840709973018240075e-03,9.778385653478836870e-02,-3.479335292430440485e-01
+2.922878092792044122e-02,5.253190287861421170e-01,-1.225311428517541004e-02,4.877165008305438948e-02,-2.497974193438556867e-03,-3.395273341131940792e-01,2.643954788336616568e-01,-3.682489008909295425e-01,-2.788295816935214000e-01,-1.064761765342429889e-02,-1.193481551186681942e-02,-1.198181587144063823e-02,9.510565162952676344e-02,-1.100000000000000006e-01,-7.016311896062218390e-01,-9.510565162952676344e-02,1.100000000000000006e-01,-6.583688103937782587e-01,9.903549363188619836e-02,-1.245429741631763482e-01,-3.988135814364083265e-01,9.645063681138002498e-04,9.545702583682365294e-02,-3.411864185635916646e-01
+-3.191699582440918337e-02,4.828051591285775768e-01,-1.631742097926534851e-02,3.609134982025487270e-02,4.768801171425604557e-02,-3.107876914954652015e-01,3.319682847510304069e-01,-3.298837045300082593e-01,-3.039753575646911843e-01,-1.374068819078387051e-02,-1.498012027512769968e-02,-1.395079121639205069e-02,8.910065241885364862e-02,-1.100000000000000006e-01,-7.117793349817451709e-01,-8.910065241885364862e-02,1.100000000000000006e-01,-6.482206650182549268e-01,9.302286069806403601e-02,-1.265117085718795720e-01,-4.048512061141020246e-01,6.977139301935962601e-03,9.348829142812041526e-02,-3.351487938858979665e-01
+-1.095522403408288464e-01,4.378336598937068169e-01,-2.363195766966015576e-02,2.442778464483335785e-02,1.102372783053356953e-01,-2.808774127908256202e-01,4.144794111094677880e-01,-2.956860640217055525e-01,-3.318676187595418492e-01,-1.181813277408215110e-02,-1.744878856002953296e-02,-1.581207081670095091e-02,8.090169943751673864e-02,-1.100000000000000006e-01,-7.211449676604519965e-01,-8.090169943751673864e-02,1.100000000000000006e-01,-6.388550323395481012e-01,8.595086214916712597e-02,-1.280738699163241900e-01,-4.100306784327448217e-01,1.404913785083287264e-02,9.192613008367579719e-02,-3.299693215672551694e-01
+-1.980260120083379705e-01,3.907770986532184687e-01,-3.546144753774527203e-02,1.395745259039650639e-02,1.798060562165669229e-01,-2.498681818960949153e-01,5.040411986080512996e-01,-2.652653009987868682e-01,-3.478089728115753565e-01,-5.665123502632870428e-03,-1.886183327923032782e-02,-1.743836329117780942e-02,7.071067811868163300e-02,-1.100000000000000006e-01,-7.294974746830396040e-01,-7.071067811868163300e-02,1.100000000000000006e-01,-6.305025253169604937e-01,7.799363406008702482e-02,-1.291909925996936603e-01,-4.142244625941685077e-01,2.200636593991297726e-02,9.080900740030632690e-02,-3.257755374058314835e-01
+-2.895443046002589838e-01,3.420655581768253795e-01,-5.160187264019521630e-02,4.841596824637313390e-03,2.492728734052042650e-01,-2.178979182517445934e-01,5.905773675885916951e-01,-2.382376078106197559e-01,-3.489874358007234445e-01,3.968751817778243957e-03,-1.860051970969462537e-02,-1.872202140058165654e-02,5.877852522927828893e-02,-1.100000000000000006e-01,-7.366311896062306408e-01,-5.877852522927828893e-02,1.100000000000000006e-01,-6.233688103937694569e-01,6.934710979490248117e-02,-1.298355693540058364e-01,-4.173292937139474468e-01,3.065289020509751397e-02,9.016443064599415080e-02,-3.226707062860525443e-01
+-3.793666227247690093e-01,2.922088815131102524e-01,-7.120691345991238264e-02,-2.782043068102819927e-03,3.145830796546221220e-01,-1.851921758806716611e-01,6.714023036866142435e-01,-2.142641032480029073e-01,-3.490610897375452382e-01,1.639386155513929827e-02,-1.703940665431014773e-02,-1.958198324588228748e-02,4.539904997398903908e-02,-1.100000000000000006e-01,-7.423704566931735860e-01,-4.539904997398903908e-02,1.100000000000000006e-01,-6.176295433068265117e-01,6.022419547719133626e-02,-1.299917285603419681e-01,-4.192687205455687405e-01,3.977580452280866236e-02,9.000827143965801913e-02,-3.207312794544312506e-01
+-4.622966703089888552e-01,2.418044428699110127e-01,-9.227356492621147099e-02,-8.810760645477718964e-03,3.717175438094411088e-01,-1.520718893938318161e-01,7.407176961219021916e-01,-1.930679167301966315e-01,-3.490656931085965309e-01,3.098756273251562776e-02,-1.457753668248639757e-02,-1.996643096950633314e-02,3.090169943753167184e-02,-1.100000000000000006e-01,-7.465739561406523617e-01,-3.090169943753167184e-02,1.100000000000000006e-01,-6.134260438593477360e-01,5.084952753467237435e-02,-1.296556250607793226e-01,-4.199949879638493200e-01,4.915047246532762426e-02,9.034437493922066464e-02,-3.200050120361506711e-01
+-5.348385334531952084e-01,1.915338529942971768e-01,-1.124415214075820402e-01,-1.318858593751052674e-02,4.184620240910358890e-01,-1.189504629204498343e-01,7.942577162623570830e-01,-1.744406738136183854e-01,-3.490659808192872471e-01,4.719277263850605447e-02,-1.166413896012859913e-02,-1.985221780112865139e-02,1.564344650406170045e-02,-1.100000000000000006e-01,-7.491381838416554251e-01,-1.564344650406170045e-02,1.100000000000000006e-01,-6.108618161583446726e-01,4.145394140482952516e-02,-1.288355348389407240e-01,-4.194902128546077469e-01,5.854605859517046651e-02,9.116446516105926323e-02,-3.205097871453922442e-01
+-5.953693400279238546e-01,1.421519329443272639e-01,-1.297194457235563148e-01,-1.591602986309920142e-02,4.543397535388267738e-01,-8.632316183593899406e-02,8.301158477194310326e-01,-1.582451059999211984e-01,-3.490659988012054238e-01,6.451373185722669712e-02,-8.703821904373632012e-03,-1.924197278445514969e-02,3.971685249655311529e-14,-1.100000000000000006e-01,-7.500000000000000000e-01,-3.971685249655311529e-14,1.100000000000000006e-01,-6.100000000000000977e-01,3.226878760034235238e-02,-1.275516512378112588e-01,-4.177668244562861566e-01,6.773121239965763929e-02,9.244834876218872843e-02,-3.222331755437138345e-01
+-6.433256773731811373e-01,9.447163462320419536e-02,-1.426945809658245190e-01,-1.705646484153895692e-02,4.797609735116572516e-01,-5.475217720659095871e-02,8.476869101482898960e-01,-1.444180509880225727e-01,-3.459210837709622566e-01,8.251230611387933012e-02,-5.985677071246164362e-03,-1.815963020596327721e-02,-1.564344650398359626e-02,-1.100000000000000006e-01,-7.491381838416640848e-01,1.564344650398359626e-02,1.100000000000000006e-01,-6.108618161583360129e-01,2.352023509165466347e-02,-1.258355877326160499e-01,-4.148672583108492518e-01,7.647976490834533514e-02,9.416441226738393733e-02,-3.251327416891507394e-01
+-6.773332858453451344e-01,4.934908311165220329e-02,-1.498575406396699394e-01,-1.673834903915582401e-02,4.945905135244688111e-01,-2.485129274920799824e-02,8.412338040721011323e-01,-1.329767390243138392e-01,-3.118859117683053794e-01,1.008067836223253411e-01,-3.185372749508426360e-03,-1.664499566594408730e-02,-3.090169943745646117e-02,-1.100000000000000006e-01,-7.465739561406694591e-01,3.090169943745646117e-02,1.100000000000000006e-01,-6.134260438593306386e-01,1.542370227631169322e-02,-1.237295995021413103e-01,-4.108629113599061577e-01,8.457629772368829846e-02,9.627040049785869080e-02,-3.291370886400938334e-01
+-6.991592328519050659e-01,7.673188385171078249e-03,-1.516888329904869936e-01,-1.515302578486135004e-02,5.007475828906694515e-01,2.725583435087592862e-03,8.177541401320763681e-01,-1.240306783858260570e-01,-2.714130818282460833e-01,1.190744289965676994e-01,-7.917428048796500270e-04,-1.474786567659762057e-02,-4.539904997391858155e-02,-1.100000000000000006e-01,-7.423704566931986770e-01,4.539904997391858155e-02,1.100000000000000006e-01,-6.176295433068014207e-01,8.178552663079027840e-03,-1.212855429659955020e-01,-4.058523839150545154e-01,9.182144733692096383e-02,9.871445703400449911e-02,-3.341476160849454202e-01
+-7.098632864869038883e-01,-2.963590179858993992e-02,-1.487310921673742625e-01,-1.254818146291435295e-02,4.994660274918663601e-01,2.728787781469199647e-02,7.809684223237777223e-01,-1.178014005988174684e-01,-2.278042664175991550e-01,1.370588412564855696e-01,1.026656369142097455e-03,-1.252216408641333885e-02,-5.877852522921431927e-02,-1.100000000000000006e-01,-7.366311896062631703e-01,5.877852522921431927e-02,1.100000000000000006e-01,-6.233688103937369274e-01,1.963185880707429831e-03,-1.185635989074571572e-01,-3.999590517909739629e-01,9.803681411929257572e-02,1.014364010925428439e-01,-3.400409482090260282e-01
+-7.103901144865973905e-01,-6.161585822194742823e-02,-1.416878746226587771e-01,-9.217067175093567044e-03,4.917885642703707649e-01,4.810022722825289809e-02,7.340487569099086729e-01,-1.146525911131254100e-01,-1.832300851384106033e-01,1.545832616036074136e-01,2.367965080444118034e-03,-1.002054977264624572e-02,-7.071067811862546959e-02,-1.100000000000000006e-01,-7.294974746830789059e-01,7.071067811862546959e-02,1.100000000000000006e-01,-6.305025253169211918e-01,-3.069355113001277779e-03,-1.156307906228619675e-01,-3.933280283834073576e-01,1.030693551130012764e-01,1.043692093771380336e-01,-3.466719716165926335e-01
+-7.018536152211711787e-01,-8.723604095427700544e-02,-1.314589164208110061e-01,-5.483080761094635651e-03,4.787833981385371529e-01,6.436012173373320544e-02,6.803817301687161700e-01,-1.151334353455674281e-01,-1.398613826581538155e-01,1.715712081078674955e-01,3.411449538232959062e-03,-7.290000459080776471e-03,-8.090169943747024806e-02,-1.100000000000000006e-01,-7.211449676604967385e-01,8.090169943747024806e-02,1.100000000000000006e-01,-6.388550323395033592e-01,-6.795152456736251734e-03,-1.125593335856091698e-01,-3.861225914957536753e-01,1.067951524567362503e-01,1.074406664143908313e-01,-3.538774085042463158e-01
+-6.854951399744679819e-01,-1.053548694612685827e-01,-1.190053900479417365e-01,-1.678016517605735239e-03,4.615221586757290995e-01,7.516005639096386137e-02,6.233272708743627932e-01,-1.200377521512985129e-01,-9.974724695728875989e-02,1.880758526935840669e-01,4.366040839592300916e-03,-4.369022085693886198e-03,-8.910065241881776066e-02,-1.100000000000000006e-01,-7.117793349817944648e-01,8.910065241881776066e-02,1.100000000000000006e-01,-6.482206650182056329e-01,-9.122464654682138629e-03,-1.094248572615374865e-01,-3.785201628976611055e-01,1.091224646546821442e-01,1.105751427384625146e-01,-3.614798371023388857e-01
+-6.625800878603231858e-01,-1.146620808150830145e-01,-1.052190971445526868e-01,1.890103040913367928e-03,4.410041489839338080e-01,7.943570573496769316e-02,5.658964679616697024e-01,-1.304791654639316789e-01,-6.461523056279745714e-02,2.043186048996734339e-01,5.419406970882381311e-03,-1.287435098147346555e-03,-9.510565162950232465e-02,-1.100000000000000006e-01,-7.016311896062744635e-01,9.510565162950232465e-02,1.100000000000000006e-01,-6.583688103937256342e-01,-9.993985556619171262e-03,-1.063045428604760673e-01,-3.707079396122286430e-01,1.099939855566191838e-01,1.136954571395239338e-01,-3.692920603877713481e-01
+-6.342675291554070727e-01,-1.136141537209152119e-01,-9.083235139050757634e-02,4.987495030829096863e-03,4.180607698341899936e-01,7.590858215731836889e-02,5.104581687394206257e-01,-1.479745070380786010e-01,-3.567820158599288582e-02,2.207334564717145231e-01,6.698175941158996879e-03,1.929766589094419373e-03,-9.876883405950713513e-02,-1.100000000000000006e-01,-6.909504125528456164e-01,9.876883405950713513e-02,1.100000000000000006e-01,-6.690495874471544813e-01,-9.388255425529602738e-03,-1.032752228787088139e-01,-3.628782845040262606e-01,1.093882554255296152e-01,1.167247771212911872e-01,-3.771217154959737305e-01
+-6.015091030976058573e-01,-1.003892154378188406e-01,-7.639017382000765077e-02,7.536003586171541313e-03,3.932898026092921939e-01,6.304935679359950640e-02,4.585879697261966981e-01,-1.745055716379621535e-01,-1.353823766727761668e-02,2.380022910156439908e-01,8.248665217430655588e-03,5.252174634714119016e-03,-1.000000000000000056e-01,-1.100000000000000006e-01,-6.800000000000302469e-01,1.000000000000000056e-01,1.100000000000000006e-01,-6.799999999999698508e-01,-7.320189347543984426e-03,-1.004114892279235061e-01,-3.552239896669535657e-01,1.073201893475439900e-01,1.195885107720764950e-01,-3.847760103330464254e-01
+-5.650199172975689521e-01,-7.293045398968014958e-02,-6.227748628622897797e-02,9.739606996810408132e-03,3.670525667964797401e-01,3.912876259711461913e-02,4.111058022737115736e-01,-2.124776593390128310e-01,1.772078937273787510e-03,2.570391413964832616e-01,1.003981562872577858e-02,8.624325639687926287e-03,-9.876883405952056882e-02,-1.100000000000000006e-01,-6.690495874472138782e-01,9.876883405952056882e-02,1.100000000000000006e-01,-6.909504125527862195e-01,-3.840709973020030310e-03,-9.778385653478945116e-02,-3.479335292430470461e-01,1.038407099730200428e-01,1.222161434652105499e-01,-3.920664707569529450e-01
+-5.253190287861598806e-01,-2.922878092794305854e-02,-4.877165008306011407e-02,1.225311428517410900e-02,3.395273341132062361e-01,2.497974193457271064e-03,3.682489008909471395e-01,-2.643954788336358996e-01,1.064761765342172803e-02,2.788295816935113525e-01,1.198181587143973444e-02,1.193481551186543685e-02,-9.510565162952884510e-02,-1.100000000000000006e-01,-6.583688103937828107e-01,9.510565162952884510e-02,1.100000000000000006e-01,-7.016311896062172870e-01,9.645063681114687815e-04,-9.545702583682458275e-02,-3.411864185635944402e-01,9.903549363188854371e-02,1.245429741631754184e-01,-3.988135814364055509e-01
+-4.828051591285971167e-01,3.191699582437926286e-02,-3.609134982026027810e-02,1.631742097926306909e-02,3.107876914954782466e-01,-4.768801171423184965e-02,3.298837045300248572e-01,-3.319682847509982659e-01,1.374068819078319223e-02,3.039753575646796935e-01,1.395079121639118333e-02,1.498012027512648711e-02,-8.910065241885672949e-02,-1.100000000000000006e-01,-6.482206650182591456e-01,8.910065241885672949e-02,1.100000000000000006e-01,-7.117793349817409521e-01,6.977139301933138471e-03,-9.348829142812116466e-02,-3.351487938859004090e-01,9.302286069806703361e-02,1.265117085718788226e-01,-4.048512061140994711e-01
+-4.378336598937289104e-01,1.095522403407925144e-01,-2.442778464483860018e-02,2.363195766965603753e-02,2.808774127908399976e-01,-1.102372783053067185e-01,2.956860640217220948e-01,-4.144794111094299294e-01,1.181813277408351980e-02,3.318676187595297478e-01,1.581207081670005579e-02,1.744878856002869683e-02,-8.090169943752070769e-02,-1.100000000000000006e-01,-6.388550323395518760e-01,8.090169943752070769e-02,1.100000000000000006e-01,-7.211449676604482217e-01,1.404913785082963218e-02,-9.192613008367638006e-02,-3.299693215672572233e-01,8.595086214917072032e-02,1.280738699163236072e-01,-4.100306784327425458e-01
+-3.907770986532406732e-01,1.980260120082990294e-01,-1.395745259040109473e-02,3.546144753773922825e-02,2.498681818961096257e-01,-1.798060562165368359e-01,2.652653009988013566e-01,-5.040411986080134410e-01,5.665123502635503738e-03,3.478089728115738577e-01,1.743836329117708431e-02,1.886183327923013700e-02,-7.071067811868642083e-02,-1.100000000000000006e-01,-6.305025253169639354e-01,7.071067811868642083e-02,1.100000000000000006e-01,-7.294974746830361623e-01,2.200636593990939333e-02,-9.080900740030671547e-02,-3.257755374058330378e-01,7.799363406009099386e-02,1.291909925996932718e-01,-4.142244625941667868e-01
+-3.420655581768476394e-01,2.895443046002195708e-01,-4.841596824641158404e-03,5.160187264018746556e-02,2.178979182517591651e-01,-2.492728734051751216e-01,2.382376078106319683e-01,-5.905773675885552798e-01,-3.968751817773893270e-03,3.489874358007233335e-01,1.872202140058103204e-02,1.860051970969505905e-02,-5.877852522928376372e-02,-1.100000000000000006e-01,-6.233688103937722325e-01,5.877852522928376372e-02,1.100000000000000006e-01,-7.366311896062278652e-01,3.065289020509368023e-02,-9.016443064599431734e-02,-3.226707062860536546e-01,6.934710979490653349e-02,1.298355693540056699e-01,-4.173292937139462810e-01
+-2.922088815131319017e-01,3.793666227247313727e-01,2.782043068099850081e-03,7.120691345990340371e-02,1.851921758806857332e-01,-3.145830796545953656e-01,2.142641032480126217e-01,-6.714023036865812699e-01,-1.639386155513342103e-02,3.490610897375451827e-01,1.958198324588193012e-02,1.703940665431108795e-02,-4.539904997399506897e-02,-1.100000000000000006e-01,-6.176295433068287322e-01,4.539904997399506897e-02,1.100000000000000006e-01,-7.423704566931713655e-01,3.977580452280467249e-02,-9.000827143965799138e-02,-3.207312794544318058e-01,6.022419547719534694e-02,1.299917285603419959e-01,-4.192687205455681854e-01
+-2.418044428699336057e-01,4.622966703089552709e-01,8.810760645475439537e-03,9.227356492620249206e-02,1.520718893938464988e-01,-3.717175438094186823e-01,1.930679167302061516e-01,-7.407176961218753242e-01,-3.098756273250936888e-02,3.490656931085965309e-01,1.996643096950634702e-02,1.457753668248758065e-02,-3.090169943753810072e-02,-1.100000000000000006e-01,-6.134260438593491793e-01,3.090169943753810072e-02,1.100000000000000006e-01,-7.465739561406509184e-01,4.915047246532357889e-02,-9.034437493922041484e-02,-3.200050120361507267e-01,5.084952753467664871e-02,1.296556250607795724e-01,-4.199949879638492645e-01
+-1.915338529943206858e-01,5.348385334531668978e-01,1.318858593750884753e-02,1.124415214075740188e-01,1.189504629204658076e-01,-4.184620240910184585e-01,1.744406738136282942e-01,-7.942577162623382092e-01,-4.719277263850209236e-02,3.490659808192872471e-01,1.985221780112969223e-02,1.166413896012977180e-02,-1.564344650406837914e-02,-1.100000000000000006e-01,-6.108618161583454498e-01,1.564344650406837914e-02,1.100000000000000006e-01,-7.491381838416546479e-01,5.854605859516645583e-02,-9.116446516105881914e-02,-3.205097871453917446e-01,4.145394140483397993e-02,1.288355348389411681e-01,-4.194902128546083020e-01
+-1.421519329443476642e-01,5.953693400279017611e-01,1.591602986309842080e-02,1.297194457235500975e-01,8.632316183595234449e-02,-4.543397535388142838e-01,1.582451059999280540e-01,-8.301158477194201524e-01,-6.451373185722039660e-02,3.490659988012054238e-01,1.924197278445550705e-02,8.703821904374893156e-03,-4.612398358638549047e-14,-1.100000000000000006e-01,-6.100000000000000977e-01,4.612398358638549047e-14,1.100000000000000006e-01,-7.500000000000000000e-01,6.773121239965397555e-02,-9.244834876218811781e-02,-3.222331755437128908e-01,3.226878760034623816e-02,1.275516512378118694e-01,-4.177668244562871558e-01
+-9.447163462322508143e-02,6.433256773731639289e-01,1.705646484153880080e-02,1.426945809658203557e-01,5.475217720660412180e-02,-4.797609735116488694e-01,1.444180509880289842e-01,-8.476869101482878976e-01,-8.251230611387219693e-02,3.459210837709741360e-01,1.815963020596380109e-02,5.985677071247254635e-03,1.564344650397691758e-02,-1.100000000000000006e-01,-6.108618161583352357e-01,-1.564344650397691758e-02,1.100000000000000006e-01,-7.491381838416648620e-01,7.647976490834169916e-02,-9.416441226738310466e-02,-3.251327416891491850e-01,2.352023509165850415e-02,1.258355877326168826e-01,-4.148672583108508616e-01
+-4.934908311167091055e-02,6.773332858453333660e-01,1.673834903915621952e-02,1.498575406396680521e-01,2.485129274922027315e-02,-4.945905135244645368e-01,1.329767390243180580e-01,-8.412338040721079047e-01,-1.008067836223165425e-01,3.118859117683216997e-01,1.664499566594430588e-02,3.185372749509652809e-03,3.090169943745003228e-02,-1.100000000000000006e-01,-6.134260438593290843e-01,-3.090169943745003228e-02,1.100000000000000006e-01,-7.465739561406710134e-01,8.457629772368499554e-02,-9.627040049785770548e-02,-3.291370886400918905e-01,1.542370227631501695e-02,1.237295995021422956e-01,-4.108629113599081006e-01
+-7.673188385188914676e-03,6.991592328518980715e-01,1.515302578486228680e-02,1.516888329904872157e-01,-2.725583435075834907e-03,-5.007475828906683413e-01,1.240306783858302758e-01,-8.177541401320892467e-01,-1.190744289965603581e-01,2.714130818282643465e-01,1.474786567659850701e-02,7.917428048805096909e-04,4.539904997391255859e-02,-1.100000000000000006e-01,-6.176295433067993113e-01,-4.539904997391255859e-02,1.100000000000000006e-01,-7.423704566932007864e-01,9.182144733691806338e-02,-9.871445703400337501e-02,-3.341476160849430888e-01,8.178552663082094831e-03,1.212855429659966261e-01,-4.058523839150570134e-01
+2.963590179857365781e-02,7.098632864869015568e-01,1.254818146291566440e-02,1.487310921673765107e-01,-2.728787781468132792e-02,-4.994660274918683585e-01,1.178014005988208823e-01,-7.809684223237961520e-01,-1.370588412564779091e-01,2.278042664176178622e-01,1.252216408641435366e-02,-1.026656369141470135e-03,5.877852522920884448e-02,-1.100000000000000006e-01,-6.233688103937341518e-01,-5.877852522920884448e-02,1.100000000000000006e-01,-7.366311896062659459e-01,9.803681411929013323e-02,-1.014364010925416226e-01,-3.400409482090233082e-01,1.963185880710122122e-03,1.185635989074583785e-01,-3.999590517909769605e-01
+6.161585822193509782e-02,7.103901144865991668e-01,9.217067175095074519e-03,1.416878746226624686e-01,-4.810022722824427999e-02,-4.917885642703750948e-01,1.146525911131266312e-01,-7.340487569099296561e-01,-1.545832616036004470e-01,1.832300851384290885e-01,1.002054977264879576e-02,-2.367965080443630143e-03,7.071067811862094543e-02,-1.100000000000000006e-01,-6.305025253169180832e-01,-7.071067811862094543e-02,1.100000000000000006e-01,-7.294974746830820145e-01,1.030693551129995000e-01,-1.043692093771368123e-01,-3.466719716165898024e-01,-3.069355112999383461e-03,1.156307906228631888e-01,-3.933280283834103552e-01
+8.723604095426705507e-02,7.018536152211766188e-01,5.483080761096353027e-03,1.314589164208158911e-01,-6.436012173372700207e-02,-4.787833981385434812e-01,1.151334353455669007e-01,-6.803817301687400398e-01,-1.715712081078604179e-01,1.398613826581720232e-01,7.290000459082061901e-03,-3.411449538232562244e-03,8.090169943746627901e-02,-1.100000000000000006e-01,-6.388550323394994734e-01,-8.090169943746627901e-02,1.100000000000000006e-01,-7.211449676605006243e-01,1.067951524567349458e-01,-1.074406664143894991e-01,-3.538774085042430961e-01,-6.795152456734870894e-03,1.125593335856105021e-01,-3.861225914957570615e-01
+1.053548694612626152e-01,6.854951399744767526e-01,1.678016517607390165e-03,1.190053900479472460e-01,-7.516005639096055846e-02,-4.615221586757364269e-01,1.200377521512952378e-01,-6.233272708743876622e-01,-1.880758526935769059e-01,9.974724695730335933e-02,4.369022085695232344e-03,-4.366040839591474321e-03,8.910065241881467979e-02,-1.100000000000000006e-01,-6.482206650182014140e-01,-8.910065241881467979e-02,1.100000000000000006e-01,-7.117793349817986837e-01,1.091224646546814503e-01,-1.105751427384611685e-01,-3.614798371023355550e-01,-9.122464654681444740e-03,1.094248572615388326e-01,-3.785201628976644361e-01
+1.146620808150809190e-01,6.625800878603343991e-01,-1.890103040911975596e-03,1.052190971445587930e-01,-7.943570573496724907e-02,-4.410041489839431894e-01,1.304791654639261556e-01,-5.658964679616943494e-01,-2.043186048996667725e-01,6.461523056281151534e-02,1.287435098148684027e-03,-5.419406970881889517e-03,9.510565162950022911e-02,-1.100000000000000006e-01,-6.583688103937210823e-01,-9.510565162950022911e-02,1.100000000000000006e-01,-7.016311896062790154e-01,1.099939855566191144e-01,-1.136954571395226155e-01,-3.692920603877679619e-01,-9.993985556619108812e-03,1.063045428604773857e-01,-3.707079396122322512e-01
+1.136141537209181818e-01,6.342675291554203953e-01,-4.987495030827899037e-03,9.083235139051386298e-02,-7.590858215732179670e-02,-4.180607698342003742e-01,1.479745070380693306e-01,-5.104581687394439404e-01,-2.207334564717075287e-01,3.567820158600393948e-02,-1.929766589093028992e-03,-6.698175941158377583e-03,9.876883405950608041e-02,-1.100000000000000006e-01,-6.690495874471498183e-01,-9.876883405950608041e-02,1.100000000000000006e-01,-6.909504125528502794e-01,1.093882554255301842e-01,-1.167247771212899243e-01,-3.771217154959703444e-01,-9.388255425530241116e-03,1.032752228787100768e-01,-3.628782845040299798e-01
+1.003892154378275697e-01,6.015091030976198461e-01,-7.536003586170605430e-03,7.639017382001342393e-02,-6.304935679360736123e-02,-3.932898026093025190e-01,1.745055716379483590e-01,-4.585879697262166821e-01,-2.380022910156362193e-01,1.353823766728506905e-02,-5.252174634712693073e-03,-8.248665217429963434e-03,1.000000000000000056e-01,-1.100000000000000006e-01,-6.799999999999654099e-01,-1.000000000000000056e-01,1.100000000000000006e-01,-6.800000000000346878e-01,1.073201893475451280e-01,-1.195885107720753709e-01,-3.847760103330433723e-01,-7.320189347545184855e-03,1.004114892279246302e-01,-3.552239896669567853e-01
+7.293045398969588700e-02,5.650199172975852724e-01,-9.739606996809521688e-03,6.227748628623489685e-02,-3.912876259712791405e-02,-3.670525667964912309e-01,2.124776593389929857e-01,-4.111058022737311690e-01,-2.570391413964743244e-01,-1.772078937268505711e-03,-8.624325639686465650e-03,-1.003981562872493204e-02,9.876883405952162354e-02,-1.100000000000000006e-01,-6.909504125527815566e-01,-9.876883405952162354e-02,1.100000000000000006e-01,-6.690495874472185411e-01,1.038407099730218330e-01,-1.222161434652095369e-01,-3.920664707569498919e-01,-3.840709973021917689e-03,9.778385653479046424e-02,-3.479335292430502657e-01
+2.922878092796556138e-02,5.253190287861784213e-01,-1.225311428517276979e-02,4.877165008306594968e-02,-2.497974193475957505e-03,-3.395273341132187817e-01,2.643954788336104200e-01,-3.682489008909655137e-01,-2.788295816935015270e-01,-1.064761765341888135e-02,-1.193481551186406815e-02,-1.198181587143884279e-02,9.510565162953094065e-02,-1.100000000000000006e-01,-7.016311896062128461e-01,-9.510565162953094065e-02,1.100000000000000006e-01,-6.583688103937872516e-01,9.903549363189100008e-02,-1.245429741631744885e-01,-3.988135814364026088e-01,9.645063681091234353e-04,9.545702583682551257e-02,-3.411864185635972158e-01
+-3.191699582434820437e-02,4.828051591286153243e-01,-1.631742097926064047e-02,3.609134982026541982e-02,4.768801171420655738e-02,-3.107876914954905700e-01,3.319682847509642931e-01,-3.298837045300395676e-01,-3.039753575646675365e-01,-1.374068819078345417e-02,-1.498012027512519648e-02,-1.395079121639037842e-02,8.910065241885978260e-02,-1.100000000000000006e-01,-7.117793349817367332e-01,-8.910065241885978260e-02,1.100000000000000006e-01,-6.482206650182633645e-01,9.302286069806969815e-02,-1.265117085718780177e-01,-4.048512061140971952e-01,6.977139301930147808e-03,9.348829142812196957e-02,-3.351487938859029625e-01
+-1.095522403407540174e-01,4.378336598937478397e-01,-2.363195766965178746e-02,2.442778464484329434e-02,1.102372783052760208e-01,-2.808774127908527651e-01,4.144794111093892952e-01,-2.956860640217350844e-01,-3.318676187595163696e-01,-1.181813277408532738e-02,-1.744878856002777395e-02,-1.581207081669926823e-02,8.090169943752467674e-02,-1.100000000000000006e-01,-7.211449676604443360e-01,-8.090169943752467674e-02,1.100000000000000006e-01,-6.388550323395557617e-01,8.595086214917380119e-02,-1.280738699163230243e-01,-4.100306784327406584e-01,1.404913785082603783e-02,9.192613008367696292e-02,-3.299693215672594437e-01
+-1.980260120082569797e-01,3.907770986532606017e-01,-3.546144753773271957e-02,1.395745259040513837e-02,1.798060562165042786e-01,-2.498681818961225320e-01,5.040411986079719187e-01,-2.652653009988125699e-01,-3.478089728115721369e-01,-5.665123502639375641e-03,-1.886183327922987332e-02,-1.743836329117644940e-02,7.071067811869120867e-02,-1.100000000000000006e-01,-7.294974746830328316e-01,-7.071067811869120867e-02,1.100000000000000006e-01,-6.305025253169672661e-01,7.799363406009438004e-02,-1.291909925996929109e-01,-4.142244625941652880e-01,2.200636593990542428e-02,9.080900740030709017e-02,-3.257755374058347586e-01
+-2.895443046001815457e-01,3.420655581768677345e-01,-5.160187264017982584e-02,4.841596824644555860e-03,2.492728734051465334e-01,-2.178979182517722935e-01,5.905773675885199747e-01,-2.382376078106421546e-01,-3.489874358007232225e-01,3.968751817769207782e-03,-1.860051970969539212e-02,-1.872202140058061223e-02,5.877852522928894707e-02,-1.100000000000000006e-01,-7.366311896062252007e-01,-5.877852522928894707e-02,1.100000000000000006e-01,-6.233688103937748970e-01,6.934710979491016947e-02,-1.298355693540055034e-01,-4.173292937139452263e-01,3.065289020509003384e-02,9.016443064599448387e-02,-3.226707062860547093e-01
+-3.793666227246940692e-01,2.922088815131543837e-01,-7.120691345989454968e-02,-2.782043068096802171e-03,3.145830796545688313e-01,-1.851921758807003882e-01,6.714023036865489624e-01,-2.142641032480233632e-01,-3.490610897375451827e-01,1.639386155512803644e-02,-1.703940665431194490e-02,-1.958198324588165604e-02,4.539904997400109193e-02,-1.100000000000000006e-01,-7.423704566931692561e-01,-4.539904997400109193e-02,1.100000000000000006e-01,-6.176295433068308416e-01,6.022419547719954497e-02,-1.299917285603420514e-01,-4.192687205455675747e-01,3.977580452280066181e-02,9.000827143965794974e-02,-3.207312794544324164e-01
+-4.622966703089209095e-01,2.418044428699537562e-01,-9.227356492619323558e-02,-8.810760645473319705e-03,3.717175438093958117e-01,-1.520718893938598215e-01,7.407176961218466804e-01,-1.930679167302137289e-01,-3.490656931085965309e-01,3.098756273250359225e-02,-1.457753668248886955e-02,-1.996643096950622906e-02,3.090169943754419654e-02,-1.100000000000000006e-01,-7.465739561406495861e-01,-3.090169943754419654e-02,1.100000000000000006e-01,-6.134260438593505116e-01,5.084952753468048592e-02,-1.296556250607798222e-01,-4.199949879638492645e-01,4.915047246531929759e-02,9.034437493922017892e-02,-3.200050120361507267e-01
+-5.348385334531361446e-01,1.915338529943411694e-01,-1.124415214075652064e-01,-1.318858593750741465e-02,4.184620240909993627e-01,-1.189504629204788527e-01,7.942577162623164488e-01,-1.744406738136344837e-01,-3.490659808192872471e-01,4.719277263849162157e-02,-1.166413896013117520e-02,-1.985221780112900181e-02,1.564344650407506129e-02,-1.100000000000000006e-01,-7.491381838416539818e-01,-1.564344650407506129e-02,1.100000000000000006e-01,-6.108618161583461159e-01,4.145394140483776857e-02,-1.288355348389416399e-01,-4.194902128546087461e-01,5.854605859516201494e-02,9.116446516105836118e-02,-3.205097871453911895e-01
+-5.953693400278758929e-01,1.421519329443699797e-01,-1.297194457235426868e-01,-1.591602986309754650e-02,4.543397535387995734e-01,-8.632316183596723536e-02,8.301158477194064966e-01,-1.582451059999351317e-01,-3.490659988012054793e-01,6.451373185721193115e-02,-8.703821904376182056e-03,-1.924197278445595807e-02,5.324165741197795701e-14,-1.100000000000000006e-01,-7.500000000000000000e-01,-5.324165741197795701e-14,1.100000000000000006e-01,-6.100000000000000977e-01,3.226878760035030436e-02,-1.275516512378125633e-01,-4.177668244562882105e-01,6.773121239964949303e-02,9.244834876218743780e-02,-3.222331755437117251e-01
+-6.433256773731469425e-01,9.447163462324405236e-02,-1.426945809658161368e-01,-1.705646484153861692e-02,4.797609735116404872e-01,-5.475217720661731957e-02,8.476869101482852331e-01,-1.444180509880340635e-01,-3.459210837709849606e-01,8.251230611386438374e-02,-5.985677071248157559e-03,-1.815963020596439784e-02,-1.564344650397058931e-02,-1.100000000000000006e-01,-7.491381838416655281e-01,1.564344650397058931e-02,1.100000000000000006e-01,-6.108618161583345696e-01,2.352023509166194584e-02,-1.258355877326176597e-01,-4.148672583108522494e-01,7.647976490833824359e-02,9.416441226738232750e-02,-3.251327416891477973e-01
+-6.773332858453214866e-01,4.934908311169048517e-02,-1.498575406396662202e-01,-1.673834903915664973e-02,4.945905135244602069e-01,-2.485129274923319684e-02,8.412338040721152321e-01,-1.329767390243234149e-01,-3.118859117683382975e-01,1.008067836223090485e-01,-3.185372749510738313e-03,-1.664499566594505181e-02,-3.090169943744359993e-02,-1.100000000000000006e-01,-7.465739561406724567e-01,3.090169943744359993e-02,1.100000000000000006e-01,-6.134260438593276410e-01,1.542370227631850027e-02,-1.237295995021432810e-01,-4.108629113599101546e-01,8.457629772368166488e-02,9.627040049785672016e-02,-3.291370886400899476e-01
+-6.991592328518911881e-01,7.673188385204841172e-03,-1.516888329904874377e-01,-1.515302578486314028e-02,5.007475828906673421e-01,2.725583435065324217e-03,8.177541401321016812e-01,-1.240306783858332040e-01,-2.714130818282822766e-01,1.190744289965535996e-01,-7.917428048814937128e-04,-1.474786567659925815e-02,-4.539904997390684094e-02,-1.100000000000000006e-01,-7.423704566932028959e-01,4.539904997390684094e-02,1.100000000000000006e-01,-6.176295433067972018e-01,8.178552663084842633e-03,-1.212855429659976808e-01,-4.058523839150592338e-01,9.182144733691499638e-02,9.871445703400232030e-02,-3.341476160849405908e-01
+-7.098632864868988923e-01,-2.963590179855928736e-02,-1.487310921673785646e-01,-1.254818146291696197e-02,4.994660274918701348e-01,2.728787781467191531e-02,7.809684223238135825e-01,-1.178014005988222423e-01,-2.278042664176367638e-01,1.370588412564701097e-01,1.026656369140745671e-03,-1.252216408641540317e-02,-5.877852522920337663e-02,-1.100000000000000006e-01,-7.366311896062687214e-01,5.877852522920337663e-02,1.100000000000000006e-01,-6.233688103937313763e-01,1.963185880712425835e-03,-1.185635989074595997e-01,-3.999590517909795140e-01,9.803681411928744094e-02,1.014364010925404014e-01,-3.400409482090203106e-01
+-7.103901144866007211e-01,-6.161585822192193473e-02,-1.416878746226662711e-01,-9.217067175096699955e-03,4.917885642703796467e-01,4.810022722823644598e-02,7.340487569099520826e-01,-1.146525911131273112e-01,-1.832300851384482121e-01,1.545832616035927864e-01,2.367965080443148324e-03,-1.002054977264851994e-02,-7.071067811861590779e-02,-1.100000000000000006e-01,-7.294974746830855672e-01,7.071067811861590779e-02,1.100000000000000006e-01,-6.305025253169145305e-01,-3.069355112997391999e-03,-1.156307906228645627e-01,-3.933280283834134639e-01,1.030693551129972935e-01,1.043692093771354384e-01,-3.466719716165863607e-01
+-7.018536152211816148e-01,-8.723604095425806226e-02,-1.314589164208205818e-01,-5.483080761097917748e-03,4.787833981385498650e-01,6.436012173372145095e-02,6.803817301687627994e-01,-1.151334353455659015e-01,-1.398613826581889263e-01,1.715712081078537288e-01,3.411449538232109481e-03,-7.290000459083212023e-03,-8.090169943746250425e-02,-1.100000000000000006e-01,-7.211449676605041770e-01,8.090169943746250425e-02,1.100000000000000006e-01,-6.388550323394959207e-01,-6.795152456733635771e-03,-1.125593335856117788e-01,-3.861225914957600591e-01,1.067951524567337107e-01,1.074406664143882223e-01,-3.538774085042400985e-01
+-6.854951399744853013e-01,-1.053548694612563147e-01,-1.190053900479528387e-01,-1.678016517609037285e-03,4.615221586757446426e-01,7.516005639095700575e-02,6.233272708744125312e-01,-1.200377521512923373e-01,-9.974724695731974899e-02,1.880758526935701058e-01,4.366040839591146458e-03,-4.369022085696556805e-03,-8.910065241881161280e-02,-1.100000000000000006e-01,-7.117793349818029025e-01,8.910065241881161280e-02,1.100000000000000006e-01,-6.482206650181971952e-01,-9.122464654680716156e-03,-1.094248572615401927e-01,-3.785201628976679333e-01,1.091224646546807564e-01,1.105751427384598085e-01,-3.614798371023322243e-01
+-6.625800878603458344e-01,-1.146620808150791981e-01,-1.052190971445649409e-01,1.890103040910567651e-03,4.410041489839527373e-01,7.943570573496709641e-02,5.658964679617187743e-01,-1.304791654639204934e-01,-6.461523056282537925e-02,2.043186048996601389e-01,5.419406970881452366e-03,-1.287435098149969891e-03,-9.510565162949824458e-02,-1.100000000000000006e-01,-7.016311896062832343e-01,9.510565162949824458e-02,1.100000000000000006e-01,-6.583688103937168634e-01,-9.993985556619053301e-03,-1.063045428604786485e-01,-3.707079396122354153e-01,1.099939855566190589e-01,1.136954571395213526e-01,-3.692920603877644092e-01
+-6.342675291554346062e-01,-1.136141537209210545e-01,-9.083235139052037166e-02,4.987495030826643964e-03,4.180607698342111989e-01,7.590858215732518288e-02,5.104581687394682543e-01,-1.479745070380600047e-01,-3.567820158601532621e-02,2.207334564717002567e-01,6.698175941157766093e-03,1.929766589091585702e-03,-9.876883405950502570e-02,-1.100000000000000006e-01,-6.909504125528549423e-01,9.876883405950502570e-02,1.100000000000000006e-01,-6.690495874471451554e-01,-9.388255425530789289e-03,-1.032752228787113535e-01,-3.628782845040331440e-01,1.093882554255308226e-01,1.167247771212886476e-01,-3.771217154959666806e-01
+-6.015091030976370545e-01,-1.003892154378363544e-01,-7.639017382002030732e-02,7.536003586169555922e-03,3.932898026093149535e-01,6.304935679361527157e-02,4.585879697262409405e-01,-1.745055716379344535e-01,-1.353823766729426309e-02,2.380022910156284754e-01,8.248665217429243524e-03,5.252174634711215956e-03,-1.000000000000000056e-01,-1.100000000000000006e-01,-6.800000000000396838e-01,1.000000000000000056e-01,1.100000000000000006e-01,-6.799999999999604139e-01,-7.320189347546447733e-03,-1.004114892279258792e-01,-3.552239896669602270e-01,1.073201893475465157e-01,1.195885107720741219e-01,-3.847760103330395975e-01
+-5.650199172976008155e-01,-7.293045398971030602e-02,-6.227748628624062144e-02,9.739606996808565856e-03,3.670525667965022776e-01,3.912876259714012650e-02,4.111058022737494877e-01,-2.124776593389746671e-01,1.772078937263694021e-03,2.570391413964659977e-01,1.003981562872416876e-02,8.624325639685083075e-03,-9.876883405952262274e-02,-1.100000000000000006e-01,-6.690495874472229820e-01,9.876883405952262274e-02,1.100000000000000006e-01,-6.909504125527771157e-01,-3.840709973023610779e-03,-9.778385653479153283e-02,-3.479335292430531523e-01,1.038407099730235261e-01,1.222161434652084683e-01,-3.920664707569470053e-01
+-5.253190287861956298e-01,-2.922878092798879626e-02,-4.877165008307145916e-02,1.225311428517151212e-02,3.395273341132305500e-01,2.497974193495029055e-03,3.682489008909822781e-01,-2.643954788335839412e-01,1.064761765341660886e-02,2.788295816934902582e-01,1.198181587143802573e-02,1.193481551186245486e-02,-9.510565162953302232e-02,-1.100000000000000006e-01,-6.583688103937918035e-01,9.510565162953302232e-02,1.100000000000000006e-01,-7.016311896062082942e-01,9.645063681066670669e-04,-9.545702583682644238e-02,-3.411864185636001023e-01,9.903549363189322052e-02,1.245429741631735587e-01,-3.988135814363999998e-01
+-4.828051591286344757e-01,3.191699582431857529e-02,-3.609134982027062399e-02,1.631742097925840268e-02,3.107876914955032266e-01,-4.768801171418256962e-02,3.298837045300560544e-01,-3.319682847509318746e-01,1.374068819078246885e-02,3.039753575646562123e-01,1.395079121638963249e-02,1.498012027512402727e-02,-8.910065241886269694e-02,-1.100000000000000006e-01,-6.482206650182673613e-01,8.910065241886269694e-02,1.100000000000000006e-01,-7.117793349817327364e-01,6.977139301927476334e-03,-9.348829142812266346e-02,-3.351487938859052385e-01,9.302286069807268187e-02,1.265117085718773238e-01,-4.048512061140946416e-01
+-4.378336598937683233e-01,1.095522403407187678e-01,-2.442778464484812381e-02,2.363195766964779759e-02,2.808774127908661433e-01,-1.102372783052479321e-01,2.956860640217496283e-01,-4.144794111093523248e-01,1.181813277408685914e-02,3.318676187595043792e-01,1.581207081669855005e-02,1.744878856002695169e-02,-8.090169943752865966e-02,-1.100000000000000006e-01,-6.388550323395596475e-01,8.090169943752865966e-02,1.100000000000000006e-01,-7.211449676604404502e-01,1.404913785082296390e-02,-9.192613008367753191e-02,-3.299693215672613311e-01,8.595086214917721512e-02,1.280738699163224692e-01,-4.100306784327385490e-01
+-3.907770986532824176e-01,1.980260120082194264e-01,-1.395745259040959141e-02,3.546144753772691866e-02,2.498681818961368817e-01,-1.798060562164753295e-01,2.652653009988264476e-01,-5.040411986079356144e-01,5.665123502641823336e-03,3.478089728115705825e-01,1.743836329117581102e-02,1.886183327922969985e-02,-7.071067811869599651e-02,-1.100000000000000006e-01,-6.305025253169705968e-01,7.071067811869599651e-02,1.100000000000000006e-01,-7.294974746830295009e-01,2.200636593990203116e-02,-9.080900740030747875e-02,-3.257755374058363129e-01,7.799363406009816868e-02,1.291909925996925224e-01,-4.142244625941636227e-01
+-3.420655581768879960e-01,2.895443046001409115e-01,-4.841596824648016634e-03,5.160187264017186692e-02,2.178979182517856161e-01,-2.492728734051164463e-01,2.382376078106518968e-01,-5.905773675884817830e-01,-3.968751817763980193e-03,3.489874358007231114e-01,1.872202140058019243e-02,1.860051970969594029e-02,-5.877852522929442186e-02,-1.100000000000000006e-01,-6.233688103937776726e-01,5.877852522929442186e-02,1.100000000000000006e-01,-7.366311896062224251e-01,3.065289020508599888e-02,-9.016443064599465040e-02,-3.226707062860558195e-01,6.934710979491381933e-02,1.298355693540053368e-01,-4.173292937139442271e-01
+-2.922088815131753670e-01,3.793666227246551559e-01,2.782043068093907785e-03,7.120691345988527932e-02,1.851921758807142104e-01,-3.145830796545410202e-01,2.142641032480323005e-01,-6.714023036865144345e-01,-1.639386155512187471e-02,3.490610897375451827e-01,1.958198324588133685e-02,1.703940665431278104e-02,-4.539904997400711489e-02,-1.100000000000000006e-01,-6.176295433068329510e-01,4.539904997400711489e-02,1.100000000000000006e-01,-7.423704566931671467e-01,3.977580452279646378e-02,-9.000827143965790811e-02,-3.207312794544330270e-01,6.022419547720334054e-02,1.299917285603420791e-01,-4.192687205455670196e-01
+-2.418044428699766268e-01,4.622966703088882690e-01,8.810760645470936195e-03,9.227356492618438155e-02,1.520718893938746430e-01,-3.717175438093738293e-01,1.930679167302235266e-01,-7.407176961218214784e-01,-3.098756273249645907e-02,3.490656931085965309e-01,1.996643096950611110e-02,1.457753668248991732e-02,-3.090169943755062890e-02,-1.100000000000000006e-01,-6.134260438593519549e-01,3.090169943755062890e-02,1.100000000000000006e-01,-7.465739561406481428e-01,4.915047246531546038e-02,-9.034437493921992912e-02,-3.200050120361507822e-01,5.084952753468476028e-02,1.296556250607800720e-01,-4.199949879638492090e-01
+-1.915338529943635959e-01,5.348385334531083890e-01,1.318858593750578574e-02,1.124415214075573377e-01,1.189504629204938546e-01,-4.184620240909820987e-01,1.744406738136430879e-01,-7.942577162622982412e-01,-4.719277263848560555e-02,3.490659808192872471e-01,1.985221780112942161e-02,1.166413896013243981e-02,-1.564344650408173651e-02,-1.100000000000000006e-01,-6.108618161583468931e-01,1.564344650408173651e-02,1.100000000000000006e-01,-7.491381838416532046e-01,5.854605859515821242e-02,-9.116446516105790321e-02,-3.205097871453907454e-01,4.145394140484200823e-02,1.288355348389420840e-01,-4.194902128546092457e-01
+-1.421519329443918511e-01,5.953693400278534664e-01,1.591602986309663750e-02,1.297194457235363307e-01,8.632316183598165438e-02,-4.543397535387868613e-01,1.582451059999425425e-01,-8.301158477193959495e-01,-6.451373185720450654e-02,3.490659988012054238e-01,1.924197278445625298e-02,8.703821904377401567e-03,-6.000405986969038734e-14,-1.100000000000000006e-01,-6.100000000000000977e-01,6.000405986969038734e-14,1.100000000000000006e-01,-7.500000000000000000e-01,6.773121239964581541e-02,-9.244834876218678554e-02,-3.222331755437107814e-01,3.226878760035439830e-02,1.275516512378132017e-01,-4.177668244562892652e-01
+-9.447163462326318983e-02,6.433256773731290679e-01,1.705646484153846079e-02,1.426945809658115849e-01,5.475217720663002469e-02,-4.797609735116318275e-01,1.444180509880385321e-01,-8.476869101482825686e-01,-8.251230611385620972e-02,3.459210837709964514e-01,1.815963020596489397e-02,5.985677071249286864e-03,1.564344650396391062e-02,-1.100000000000000006e-01,-6.108618161583337924e-01,-1.564344650396391062e-02,1.100000000000000006e-01,-7.491381838416663053e-01,7.647976490833441332e-02,-9.416441226738149484e-02,-3.251327416891462430e-01,2.352023509166540141e-02,1.258355877326184924e-01,-4.148672583108536926e-01
+-4.934908311170843609e-02,6.773332858453091632e-01,1.673834903915714239e-02,1.498575406396641663e-01,2.485129274924511786e-02,-4.945905135244555439e-01,1.329767390243270508e-01,-8.412338040721214494e-01,-1.008067836223025121e-01,3.118859117683547844e-01,1.664499566594681776e-02,3.185372749511877159e-03,3.090169943743717104e-02,-1.100000000000000006e-01,-6.134260438593261977e-01,-3.090169943743717104e-02,1.100000000000000006e-01,-7.465739561406739000e-01,8.457629772367819543e-02,-9.627040049785574871e-02,-3.291370886400878937e-01,1.542370227632165053e-02,1.237295995021442524e-01,-4.108629113599119864e-01
+-7.673188385222726171e-03,6.991592328518843047e-01,1.515302578486408397e-02,1.516888329904876043e-01,-2.725583435053525495e-03,-5.007475828906663429e-01,1.240306783858372147e-01,-8.177541401321147818e-01,-1.190744289965451480e-01,2.714130818282995961e-01,1.474786567660024174e-02,7.917428048823076233e-04,4.539904997390081798e-02,-1.100000000000000006e-01,-6.176295433067950924e-01,-4.539904997390081798e-02,1.100000000000000006e-01,-7.423704566932050053e-01,9.182144733691224858e-02,-9.871445703400121008e-02,-3.341476160849383703e-01,8.178552663087916563e-03,1.212855429659987910e-01,-4.058523839150617318e-01
+2.963590179854368178e-02,7.098632864868965608e-01,1.254818146291828036e-02,1.487310921673806186e-01,-2.728787781466166656e-02,-4.994660274918721887e-01,1.178014005988250318e-01,-7.809684223238315681e-01,-1.370588412564626990e-01,2.278042664176558318e-01,1.252216408641643533e-02,-1.026656369140128760e-03,5.877852522919790879e-02,-1.100000000000000006e-01,-6.233688103937286007e-01,-5.877852522919790879e-02,1.100000000000000006e-01,-7.366311896062714970e-01,9.803681411928513723e-02,-1.014364010925391801e-01,-3.400409482090177571e-01,1.963185880714986287e-03,1.185635989074608210e-01,-3.999590517909823451e-01
+6.161585822190891737e-02,7.103901144866026085e-01,9.217067175098262941e-03,1.416878746226700181e-01,-4.810022722822804297e-02,-4.917885642703841431e-01,1.146525911131285880e-01,-7.340487569099739540e-01,-1.545832616035857365e-01,1.832300851384672524e-01,1.002054977264966833e-02,-2.367965080442689489e-03,7.071067811861113384e-02,-1.100000000000000006e-01,-6.305025253169111998e-01,-7.071067811861113384e-02,1.100000000000000006e-01,-7.294974746830888979e-01,1.030693551129955032e-01,-1.043692093771341478e-01,-3.466719716165835297e-01,-3.069355112995393597e-03,1.156307906228658533e-01,-3.933280283834166280e-01
+8.723604095424895843e-02,7.018536152211874990e-01,5.483080761099577011e-03,1.314589164208257444e-01,-6.436012173371583045e-02,-4.787833981385566928e-01,1.151334353455642084e-01,-6.803817301687874464e-01,-1.715712081078462070e-01,1.398613826582073838e-01,7.290000459084493116e-03,-3.411449538231706158e-03,8.090169943745853520e-02,-1.100000000000000006e-01,-6.388550323394920349e-01,-8.090169943745853520e-02,1.100000000000000006e-01,-7.211449676605080628e-01,1.067951524567323229e-01,-1.074406664143868761e-01,-3.538774085042367123e-01,-6.795152456732386770e-03,1.125593335856131250e-01,-3.861225914957631122e-01
+1.053548694612505554e-01,6.854951399744942941e-01,1.678016517610628894e-03,1.190053900479587506e-01,-7.516005639095384161e-02,-4.615221586757530803e-01,1.200377521512888679e-01,-6.233272708744379553e-01,-1.880758526935628894e-01,9.974724695733626356e-02,4.369022085697847439e-03,-4.366040839590685022e-03,8.910065241880854581e-02,-1.100000000000000006e-01,-6.482206650181929763e-01,-8.910065241880854581e-02,1.100000000000000006e-01,-7.117793349818071214e-01,1.091224646546800348e-01,-1.105751427384584623e-01,-3.614798371023287271e-01,-9.122464654680063900e-03,1.094248572615415388e-01,-3.785201628976710975e-01
+1.146620808150771165e-01,6.625800878603563815e-01,-1.890103040909119590e-03,1.052190971445707973e-01,-7.943570573496666620e-02,-4.410041489839618412e-01,1.304791654639147480e-01,-5.658964679617424220e-01,-2.043186048996530335e-01,6.461523056283859090e-02,1.287435098151313434e-03,-5.419406970880944092e-03,9.510565162949616291e-02,-1.100000000000000006e-01,-6.583688103937123115e-01,-9.510565162949616291e-02,1.100000000000000006e-01,-7.016311896062877862e-01,1.099939855566190033e-01,-1.136954571395200203e-01,-3.692920603877611896e-01,-9.993985556618990851e-03,1.063045428604799808e-01,-3.707079396122389681e-01
+1.136141537209240798e-01,6.342675291554474848e-01,-4.987495030825458281e-03,9.083235139052653340e-02,-7.590858215732849967e-02,-4.180607698342212464e-01,1.479745070380505123e-01,-5.104581687394911249e-01,-2.207334564716921521e-01,3.567820158602625497e-02,-1.929766589090133305e-03,-6.698175941157154603e-03,9.876883405950395711e-02,-1.100000000000000006e-01,-6.690495874471404925e-01,-9.876883405950395711e-02,1.100000000000000006e-01,-6.909504125528596052e-01,1.093882554255313777e-01,-1.167247771212873708e-01,-3.771217154959635165e-01,-9.388255425531399911e-03,1.032752228787126303e-01,-3.628782845040366967e-01
+1.003892154378453611e-01,6.015091030976511544e-01,-7.536003586168568864e-03,7.639017382002626089e-02,-6.304935679362322354e-02,-3.932898026093253896e-01,1.745055716379201594e-01,-4.585879697262612020e-01,-2.380022910156193716e-01,1.353823766730179352e-02,-5.252174634709546285e-03,-8.248665217428480245e-03,1.000000000000000056e-01,-1.100000000000000006e-01,-6.799999999999556399e-01,-1.000000000000000056e-01,1.100000000000000006e-01,-6.800000000000444578e-01,1.073201893475476537e-01,-1.195885107720729285e-01,-3.847760103330365444e-01,-7.320189347547710612e-03,1.004114892279270727e-01,-3.552239896669636132e-01
+7.293045398972501647e-02,5.650199172976181350e-01,-9.739606996807644718e-03,6.227748628624681787e-02,-3.912876259715277610e-02,-3.670525667965143235e-01,2.124776593389560153e-01,-4.111058022737700268e-01,-2.570391413964574490e-01,-1.772078937258063109e-03,-8.624325639683671010e-03,-1.003981562872331701e-02,9.876883405952367745e-02,-1.100000000000000006e-01,-6.909504125527724527e-01,-9.876883405952367745e-02,1.100000000000000006e-01,-6.690495874472276450e-01,1.038407099730254135e-01,-1.222161434652073997e-01,-3.920664707569438412e-01,-3.840709973025310808e-03,9.778385653479260142e-02,-3.479335292430559834e-01
+2.922878092801051847e-02,5.253190287862138375e-01,-1.225311428517017291e-02,4.877165008307726701e-02,-2.497974193513175997e-03,-3.395273341132430400e-01,2.643954788335592943e-01,-3.682489008910006523e-01,-2.788295816934814320e-01,-1.064761765341369799e-02,-1.193481551186129259e-02,-1.198181587143716531e-02,9.510565162953510399e-02,-1.100000000000000006e-01,-7.016311896062038533e-01,-9.510565162953510399e-02,1.100000000000000006e-01,-6.583688103937962444e-01,9.903549363189567689e-02,-1.245429741631726289e-01,-3.988135814363971132e-01,9.645063681044466208e-04,9.545702583682737219e-02,-3.411864185636027669e-01
+-3.191699582428853682e-02,4.828051591286529609e-01,-1.631742097925613366e-02,3.609134982027582816e-02,4.768801171415804757e-02,-3.107876914955156056e-01,3.319682847508997336e-01,-3.298837045300711535e-01,-3.039753575646439998e-01,-1.374068819078243936e-02,-1.498012027512278348e-02,-1.395079121638870615e-02,8.910065241886577780e-02,-1.100000000000000006e-01,-7.117793349817285176e-01,-8.910065241886577780e-02,1.100000000000000006e-01,-6.482206650182715801e-01,9.302286069807536029e-02,-1.265117085718765744e-01,-4.048512061140923102e-01,6.977139301924492609e-03,9.348829142812341286e-02,-3.351487938859077920e-01
+-1.095522403406810619e-01,4.378336598937872526e-01,-2.363195766964360997e-02,2.442778464485274859e-02,1.102372783052178729e-01,-2.808774127908787444e-01,4.144794111093128008e-01,-2.956860640217623959e-01,-3.318676187594914451e-01,-1.181813277408905009e-02,-1.744878856002595943e-02,-1.581207081669778330e-02,8.090169943753262871e-02,-1.100000000000000006e-01,-7.211449676604366754e-01,-8.090169943753262871e-02,1.100000000000000006e-01,-6.388550323395634223e-01,8.595086214918029599e-02,-1.280738699163218863e-01,-4.100306784327366061e-01,1.404913785081953609e-02,9.192613008367811478e-02,-3.299693215672634961e-01
+-1.980260120081786535e-01,3.907770986533021240e-01,-3.546144753772067365e-02,1.395745259041370097e-02,1.798060562164437992e-01,-2.498681818961498990e-01,5.040411986078956463e-01,-2.652653009988376609e-01,-3.478089728115689727e-01,-5.665123502646115909e-03,-1.886183327922945352e-02,-1.743836329117511713e-02,7.071067811870077047e-02,-1.100000000000000006e-01,-7.294974746830261703e-01,-7.071067811870077047e-02,1.100000000000000006e-01,-6.305025253169739274e-01,7.799363406010156874e-02,-1.291909925996921338e-01,-4.142244625941621239e-01,2.200636593989824599e-02,9.080900740030785345e-02,-3.257755374058379783e-01
+-2.895443046001028864e-01,3.420655581769100895e-01,-5.160187264016434516e-02,4.841596824651754095e-03,2.492728734050881634e-01,-2.178979182518001045e-01,5.905773675884473661e-01,-2.382376078106639983e-01,-3.489874358007230559e-01,3.968751817759659864e-03,-1.860051970969625254e-02,-1.872202140057973793e-02,5.877852522929989665e-02,-1.100000000000000006e-01,-7.366311896062196496e-01,-5.877852522929989665e-02,1.100000000000000006e-01,-6.233688103937804481e-01,6.934710979491784388e-02,-1.298355693540051703e-01,-4.173292937139430614e-01,3.065289020508235249e-02,9.016443064599483082e-02,-3.226707062860568742e-01
+-3.793666227246190181e-01,2.922088815131977935e-01,-7.120691345987661958e-02,-2.782043068090909316e-03,3.145830796545155961e-01,-1.851921758807288931e-01,6.714023036864834593e-01,-2.142641032480429586e-01,-3.490610897375451827e-01,1.639386155511634788e-02,-1.703940665431376289e-02,-1.958198324588117725e-02,4.539904997401314479e-02,-1.100000000000000006e-01,-7.423704566931649262e-01,-4.539904997401314479e-02,1.100000000000000006e-01,-6.176295433068351715e-01,6.022419547720753857e-02,-1.299917285603421346e-01,-4.192687205455664090e-01,3.977580452279266821e-02,9.000827143965786648e-02,-3.207312794544335821e-01
+-4.622966703088537965e-01,2.418044428699974990e-01,-9.227356492617509731e-02,-8.810760645468722688e-03,3.717175438093507367e-01,-1.520718893938887983e-01,7.407176961217938338e-01,-1.930679167302312149e-01,-3.490656931085965309e-01,3.098756273248957221e-02,-1.457753668249120275e-02,-1.996643096950600008e-02,3.090169943755705778e-02,-1.100000000000000006e-01,-7.465739561406465885e-01,-3.090169943755705778e-02,1.100000000000000006e-01,-6.134260438593535092e-01,5.084952753468859749e-02,-1.296556250607803218e-01,-4.199949879638491534e-01,4.915047246531118602e-02,9.034437493921967932e-02,-3.200050120361508377e-01
+-5.348385334530788571e-01,1.915338529943843016e-01,-1.124415214075488306e-01,-1.318858593750426786e-02,4.184620240909638356e-01,-1.189504629205073161e-01,7.942577162622779241e-01,-1.744406738136495272e-01,-3.490659808192872471e-01,4.719277263847695969e-02,-1.166413896013379810e-02,-1.985221780112922732e-02,1.564344650408841866e-02,-1.100000000000000006e-01,-7.491381838416524275e-01,-1.564344650408841866e-02,1.100000000000000006e-01,-6.108618161583476702e-01,4.145394140484580381e-02,-1.288355348389425281e-01,-4.194902128546097453e-01,5.854605859515397970e-02,9.116446516105745912e-02,-3.205097871453902458e-01
+-5.953693400278290415e-01,1.421519329444117796e-01,-1.297194457235293363e-01,-1.591602986309592974e-02,4.543397535387730390e-01,-8.632316183599496318e-02,8.301158477193830709e-01,-1.582451059999480103e-01,-3.490659988012054793e-01,6.451373185719840031e-02,-8.703821904378685262e-03,-1.924197278445730075e-02,6.676646232740281767e-14,-1.100000000000000006e-01,-7.500000000000000000e-01,-6.676646232740281767e-14,1.100000000000000006e-01,-6.100000000000000977e-01,3.226878760035806204e-02,-1.275516512378138401e-01,-4.177668244562902089e-01,6.773121239964173534e-02,9.244834876218614717e-02,-3.222331755437097267e-01
+-6.433256773731121925e-01,9.447163462328420080e-02,-1.426945809658075603e-01,-1.705646484153834283e-02,4.797609735116236673e-01,-5.475217720664314613e-02,8.476869101482811253e-01,-1.444180509880449714e-01,-3.459210837710082198e-01,8.251230611384771652e-02,-5.985677071250337239e-03,-1.815963020596493560e-02,-1.564344650395722847e-02,-1.100000000000000006e-01,-7.491381838416669714e-01,1.564344650395722847e-02,1.100000000000000006e-01,-6.108618161583331263e-01,2.352023509166922821e-02,-1.258355877326193251e-01,-4.148672583108552470e-01,7.647976490833097163e-02,9.416441226738067605e-02,-3.251327416891447997e-01
+-6.773332858452973948e-01,4.934908311172789275e-02,-1.498575406396622789e-01,-1.673834903915754138e-02,4.945905135244512141e-01,-2.485129274925797910e-02,8.412338040721283328e-01,-1.329767390243321856e-01,-3.118859117683710491e-01,1.008067836222948932e-01,-3.185372749513059806e-03,-1.664499566594754634e-02,-3.090169943743073522e-02,-1.100000000000000006e-01,-7.465739561406753433e-01,3.090169943743073522e-02,1.100000000000000006e-01,-6.134260438593247544e-01,1.542370227632513385e-02,-1.237295995021452377e-01,-4.108629113599140403e-01,8.457629772367504517e-02,9.627040049785476339e-02,-3.291370886400860618e-01
+-6.991592328518770882e-01,7.673188385239240739e-03,-1.516888329904879373e-01,-1.515302578486502766e-02,5.007475828906653437e-01,2.725583435042849140e-03,8.177541401321277714e-01,-1.240306783858399348e-01,-2.714130818283179702e-01,1.190744289965371544e-01,-7.917428048832118479e-04,-1.474786567660118022e-02,-4.539904997389479502e-02,-1.100000000000000006e-01,-7.423704566932071147e-01,4.539904997389479502e-02,1.100000000000000006e-01,-6.176295433067929830e-01,8.178552663090664365e-03,-1.212855429659999151e-01,-4.058523839150639523e-01,9.182144733690918159e-02,9.871445703400008598e-02,-3.341476160849358723e-01
+-7.098632864868940073e-01,-2.963590179852933909e-02,-1.487310921673828112e-01,-1.254818146291953977e-02,4.994660274918740761e-01,2.728787781465227824e-02,7.809684223238497758e-01,-1.178014005988264196e-01,-2.278042664176746501e-01,1.370588412564548997e-01,1.026656369139535918e-03,-1.252216408641740678e-02,-5.877852522919244094e-02,-1.100000000000000006e-01,-7.366311896062742726e-01,5.877852522919244094e-02,1.100000000000000006e-01,-6.233688103937258251e-01,1.963185880717283061e-03,-1.185635989074620422e-01,-3.999590517909848986e-01,9.803681411928258371e-02,1.014364010925379589e-01,-3.400409482090149260e-01
+-7.103901144866044959e-01,-6.161585822189837719e-02,-1.416878746226735708e-01,-9.217067175099654189e-03,4.917885642703884730e-01,4.810022722822058366e-02,7.340487569099942711e-01,-1.146525911131284908e-01,-1.832300851384853213e-01,1.545832616035788531e-01,2.367965080442170373e-03,-1.002054977265210214e-02,-7.071067811860685948e-02,-1.100000000000000006e-01,-7.294974746830918955e-01,7.071067811860685948e-02,1.100000000000000006e-01,-6.305025253169082022e-01,-3.069355112993804591e-03,-1.156307906228670190e-01,-3.933280283834191260e-01,1.030693551129939073e-01,1.043692093771329821e-01,-3.466719716165809761e-01
+-7.018536152211928281e-01,-8.723604095423910521e-02,-1.314589164208306571e-01,-5.483080761101199845e-03,4.787833981385631321e-01,6.436012173370994627e-02,6.803817301688112051e-01,-1.151334353455635978e-01,-1.398613826582254804e-01,1.715712081078397955e-01,3.411449538231252961e-03,-7.290000459084945011e-03,-8.090169943745456616e-02,-1.100000000000000006e-01,-7.211449676605119485e-01,8.090169943745456616e-02,1.100000000000000006e-01,-6.388550323394881492e-01,-6.795152456731012869e-03,-1.125593335856144572e-01,-3.861225914957664429e-01,1.067951524567310878e-01,1.074406664143855439e-01,-3.538774085042336592e-01
+-6.854951399745025098e-01,-1.053548694612443243e-01,-1.190053900479647181e-01,-1.678016517612264738e-03,4.615221586757620176e-01,7.516005639095035828e-02,6.233272708744627133e-01,-1.200377521512859258e-01,-9.974724695735420754e-02,1.880758526935559227e-01,4.366040839590609561e-03,-4.369022085699157155e-03,-8.910065241880546494e-02,-1.100000000000000006e-01,-7.117793349818113402e-01,8.910065241880546494e-02,1.100000000000000006e-01,-6.482206650181887575e-01,-9.122464654679335316e-03,-1.094248572615428988e-01,-3.785201628976745947e-01,1.091224646546793686e-01,1.105751427384571023e-01,-3.614798371023255630e-01
+-6.625800878603677058e-01,-1.146620808150753540e-01,-1.052190971445769729e-01,1.890103040907653749e-03,4.410041489839712781e-01,7.943570573496651355e-02,5.658964679617670690e-01,-1.304791654639087806e-01,-6.461523056285248257e-02,2.043186048996461224e-01,5.419406970880448829e-03,-1.287435098152696442e-03,-9.510565162949408125e-02,-1.100000000000000006e-01,-7.016311896062922271e-01,9.510565162949408125e-02,1.100000000000000006e-01,-6.583688103937078706e-01,-9.993985556618935340e-03,-1.063045428604813131e-01,-3.707079396122421877e-01,1.099939855566189340e-01,1.136954571395186880e-01,-3.692920603877576369e-01
+-6.342675291554608075e-01,-1.136141537209269387e-01,-9.083235139053284779e-02,4.987495030824289945e-03,4.180607698342317380e-01,7.590858215733184422e-02,5.104581687395145506e-01,-1.479745070380413807e-01,-3.567820158603732250e-02,2.207334564716851022e-01,6.698175941156540511e-03,1.929766589088765909e-03,-9.876883405950290240e-02,-1.100000000000000006e-01,-6.909504125528642682e-01,9.876883405950290240e-02,1.100000000000000006e-01,-6.690495874471358295e-01,-9.388255425531948084e-03,-1.032752228787139070e-01,-3.628782845040398608e-01,1.093882554255319883e-01,1.167247771212860941e-01,-3.771217154959599638e-01
+-6.015091030976641440e-01,-1.003892154378529106e-01,-7.639017382003156220e-02,7.536003586167642522e-03,3.932898026093350485e-01,6.304935679363032897e-02,4.585879697262801313e-01,-1.745055716379080579e-01,-1.353823766730892150e-02,2.380022910156135152e-01,8.248665217427923399e-03,5.252174634708388357e-03,-1.000000000000000056e-01,-1.100000000000000006e-01,-6.800000000000486766e-01,1.000000000000000056e-01,1.100000000000000006e-01,-6.799999999999514211e-01,-7.320189347548716752e-03,-1.004114892279281274e-01,-3.552239896669663333e-01,1.073201893475486668e-01,1.195885107720718737e-01,-3.847760103330338244e-01
+-5.650199172976337891e-01,-7.293045398974065674e-02,-6.227748628625253552e-02,9.739606996806720110e-03,3.670525667965254812e-01,3.912876259716598776e-02,4.111058022737885675e-01,-2.124776593389365031e-01,1.772078937253230169e-03,2.570391413964476790e-01,1.003981562872255026e-02,8.624325639681938022e-03,-9.876883405952474604e-02,-1.100000000000000006e-01,-6.690495874472323079e-01,9.876883405952474604e-02,1.100000000000000006e-01,-6.909504125527677898e-01,-3.840709973027198187e-03,-9.778385653479367001e-02,-3.479335292430592030e-01,1.038407099730271066e-01,1.222161434652063311e-01,-3.920664707569409546e-01
+-5.253190287862308239e-01,-2.922878092803390254e-02,-4.877165008308269323e-02,1.225311428516887187e-02,3.395273341132547529e-01,2.497974193532537246e-03,3.682489008910169170e-01,-2.643954788335325934e-01,1.064761765341168745e-02,2.788295816934708293e-01,1.198181587143636213e-02,1.193481551185987879e-02,-9.510565162953721341e-02,-1.100000000000000006e-01,-6.583688103938007963e-01,9.510565162953721341e-02,1.100000000000000006e-01,-7.016311896061993014e-01,9.645063681019902524e-04,-9.545702583682830200e-02,-3.411864185636056535e-01,9.903549363189789734e-02,1.245429741631716991e-01,-3.988135814363945042e-01
+-4.828051591286725008e-01,3.191699582425946979e-02,-3.609134982028124744e-02,1.631742097925389934e-02,3.107876914955286507e-01,-4.768801171413442758e-02,3.298837045300876403e-01,-3.319682847508684809e-01,1.374068819078202823e-02,3.039753575646330086e-01,1.395079121638787174e-02,1.498012027512160386e-02,-8.910065241886883092e-02,-1.100000000000000006e-01,-6.482206650182757990e-01,8.910065241886883092e-02,1.100000000000000006e-01,-7.117793349817242987e-01,6.977139301921821135e-03,-9.348829142812419002e-02,-3.351487938859100679e-01,9.302286069807833013e-02,1.265117085718757972e-01,-4.048512061140897567e-01
+-4.378336598938080693e-01,1.095522403406457984e-01,-2.442778464485769602e-02,2.363195766963963398e-02,2.808774127908925111e-01,-1.102372783051897703e-01,2.956860640217774949e-01,-4.144794111092759969e-01,1.181813277409047604e-02,3.318676187594799543e-01,1.581207081669706166e-02,1.744878856002511289e-02,-8.090169943753661164e-02,-1.100000000000000006e-01,-6.388550323395673081e-01,8.090169943753661164e-02,1.100000000000000006e-01,-7.211449676604327896e-01,1.404913785081646910e-02,-9.192613008367868377e-02,-3.299693215672654389e-01,8.595086214918370993e-02,1.280738699163213035e-01,-4.100306784327344412e-01
+-3.907770986533188884e-01,1.980260120081434871e-01,-1.395745259041708541e-02,3.546144753771510866e-02,2.498681818961608070e-01,-1.798060562164164322e-01,2.652653009988463761e-01,-5.040411986078610074e-01,5.665123502649302596e-03,3.478089728115674739e-01,1.743836329117474937e-02,1.886183327922923494e-02,-7.071067811870505870e-02,-1.100000000000000006e-01,-6.305025253169769250e-01,7.071067811870505870e-02,1.100000000000000006e-01,-7.294974746830231727e-01,2.200636593989522757e-02,-9.080900740030820040e-02,-3.257755374058392550e-01,7.799363406010459410e-02,1.291909925996918007e-01,-4.142244625941607916e-01
+-3.420655581769307396e-01,2.895443046000625298e-01,-4.841596824655212267e-03,5.160187264015633768e-02,2.178979182518137048e-01,-2.492728734050581041e-01,2.382376078106742401e-01,-5.905773675884098406e-01,-3.968751817755156522e-03,3.489874358007229449e-01,1.872202140057940833e-02,1.860051970969664459e-02,-5.877852522930535756e-02,-1.100000000000000006e-01,-6.233688103937832237e-01,5.877852522930535756e-02,1.100000000000000006e-01,-7.366311896062168740e-01,3.065289020507831405e-02,-9.016443064599499735e-02,-3.226707062860580399e-01,6.934710979492149374e-02,1.298355693540050038e-01,-4.173292937139420067e-01
+-2.922088815132183326e-01,3.793666227245802158e-01,2.782043068088043553e-03,7.120691345986736309e-02,1.851921758807426044e-01,-3.145830796544880625e-01,2.142641032480514240e-01,-6.714023036864489313e-01,-1.639386155510989818e-02,3.490610897375451827e-01,1.958198324588087194e-02,1.703940665431470311e-02,-4.539904997401916775e-02,-1.100000000000000006e-01,-6.176295433068372809e-01,4.539904997401916775e-02,1.100000000000000006e-01,-7.423704566931628168e-01,3.977580452278846324e-02,-9.000827143965782484e-02,-3.207312794544341372e-01,6.022419547721133415e-02,1.299917285603421624e-01,-4.192687205455658539e-01
+-2.418044428700202308e-01,4.622966703088213780e-01,8.810760645466425914e-03,9.227356492616645145e-02,1.520718893939035088e-01,-3.717175438093293094e-01,1.930679167302410126e-01,-7.407176961217687428e-01,-3.098756273248351803e-02,3.490656931085965309e-01,1.996643096950601742e-02,1.457753668249235635e-02,-3.090169943756349014e-02,-1.100000000000000006e-01,-6.134260438593549525e-01,3.090169943756349014e-02,1.100000000000000006e-01,-7.465739561406451452e-01,4.915047246530734881e-02,-9.034437493921942952e-02,-3.200050120361508932e-01,5.084952753469287878e-02,1.296556250607805716e-01,-4.199949879638490979e-01
+-1.915338529944065893e-01,5.348385334530513235e-01,1.318858593750268579e-02,1.124415214075410868e-01,1.189504629205225816e-01,-4.184620240909469047e-01,1.744406738136582147e-01,-7.942577162622599385e-01,-4.719277263847322657e-02,3.490659808192872471e-01,1.985221780113018142e-02,1.166413896013497424e-02,-1.564344650409509735e-02,-1.100000000000000006e-01,-6.108618161583483364e-01,1.564344650409509735e-02,1.100000000000000006e-01,-7.491381838416517613e-01,5.854605859515018412e-02,-9.116446516105698727e-02,-3.205097871453898017e-01,4.145394140485003653e-02,1.288355348389430000e-01,-4.194902128546102449e-01
+-1.421519329444291269e-01,5.953693400278083914e-01,1.591602986309523585e-02,1.297194457235235077e-01,8.632316183600630133e-02,-4.543397535387615482e-01,1.582451059999522569e-01,-8.301158477193730789e-01,-6.451373185719201653e-02,3.490659988012054238e-01,1.924197278445749851e-02,8.703821904379778138e-03,-7.281832204935515034e-14,-1.100000000000000006e-01,-6.100000000000000977e-01,7.281832204935515034e-14,1.100000000000000006e-01,-7.500000000000000000e-01,6.773121239963847406e-02,-9.244834876218556430e-02,-3.222331755437088940e-01,3.226878760036133720e-02,1.275516512378144229e-01,-4.177668244562910416e-01
+-9.447163462330331052e-02,6.433256773730939848e-01,1.705646484153810344e-02,1.426945809658027864e-01,5.475217720665657983e-02,-4.797609735116147855e-01,1.444180509880494678e-01,-8.476869101482780167e-01,-8.251230611384054170e-02,3.459210837710197106e-01,1.815963020596595909e-02,5.985677071251424911e-03,1.564344650395054978e-02,-1.100000000000000006e-01,-6.108618161583323491e-01,-1.564344650395054978e-02,1.100000000000000006e-01,-7.491381838416677486e-01,7.647976490832714136e-02,-9.416441226737985726e-02,-3.251327416891432454e-01,2.352023509167268378e-02,1.258355877326201300e-01,-4.148672583108566903e-01
+-4.934908311174603102e-02,6.773332858452852934e-01,1.673834903915796812e-02,1.498575406396603915e-01,2.485129274927003196e-02,-4.945905135244467177e-01,1.329767390243359881e-01,-8.412338040721347721e-01,-1.008067836222868302e-01,3.118859117683874249e-01,1.664499566594824370e-02,3.185372749514273679e-03,3.090169943742430980e-02,-1.100000000000000006e-01,-6.134260438593233111e-01,-3.090169943742430980e-02,1.100000000000000006e-01,-7.465739561406767866e-01,8.457629772367156185e-02,-9.627040049785377807e-02,-3.291370886400840079e-01,1.542370227632827717e-02,1.237295995021462230e-01,-4.108629113599158722e-01
+-7.673188385256952265e-03,6.991592328518704269e-01,1.515302578486592798e-02,1.516888329904883259e-01,-2.725583435031159706e-03,-5.007475828906644555e-01,1.240306783858439732e-01,-8.177541401321409831e-01,-1.190744289965296882e-01,2.714130818283362889e-01,1.474786567660202156e-02,7.917428048840701024e-04,4.539904997388877206e-02,-1.100000000000000006e-01,-6.176295433067907625e-01,-4.539904997388877206e-02,1.100000000000000006e-01,-7.423704566932093352e-01,9.182144733690641991e-02,-9.871445703399897575e-02,-3.341476160849336519e-01,8.178552663093731356e-03,1.212855429660010254e-01,-4.058523839150664503e-01
+2.963590179851372658e-02,7.098632864868920089e-01,1.254818146292091367e-02,1.487310921673851427e-01,-2.728787781464225848e-02,-4.994660274918762966e-01,1.178014005988291119e-01,-7.809684223238685385e-01,-1.370588412564473779e-01,2.278042664176941901e-01,1.252216408641960987e-02,-1.026656369138766352e-03,5.877852522918696615e-02,-1.100000000000000006e-01,-6.233688103937230496e-01,-5.877852522918696615e-02,1.100000000000000006e-01,-7.366311896062770481e-01,9.803681411928028000e-02,-1.014364010925367238e-01,-3.400409482090123725e-01,1.963185880719850451e-03,1.185635989074632773e-01,-3.999590517909877851e-01
+6.161585822188640066e-02,7.103901144866061612e-01,9.217067175101213705e-03,1.416878746226773456e-01,-4.810022722821359620e-02,-4.917885642703929139e-01,1.146525911131285325e-01,-7.340487569100158094e-01,-1.545832616035716645e-01,1.832300851385041673e-01,1.002054977265184194e-02,-2.367965080441660364e-03,7.071067811860207164e-02,-1.100000000000000006e-01,-6.305025253169048716e-01,-7.071067811860207164e-02,1.100000000000000006e-01,-7.294974746830952261e-01,1.030693551129919228e-01,-1.043692093771316914e-01,-3.466719716165778675e-01,-3.069355112992014356e-03,1.156307906228683097e-01,-3.933280283834219571e-01
+8.723604095423004301e-02,7.018536152211983792e-01,5.483080761102854771e-03,1.314589164208356808e-01,-6.436012173370435352e-02,-4.787833981385698490e-01,1.151334353455620158e-01,-6.803817301688355190e-01,-1.715712081078323847e-01,1.398613826582434938e-01,7.290000459086194012e-03,-3.411449538230868286e-03,8.090169943745058323e-02,-1.100000000000000006e-01,-6.388550323394843744e-01,-8.090169943745058323e-02,1.100000000000000006e-01,-7.211449676605157233e-01,1.067951524567297139e-01,-1.074406664143841977e-01,-3.538774085042303286e-01,-6.795152456729777746e-03,1.125593335856158034e-01,-3.861225914957694960e-01
+1.053548694612385789e-01,6.854951399745111695e-01,1.678016517613837265e-03,1.190053900479704774e-01,-7.516005639094720803e-02,-4.615221586757702887e-01,1.200377521512823453e-01,-6.233272708744878043e-01,-1.880758526935488451e-01,9.974724695737055558e-02,4.369022085700421769e-03,-4.366040839590171543e-03,8.910065241880239795e-02,-1.100000000000000006e-01,-6.482206650181845387e-01,-8.910065241880239795e-02,1.100000000000000006e-01,-7.117793349818155590e-01,1.091224646546786470e-01,-1.105751427384557561e-01,-3.614798371023220658e-01,-9.122464654678676121e-03,1.094248572615442450e-01,-3.785201628976777588e-01
+1.146620808150734250e-01,6.625800878603788080e-01,-1.890103040906245587e-03,1.052190971445830930e-01,-7.943570573496623599e-02,-4.410041489839807149e-01,1.304791654639028409e-01,-5.658964679617913829e-01,-2.043186048996391557e-01,6.461523056286636035e-02,1.287435098154058634e-03,-5.419406970879937953e-03,9.510565162949197182e-02,-1.100000000000000006e-01,-6.583688103937033187e-01,-9.510565162949197182e-02,1.100000000000000006e-01,-7.016311896062967790e-01,1.099939855566188923e-01,-1.136954571395173558e-01,-3.692920603877544172e-01,-9.993985556618879829e-03,1.063045428604826453e-01,-3.707079396122457404e-01
+1.136141537209298807e-01,6.342675291554734640e-01,-4.987495030823066097e-03,9.083235139053882912e-02,-7.590858215733538306e-02,-4.180607698342416745e-01,1.479745070380320271e-01,-5.104581687395368661e-01,-2.207334564716783298e-01,3.567820158604803615e-02,-1.929766589087313078e-03,-6.698175941155954174e-03,9.876883405950184769e-02,-1.100000000000000006e-01,-6.690495874471311666e-01,-9.876883405950184769e-02,1.100000000000000006e-01,-6.909504125528689311e-01,1.093882554255325296e-01,-1.167247771212848312e-01,-3.771217154959567996e-01,-9.388255425532551768e-03,1.032752228787151699e-01,-3.628782845040433580e-01
+1.003892154378613899e-01,6.015091030976794650e-01,-7.536003586166637250e-03,7.639017382003789047e-02,-6.304935679363798950e-02,-3.932898026093462063e-01,1.745055716378945410e-01,-4.585879697263018362e-01,-2.380022910156057991e-01,1.353823766731713021e-02,-5.252174634706938995e-03,-8.248665217427135835e-03,1.000000000000000056e-01,-1.100000000000000006e-01,-6.799999999999467581e-01,-1.000000000000000056e-01,1.100000000000000006e-01,-6.800000000000533396e-01,1.073201893475499158e-01,-1.195885107720706803e-01,-3.847760103330304382e-01,-7.320189347549854730e-03,1.004114892279293209e-01,-3.552239896669693864e-01
+7.293045398975521454e-02,5.650199172976507755e-01,-9.739606996805693154e-03,6.227748628625864868e-02,-3.912876259717852634e-02,-3.670525667965374161e-01,2.124776593389180734e-01,-4.111058022738087181e-01,-2.570391413964401295e-01,-1.772078937247808291e-03,-8.624325639680728919e-03,-1.003981562872175402e-02,9.876883405952580075e-02,-1.100000000000000006e-01,-6.909504125527631269e-01,-9.876883405952580075e-02,1.100000000000000006e-01,-6.690495874472369708e-01,1.038407099730289940e-01,-1.222161434652052625e-01,-3.920664707569377350e-01,-3.840709973028898216e-03,9.778385653479473860e-02,-3.479335292430620896e-01
+2.922878092805556577e-02,5.253190287862491425e-01,-1.225311428516755348e-02,4.877165008308845251e-02,-2.497974193550422245e-03,-3.395273341132671319e-01,2.643954788335080019e-01,-3.682489008910351247e-01,-2.788295816934604487e-01,-1.064761765340886332e-02,-1.193481551185831407e-02,-1.198181587143555375e-02,9.510565162953929508e-02,-1.100000000000000006e-01,-7.016311896061948605e-01,-9.510565162953929508e-02,1.100000000000000006e-01,-6.583688103938052372e-01,9.903549363190035371e-02,-1.245429741631707693e-01,-3.988135814363915621e-01,9.645063680997767452e-04,9.545702583682923181e-02,-3.411864185636082625e-01
+-3.191699582422851539e-02,4.828051591286905420e-01,-1.631742097925151236e-02,3.609134982028637528e-02,4.768801171410932960e-02,-3.107876914955407521e-01,3.319682847508349521e-01,-3.298837045301022952e-01,-3.039753575646211292e-01,-1.374068819078210282e-02,-1.498012027512035139e-02,-1.395079121638695754e-02,8.910065241887191179e-02,-1.100000000000000006e-01,-7.117793349817200799e-01,-8.910065241887191179e-02,1.100000000000000006e-01,-6.482206650182800178e-01,9.302286069808102242e-02,-1.265117085718750478e-01,-4.048512061140874807e-01,6.977139301918837411e-03,9.348829142812493942e-02,-3.351487938859126769e-01
+-1.095522403406083700e-01,4.378336598938271096e-01,-2.363195766963539779e-02,2.442778464486236936e-02,1.102372783051598915e-01,-2.808774127909051121e-01,4.144794111092367506e-01,-2.956860640217904845e-01,-3.318676187594675753e-01,-1.181813277409246750e-02,-1.744878856002425940e-02,-1.581207081669621511e-02,8.090169943754058068e-02,-1.100000000000000006e-01,-7.211449676604290149e-01,-8.090169943754058068e-02,1.100000000000000006e-01,-6.388550323395710828e-01,8.595086214918679079e-02,-1.280738699163207206e-01,-4.100306784327325538e-01,1.404913785081304128e-02,9.192613008367926664e-02,-3.299693215672675484e-01
+-1.980260120081061559e-01,3.907770986533410928e-01,-3.546144753770932162e-02,1.395745259042168243e-02,1.798060562163875109e-01,-2.498681818961756007e-01,5.040411986078254802e-01,-2.652653009988608646e-01,-3.478089728115659196e-01,-5.665123502652717399e-03,-1.886183327922890882e-02,-1.743836329117396181e-02,7.071067811870983266e-02,-1.100000000000000006e-01,-7.294974746830198420e-01,-7.071067811870983266e-02,1.100000000000000006e-01,-6.305025253169802557e-01,7.799363406010836886e-02,-1.291909925996914121e-01,-4.142244625941591263e-01,2.200636593989182058e-02,9.080900740030857510e-02,-3.257755374058407538e-01
+-2.895443046000242271e-01,3.420655581769525555e-01,-5.160187264014878816e-02,4.841596824658941922e-03,2.492728734050295714e-01,-2.178979182518279989e-01,5.905773675883748686e-01,-2.382376078106858419e-01,-3.489874358007228339e-01,3.968751817750620220e-03,-1.860051970969708521e-02,-1.872202140057885669e-02,5.877852522931083235e-02,-1.100000000000000006e-01,-7.366311896062140985e-01,-5.877852522931083235e-02,1.100000000000000006e-01,-6.233688103937859992e-01,6.934710979492553218e-02,-1.298355693540048095e-01,-4.173292937139408965e-01,3.065289020507467113e-02,9.016443064599517776e-02,-3.226707062860590391e-01
+-3.793666227245442446e-01,2.922088815132410367e-01,-7.120691345985898091e-02,-2.782043068085029471e-03,3.145830796544626939e-01,-1.851921758807572593e-01,6.714023036864185112e-01,-2.142641032480623597e-01,-3.490610897375451827e-01,1.639386155510466278e-02,-1.703940665431558435e-02,-1.958198324588062214e-02,4.539904997402519071e-02,-1.100000000000000006e-01,-7.423704566931607074e-01,-4.539904997402519071e-02,1.100000000000000006e-01,-6.176295433068393903e-01,6.022419547721553912e-02,-1.299917285603421901e-01,-4.192687205455652433e-01,3.977580452278467460e-02,9.000827143965779709e-02,-3.207312794544346923e-01
+-4.622966703087865725e-01,2.418044428700410198e-01,-9.227356492615707007e-02,-8.810760645464321694e-03,3.717175438093059947e-01,-1.520718893939172478e-01,7.407176961217404321e-01,-1.930679167302484511e-01,-3.490656931085965309e-01,3.098756273247640219e-02,-1.457753668249351341e-02,-1.996643096950602089e-02,3.090169943756991902e-02,-1.100000000000000006e-01,-7.465739561406437019e-01,-3.090169943756991902e-02,1.100000000000000006e-01,-6.134260438593563958e-01,5.084952753469671599e-02,-1.296556250607808214e-01,-4.199949879638490424e-01,4.915047246530306752e-02,9.034437493921917972e-02,-3.200050120361509487e-01
+-5.348385334530215696e-01,1.915338529944273227e-01,-1.124415214075325659e-01,-1.318858593750124250e-02,4.184620240909285305e-01,-1.189504629205361541e-01,7.942577162622396214e-01,-1.744406738136647927e-01,-3.490659808192872471e-01,4.719277263846553827e-02,-1.166413896013633253e-02,-1.985221780113036183e-02,1.564344650410177603e-02,-1.100000000000000006e-01,-7.491381838416509842e-01,-1.564344650410177603e-02,1.100000000000000006e-01,-6.108618161583491135e-01,4.145394140485383905e-02,-1.288355348389434440e-01,-4.194902128546106890e-01,5.854605859514595140e-02,9.116446516105654319e-02,-3.205097871453893021e-01
+-5.953693400277856318e-01,1.421519329444516644e-01,-1.297194457235173459e-01,-1.591602986309431991e-02,4.543397535387487807e-01,-8.632316183602117832e-02,8.301158477193624208e-01,-1.582451059999602505e-01,-3.490659988012054238e-01,6.451373185718205228e-02,-8.703821904380910912e-03,-1.924197278445734238e-02,7.958072450706756805e-14,-1.100000000000000006e-01,-7.500000000000000000e-01,-7.958072450706756805e-14,1.100000000000000006e-01,-6.100000000000000977e-01,3.226878760036540339e-02,-1.275516512378150891e-01,-4.177668244562920963e-01,6.773121239963479645e-02,9.244834876218491204e-02,-3.222331755437079504e-01
+-6.433256773730769984e-01,9.447163462332412720e-02,-1.426945809657988451e-01,-1.705646484153799589e-02,4.797609735116066254e-01,-5.475217720666960414e-02,8.476869101482767954e-01,-1.444180509880557128e-01,-3.459210837710319231e-01,8.251230611383204849e-02,-5.985677071252465745e-03,-1.815963020596604235e-02,-1.564344650394387456e-02,-1.100000000000000006e-01,-7.491381838416685257e-01,1.564344650394387456e-02,1.100000000000000006e-01,-6.108618161583315720e-01,2.352023509167650711e-02,-1.258355877326209626e-01,-4.148672583108582446e-01,7.647976490832367191e-02,9.416441226737902459e-02,-3.251327416891418576e-01
+-6.773332858452736360e-01,4.934908311176537665e-02,-1.498575406396586429e-01,-1.673834903915831507e-02,4.945905135244424433e-01,-2.485129274928282034e-02,8.412338040721422106e-01,-1.329767390243410119e-01,-3.118859117684040227e-01,1.008067836222791280e-01,-3.185372749515414260e-03,-1.664499566594886126e-02,-3.090169943741787398e-02,-1.100000000000000006e-01,-7.465739561406783409e-01,3.090169943741787398e-02,1.100000000000000006e-01,-6.134260438593217568e-01,1.542370227633176050e-02,-1.237295995021472084e-01,-4.108629113599179261e-01,8.457629772366841159e-02,9.627040049785279274e-02,-3.291370886400821760e-01
+-6.991592328518632105e-01,7.673188385273251727e-03,-1.516888329904885202e-01,-1.515302578486685432e-02,5.007475828906632342e-01,2.725583435020384471e-03,8.177541401321539727e-01,-1.240306783858464990e-01,-2.714130818283543300e-01,1.190744289965216668e-01,-7.917428048850162856e-04,-1.474786567660292189e-02,-4.539904997388274910e-02,-1.100000000000000006e-01,-7.423704566932114446e-01,4.539904997388274910e-02,1.100000000000000006e-01,-6.176295433067886531e-01,8.178552663096479158e-03,-1.212855429660021495e-01,-4.058523839150686707e-01,9.182144733690336680e-02,9.871445703399785165e-02,-3.341476160849311539e-01
+-7.098632864868895664e-01,-2.963590179849938736e-02,-1.487310921673873909e-01,-1.254818146292216961e-02,4.994660274918782394e-01,2.728787781463285975e-02,7.809684223238867462e-01,-1.178014005988303609e-01,-2.278042664177136745e-01,1.370588412564394121e-01,1.026656369138102386e-03,-1.252216408642056397e-02,-5.877852522918149136e-02,-1.100000000000000006e-01,-7.366311896062798237e-01,5.877852522918149136e-02,1.100000000000000006e-01,-6.233688103937202740e-01,1.963185880722147225e-03,-1.185635989074644986e-01,-3.999590517909903387e-01,9.803681411927772649e-02,1.014364010925355025e-01,-3.400409482090094859e-01
+-7.103901144866080486e-01,-6.161585822187345268e-02,-1.416878746226810926e-01,-9.217067175102721180e-03,4.917885642703974658e-01,4.810022722820520708e-02,7.340487569100377918e-01,-1.146525911131295317e-01,-1.832300851385227913e-01,1.545832616035637264e-01,2.367965080441195892e-03,-1.002054977265296430e-02,-7.071067811859728380e-02,-1.100000000000000006e-01,-7.294974746830986678e-01,7.071067811859728380e-02,1.100000000000000006e-01,-6.305025253169014299e-01,-3.069355112990022894e-03,-1.156307906228696142e-01,-3.933280283834251212e-01,1.030693551129901187e-01,1.043692093771303869e-01,-3.466719716165750365e-01
+-7.018536152212035972e-01,-8.723604095422006488e-02,-1.314589164208404271e-01,-5.483080761104541789e-03,4.787833981385761772e-01,6.436012173369785871e-02,6.803817301688591668e-01,-1.151334353455614606e-01,-1.398613826582617292e-01,1.715712081078248630e-01,3.411449538230483178e-03,-7.290000459088142107e-03,-8.090169943744661418e-02,-1.100000000000000006e-01,-7.211449676605194981e-01,8.090169943744661418e-02,1.100000000000000006e-01,-6.388550323394805996e-01,-6.795152456728396906e-03,-1.125593335856171495e-01,-3.861225914957728822e-01,1.067951524567284649e-01,1.074406664143828516e-01,-3.538774085042272755e-01
+-6.854951399745197183e-01,-1.053548694612323061e-01,-1.190053900479758342e-01,-1.678016517615415646e-03,4.615221586757776162e-01,7.516005639094369695e-02,6.233272708745123403e-01,-1.200377521512794587e-01,-9.974724695738512725e-02,1.880758526935418784e-01,4.366040839589445562e-03,-4.369022085701668168e-03,-8.910065241879933096e-02,-1.100000000000000006e-01,-7.117793349818197779e-01,8.910065241879933096e-02,1.100000000000000006e-01,-6.482206650181803198e-01,-9.122464654677954476e-03,-1.094248572615455911e-01,-3.785201628976812560e-01,1.091224646546779947e-01,1.105751427384544100e-01,-3.614798371023189016e-01
+-6.625800878603901323e-01,-1.146620808150715237e-01,-1.052190971445892687e-01,1.890103040904786251e-03,4.410041489839902074e-01,7.943570573496597231e-02,5.658964679618160298e-01,-1.304791654638970400e-01,-6.461523056288023814e-02,2.043186048996321058e-01,5.419406970879468710e-03,-1.287435098155385047e-03,-9.510565162948989015e-02,-1.100000000000000006e-01,-7.016311896063012199e-01,9.510565162948989015e-02,1.100000000000000006e-01,-6.583688103936988778e-01,-9.993985556618824317e-03,-1.063045428604839637e-01,-3.707079396122489601e-01,1.099939855566188229e-01,1.136954571395160374e-01,-3.692920603877508645e-01
+-6.342675291554873418e-01,-1.136141537209327673e-01,-9.083235139054529617e-02,4.987495030821883883e-03,4.180607698342523881e-01,7.590858215733861658e-02,5.104581687395610690e-01,-1.479745070380227845e-01,-3.567820158605954778e-02,2.207334564716707248e-01,6.698175941155322735e-03,1.929766589085969101e-03,-9.876883405950077910e-02,-1.100000000000000006e-01,-6.909504125528735941e-01,9.876883405950077910e-02,1.100000000000000006e-01,-6.690495874471265036e-01,-9.388255425533099940e-03,-1.032752228787164467e-01,-3.628782845040465221e-01,1.093882554255331402e-01,1.167247771212835544e-01,-3.771217154959533024e-01
+-6.015091030976941200e-01,-1.003892154378699386e-01,-7.639017382004398282e-02,7.536003586165652794e-03,3.932898026093570309e-01,6.304935679364573331e-02,4.585879697263228194e-01,-1.745055716378808297e-01,-1.353823766732497810e-02,2.380022910155980831e-01,8.248665217426405516e-03,5.252174634705539941e-03,-1.000000000000000056e-01,-1.100000000000000006e-01,-6.800000000000581135e-01,1.000000000000000056e-01,1.100000000000000006e-01,-6.799999999999419842e-01,-7.320189347551117609e-03,-1.004114892279305005e-01,-3.552239896669727726e-01,1.073201893475510538e-01,1.195885107720695006e-01,-3.847760103330273851e-01
+-5.650199172976666517e-01,-7.293045398977091032e-02,-6.227748628626445654e-02,9.739606996804818853e-03,3.670525667965486294e-01,3.912876259719187677e-02,4.111058022738272588e-01,-2.124776593388982837e-01,1.772078937242948897e-03,2.570391413964312477e-01,1.003981562872092483e-02,8.624325639679320324e-03,-9.876883405952685546e-02,-1.100000000000000006e-01,-6.690495874472416338e-01,9.876883405952685546e-02,1.100000000000000006e-01,-6.909504125527584639e-01,-3.840709973030771718e-03,-9.778385653479580719e-02,-3.479335292430652538e-01,1.038407099730306871e-01,1.222161434652041939e-01,-3.920664707569349039e-01
+-5.253190287862662400e-01,-2.922878092807889433e-02,-4.877165008309399669e-02,1.225311428516621254e-02,3.395273341132789557e-01,2.497974193569896251e-03,3.682489008910518891e-01,-2.643954788334814121e-01,1.064761765340655267e-02,2.788295816934508453e-01,1.198181587143466037e-02,1.193481551185709283e-02,-9.510565162954137675e-02,-1.100000000000000006e-01,-6.583688103938097891e-01,9.510565162954137675e-02,1.100000000000000006e-01,-7.016311896061903086e-01,9.645063680973134379e-04,-9.545702583683016162e-02,-3.411864185636112046e-01,9.903549363190256027e-02,1.245429741631698395e-01,-3.988135814363889531e-01
+-4.828051591287101374e-01,3.191699582419949693e-02,-3.609134982029173905e-02,1.631742097924921558e-02,3.107876914955537417e-01,-4.768801171408555001e-02,3.298837045301186155e-01,-3.319682847508036438e-01,1.374068819078185823e-02,3.039753575646100825e-01,1.395079121638616478e-02,1.498012027511910066e-02,-8.910065241887497878e-02,-1.100000000000000006e-01,-6.482206650182842367e-01,8.910065241887497878e-02,1.100000000000000006e-01,-7.117793349817158610e-01,6.977139301916158998e-03,-9.348829142812571658e-02,-3.351487938859149529e-01,9.302286069808399227e-02,1.265117085718742707e-01,-4.048512061140849272e-01
+-4.378336598938476487e-01,1.095522403405731759e-01,-2.442778464486725434e-02,2.363195766963146691e-02,2.808774127909186014e-01,-1.102372783051317473e-01,2.956860640218050285e-01,-4.144794111092000022e-01,1.181813277409408426e-02,3.318676187594551408e-01,1.581207081669545877e-02,1.744878856002335041e-02,-8.090169943754454973e-02,-1.100000000000000006e-01,-6.388550323395749686e-01,8.090169943754454973e-02,1.100000000000000006e-01,-7.211449676604251291e-01,1.404913785080997429e-02,-9.192613008367984950e-02,-3.299693215672694357e-01,8.595086214919020473e-02,1.280738699163201377e-01,-4.100306784327304443e-01
+-3.907770986533608548e-01,1.980260120080665764e-01,-1.395745259042569311e-02,3.546144753770327090e-02,2.498681818961887291e-01,-1.798060562163568410e-01,2.652653009988722443e-01,-5.040411986077871775e-01,5.665123502656384605e-03,3.478089728115644208e-01,1.743836329117342751e-02,1.886183327922870412e-02,-7.071067811871460662e-02,-1.100000000000000006e-01,-6.305025253169835864e-01,7.071067811871460662e-02,1.100000000000000006e-01,-7.294974746830165113e-01,2.200636593988805276e-02,-9.080900740030896368e-02,-3.257755374058424191e-01,7.799363406011176891e-02,1.291909925996910236e-01,-4.142244625941576275e-01
+-3.420655581769730391e-01,2.895443045999837595e-01,-4.841596824662513718e-03,5.160187264014077374e-02,2.178979182518414326e-01,-2.492728734049994566e-01,2.382376078106958617e-01,-5.905773675883370100e-01,-3.968751817744928592e-03,3.489874358007227784e-01,1.872202140057827036e-02,1.860051970969755358e-02,-5.877852522931630713e-02,-1.100000000000000006e-01,-6.233688103937887748e-01,5.877852522931630713e-02,1.100000000000000006e-01,-7.366311896062113229e-01,3.065289020507063270e-02,-9.016443064599534429e-02,-3.226707062860602049e-01,6.934710979492916816e-02,1.298355693540046429e-01,-4.173292937139398417e-01
+-2.922088815132616868e-01,3.793666227245051648e-01,2.782043068082193198e-03,7.120691345984959952e-02,1.851921758807710539e-01,-3.145830796544347718e-01,2.142641032480709640e-01,-6.714023036863835392e-01,-1.639386155509828247e-02,3.490610897375451827e-01,1.958198324588041744e-02,1.703940665431648641e-02,-4.539904997403121367e-02,-1.100000000000000006e-01,-6.176295433068416108e-01,4.539904997403121367e-02,1.100000000000000006e-01,-7.423704566931584869e-01,3.977580452278046963e-02,-9.000827143965775545e-02,-3.207312794544353030e-01,6.022419547721932775e-02,1.299917285603422457e-01,-4.192687205455646882e-01
+-2.418044428700637238e-01,4.622966703087542650e-01,8.810760645461976348e-03,9.227356492614841033e-02,1.520718893939320970e-01,-3.717175438092844009e-01,1.930679167302581101e-01,-7.407176961217154521e-01,-3.098756273247008086e-02,3.490656931085965309e-01,1.996643096950594456e-02,1.457753668249464965e-02,-3.090169943757635485e-02,-1.100000000000000006e-01,-6.134260438593578391e-01,3.090169943757635485e-02,1.100000000000000006e-01,-7.465739561406422586e-01,4.915047246529923725e-02,-9.034437493921892992e-02,-3.200050120361510042e-01,5.084952753470099035e-02,1.296556250607810712e-01,-4.199949879638489869e-01
+-1.915338529944496659e-01,5.348385334529938140e-01,1.318858593749966737e-02,1.124415214075246972e-01,1.189504629205506009e-01,-4.184620240909112665e-01,1.744406738136731194e-01,-7.942577162622214137e-01,-4.719277263845660791e-02,3.490659808192872471e-01,1.985221780113002529e-02,1.166413896013764571e-02,-1.564344650410845472e-02,-1.100000000000000006e-01,-6.108618161583498907e-01,1.564344650410845472e-02,1.100000000000000006e-01,-7.491381838416502070e-01,5.854605859514215582e-02,-9.116446516105608522e-02,-3.205097871453888025e-01,4.145394140485807177e-02,1.288355348389439159e-01,-4.194902128546111886e-01
+-1.421519329444716206e-01,5.953693400277619840e-01,1.591602986309351847e-02,1.297194457235104903e-01,8.632316183603457038e-02,-4.543397535387353470e-01,1.582451059999656906e-01,-8.301158477193504304e-01,-6.451373185717575176e-02,3.490659988012054238e-01,1.924197278445818546e-02,8.703821904382201546e-03,-8.634312696477998575e-14,-1.100000000000000006e-01,-6.100000000000000977e-01,8.634312696477998575e-14,1.100000000000000006e-01,-7.500000000000000000e-01,6.773121239963071638e-02,-9.244834876218425979e-02,-3.222331755437068956e-01,3.226878760036908794e-02,1.275516512378157274e-01,-4.177668244562930400e-01
+-9.447163462334347284e-02,6.433256773730590128e-01,1.705646484153782588e-02,1.426945809657942932e-01,5.475217720668317661e-02,-4.797609735115977991e-01,1.444180509880604590e-01,-8.476869101482736868e-01,-8.251230611382491531e-02,3.459210837710431918e-01,1.815963020596720809e-02,5.985677071253539538e-03,1.564344650393719241e-02,-1.100000000000000006e-01,-6.108618161583309059e-01,-1.564344650393719241e-02,1.100000000000000006e-01,-7.491381838416691918e-01,7.647976490831985552e-02,-9.416441226737819192e-02,-3.251327416891402478e-01,2.352023509167996615e-02,1.258355877326217953e-01,-4.148672583108596323e-01
+-4.934908311178312634e-02,6.773332858452626448e-01,1.673834903915870365e-02,1.498575406396567278e-01,2.485129274929456789e-02,-4.945905135244382245e-01,1.329767390243463410e-01,-8.412338040721477617e-01,-1.008067836222735214e-01,3.118859117684195659e-01,1.664499566594950658e-02,3.185372749516463767e-03,3.090169943741211817e-02,-1.100000000000000006e-01,-6.134260438593205356e-01,-3.090169943741211817e-02,1.100000000000000006e-01,-7.465739561406795621e-01,8.457629772366526133e-02,-9.627040049785191844e-02,-3.291370886400802886e-01,1.542370227633491075e-02,1.237295995021480827e-01,-4.108629113599198135e-01
+-7.673188385291011826e-03,6.991592328518567712e-01,1.515302578486773036e-02,1.516888329904889920e-01,-2.725583435008649066e-03,-5.007475828906625681e-01,1.240306783858505096e-01,-8.177541401321680725e-01,-1.190744289965141867e-01,2.714130818283730928e-01,1.474786567660371639e-02,7.917428048858461340e-04,4.539904997387671920e-02,-1.100000000000000006e-01,-6.176295433067864327e-01,-4.539904997387671920e-02,1.100000000000000006e-01,-7.423704566932136650e-01,9.182144733690061900e-02,-9.871445703399674143e-02,-3.341476160849289334e-01,8.178552663099553088e-03,1.212855429660032597e-01,-4.058523839150711687e-01
+2.963590179848373668e-02,7.098632864868872350e-01,1.254818146292339433e-02,1.487310921673896391e-01,-2.728787781462233344e-02,-4.994660274918802934e-01,1.178014005988332058e-01,-7.809684223239050649e-01,-1.370588412564321679e-01,2.278042664177327425e-01,1.252216408641931497e-02,-1.026656369137440373e-03,5.877852522917603045e-02,-1.100000000000000006e-01,-6.233688103937174985e-01,-5.877852522917603045e-02,1.100000000000000006e-01,-7.366311896062825992e-01,9.803681411927542277e-02,-1.014364010925342813e-01,-3.400409482090069324e-01,1.963185880724714616e-03,1.185635989074657198e-01,-3.999590517909931697e-01
+6.161585822186143452e-02,7.103901144866096029e-01,9.217067175104195695e-03,1.416878746226848396e-01,-4.810022722819748409e-02,-4.917885642704019622e-01,1.146525911131296843e-01,-7.340487569100592191e-01,-1.545832616035563989e-01,1.832300851385421092e-01,1.002054977265399126e-02,-2.367965080440729685e-03,7.071067811859250984e-02,-1.100000000000000006e-01,-6.305025253168980992e-01,-7.071067811859250984e-02,1.100000000000000006e-01,-7.294974746831019985e-01,1.030693551129881341e-01,-1.043692093771290963e-01,-3.466719716165718723e-01,-3.069355112988218781e-03,1.156307906228709048e-01,-3.933280283834279523e-01
+8.723604095421104432e-02,7.018536152212093704e-01,5.483080761106143806e-03,1.314589164208455618e-01,-6.436012173369229372e-02,-4.787833981385830051e-01,1.151334353455597675e-01,-6.803817301688837027e-01,-1.715712081078173967e-01,1.398613826582798259e-01,7.290000459089334729e-03,-3.411449538230051232e-03,8.090169943744263126e-02,-1.100000000000000006e-01,-6.388550323394767139e-01,-8.090169943744263126e-02,1.100000000000000006e-01,-7.211449676605233838e-01,1.067951524567271049e-01,-1.074406664143815193e-01,-3.538774085042239448e-01,-6.795152456727154844e-03,1.125593335856184818e-01,-3.861225914957758798e-01
+1.053548694612267411e-01,6.854951399745277119e-01,1.678016517616868260e-03,1.190053900479810661e-01,-7.516005639094061608e-02,-4.615221586757852212e-01,1.200377521512768497e-01,-6.233272708745353219e-01,-1.880758526935358554e-01,9.974724695740039282e-02,4.369022085702815687e-03,-4.366040839589016218e-03,8.910065241879658315e-02,-1.100000000000000006e-01,-6.482206650181765450e-01,-8.910065241879658315e-02,1.100000000000000006e-01,-7.117793349818235527e-01,1.091224646546773425e-01,-1.105751427384531888e-01,-3.614798371023157375e-01,-9.122464654677302220e-03,1.094248572615468124e-01,-3.785201628976844201e-01
+1.146620808150695947e-01,6.625800878604010125e-01,-1.890103040903309351e-03,1.052190971445953610e-01,-7.943570573496568088e-02,-4.410041489839994222e-01,1.304791654638912668e-01,-5.658964679618403437e-01,-2.043186048996253334e-01,6.461523056289404654e-02,1.287435098156813808e-03,-5.419406970878914466e-03,9.510565162948780848e-02,-1.100000000000000006e-01,-6.583688103936943259e-01,-9.510565162948780848e-02,1.100000000000000006e-01,-7.016311896063057718e-01,1.099939855566187674e-01,-1.136954571395147051e-01,-3.692920603877476449e-01,-9.993985556618761867e-03,1.063045428604852960e-01,-3.707079396122525128e-01
+1.136141537209357510e-01,6.342675291554998873e-01,-4.987495030820601923e-03,9.083235139055134688e-02,-7.590858215734223868e-02,-4.180607698342622691e-01,1.479745070380133753e-01,-5.104581687395832734e-01,-2.207334564716642855e-01,3.567820158607019204e-02,-1.929766589084550964e-03,-6.698175941154750276e-03,9.876883405949972439e-02,-1.100000000000000006e-01,-6.690495874471218407e-01,-9.876883405949972439e-02,1.100000000000000006e-01,-6.909504125528782570e-01,1.093882554255336814e-01,-1.167247771212822777e-01,-3.771217154959501383e-01,-9.388255425533710563e-03,1.032752228787177234e-01,-3.628782845040500749e-01
+1.003892154378781543e-01,6.015091030977093300e-01,-7.536003586164687421e-03,7.639017382005028334e-02,-6.304935679365321344e-02,-3.932898026093682997e-01,1.745055716378677291e-01,-4.585879697263448018e-01,-2.380022910155907001e-01,1.353823766733323539e-02,-5.252174634704120937e-03,-8.248665217425680402e-03,1.000000000000000056e-01,-1.100000000000000006e-01,-6.799999999999372102e-01,-1.000000000000000056e-01,1.100000000000000006e-01,-6.800000000000628875e-01,1.073201893475523166e-01,-1.195885107720683072e-01,-3.847760103330239989e-01,-7.320189347552255588e-03,1.004114892279316940e-01,-3.552239896669758257e-01
+7.293045398978559302e-02,5.650199172976835271e-01,-9.739606996803793632e-03,6.227748628627057664e-02,-3.912876259720442923e-02,-3.670525667965605643e-01,2.124776593388797430e-01,-4.111058022738475204e-01,-2.570391413964229210e-01,-1.772078937237518345e-03,-8.624325639677818053e-03,-1.003981562872013900e-02,9.876883405952791017e-02,-1.100000000000000006e-01,-6.909504125527538010e-01,-9.876883405952791017e-02,1.100000000000000006e-01,-6.690495874472462967e-01,1.038407099730325744e-01,-1.222161434652031115e-01,-3.920664707569316842e-01,-3.840709973032471747e-03,9.778385653479688966e-02,-3.479335292430681403e-01
+2.922878092810021408e-02,5.253190287862826713e-01,-1.225311428516509017e-02,4.877165008309911065e-02,-2.497974193587382263e-03,-3.395273341132899469e-01,2.643954788334569872e-01,-3.682489008910679318e-01,-2.788295816934404092e-01,-1.064761765340419691e-02,-1.193481551185560444e-02,-1.198181587143392138e-02,9.510565162954326413e-02,-1.100000000000000006e-01,-7.016311896061863118e-01,-9.510565162954326413e-02,1.100000000000000006e-01,-6.583688103938137859e-01,9.903549363190478072e-02,-1.245429741631690068e-01,-3.988135814363863441e-01,9.645063680950999307e-04,9.545702583683099429e-02,-3.411864185636138136e-01
+-3.191699582416846620e-02,4.828051591287281785e-01,-1.631742097924693963e-02,3.609134982029678362e-02,4.768801171406052836e-02,-3.107876914955658432e-01,3.319682847507699486e-01,-3.298837045301331594e-01,-3.039753575645984807e-01,-1.374068819078193109e-02,-1.498012027511802860e-02,-1.395079121638535466e-02,8.910065241887804577e-02,-1.100000000000000006e-01,-7.117793349817116422e-01,-8.910065241887804577e-02,1.100000000000000006e-01,-6.482206650182884555e-01,9.302286069808667068e-02,-1.265117085718735213e-01,-4.048512061140826512e-01,6.977139301913182212e-03,9.348829142812646598e-02,-3.351487938859175064e-01
+-1.095522403405353451e-01,4.378336598938666890e-01,-2.363195766962724459e-02,2.442778464487183054e-02,1.102372783051017435e-01,-2.808774127909313689e-01,4.144794111091603117e-01,-2.956860640218180181e-01,-3.318676187594422622e-01,-1.181813277409622664e-02,-1.744878856002242754e-02,-1.581207081669481346e-02,8.090169943754853266e-02,-1.100000000000000006e-01,-7.211449676604213543e-01,-8.090169943754853266e-02,1.100000000000000006e-01,-6.388550323395787434e-01,8.595086214919328560e-02,-1.280738699163195549e-01,-4.100306784327285015e-01,1.404913785080654648e-02,9.192613008368043237e-02,-3.299693215672716007e-01
+-1.980260120080288566e-01,3.907770986533822821e-01,-3.546144753769739366e-02,1.395745259043009237e-02,1.798060562163277809e-01,-2.498681818962026346e-01,5.040411986077506512e-01,-2.652653009988854005e-01,-3.478089728115628665e-01,-5.665123502659271185e-03,-1.886183327922846820e-02,-1.743836329117275791e-02,7.071067811871939446e-02,-1.100000000000000006e-01,-7.294974746830131807e-01,-7.071067811871939446e-02,1.100000000000000006e-01,-6.305025253169869170e-01,7.799363406011554367e-02,-1.291909925996906627e-01,-4.142244625941560177e-01,2.200636593988464229e-02,9.080900740030933838e-02,-3.257755374058439179e-01
+-2.895443045999456788e-01,3.420655581769950770e-01,-5.160187264013321035e-02,4.841596824666163576e-03,2.492728734049711736e-01,-2.178979182518558932e-01,5.905773675883022600e-01,-2.382376078107077688e-01,-3.489874358007226673e-01,3.968751817741065363e-03,-1.860051970969792134e-02,-1.872202140057794076e-02,5.877852522932178192e-02,-1.100000000000000006e-01,-7.366311896062085474e-01,-5.877852522932178192e-02,1.100000000000000006e-01,-6.233688103937915503e-01,6.934710979493320659e-02,-1.298355693540044764e-01,-4.173292937139386760e-01,3.065289020506698978e-02,9.016443064599551083e-02,-3.226707062860612041e-01
+-3.793666227244701372e-01,2.922088815132815598e-01,-7.120691345984121734e-02,-2.782043068079513917e-03,3.145830796544101804e-01,-1.851921758807837937e-01,6.714023036863524529e-01,-2.142641032480801788e-01,-3.490610897375451271e-01,1.639386155509396995e-02,-1.703940665431744744e-02,-1.958198324588011907e-02,4.539904997403660519e-02,-1.100000000000000006e-01,-7.423704566931565996e-01,-4.539904997403660519e-02,1.100000000000000006e-01,-6.176295433068434981e-01,6.022419547722311639e-02,-1.299917285603422734e-01,-4.192687205455641886e-01,3.977580452277667405e-02,9.000827143965771382e-02,-3.207312794544358581e-01
+-4.622966703087194040e-01,2.418044428700844017e-01,-9.227356492613900119e-02,-8.810760645459835699e-03,3.717175438092611417e-01,-1.520718893939459471e-01,7.407176961216875855e-01,-1.930679167302654653e-01,-3.490656931085965309e-01,3.098756273246296156e-02,-1.457753668249591947e-02,-1.996643096950598273e-02,3.090169943758278720e-02,-1.100000000000000006e-01,-7.465739561406408153e-01,-3.090169943758278720e-02,1.100000000000000006e-01,-6.134260438593592824e-01,5.084952753470482756e-02,-1.296556250607813210e-01,-4.199949879638489314e-01,4.915047246529495595e-02,9.034437493921868012e-02,-3.200050120361510597e-01
+-5.348385334529638380e-01,1.915338529944704826e-01,-1.124415214075160513e-01,-1.318858593749817898e-02,4.184620240908928368e-01,-1.189504629205645203e-01,7.942577162622004305e-01,-1.744406738136797808e-01,-3.490659808192872471e-01,4.719277263844909309e-02,-1.166413896013891206e-02,-1.985221780113016754e-02,1.564344650411513341e-02,-1.100000000000000006e-01,-7.491381838416495409e-01,-1.564344650411513341e-02,1.100000000000000006e-01,-6.108618161583505568e-01,4.145394140486187429e-02,-1.288355348389443600e-01,-4.194902128546116327e-01,5.854605859513791616e-02,9.116446516105562725e-02,-3.205097871453883029e-01
+-5.953693400277392245e-01,1.421519329444935476e-01,-1.297194457235040788e-01,-1.591602986309269274e-02,4.543397535387224684e-01,-8.632316183604900328e-02,8.301158477193393281e-01,-1.582451059999734344e-01,-3.490659988012054238e-01,6.451373185716886838e-02,-8.703821904383424526e-03,-1.924197278445863996e-02,9.310552942249240346e-14,-1.100000000000000006e-01,-7.500000000000000000e-01,-9.310552942249240346e-14,1.100000000000000006e-01,-6.100000000000000977e-01,3.226878760037316107e-02,-1.275516512378163658e-01,-4.177668244562940947e-01,6.773121239962703877e-02,9.244834876218362141e-02,-3.222331755437059519e-01
+-6.433256773730421374e-01,9.447163462336426176e-02,-1.426945809657901576e-01,-1.705646484153763853e-02,4.797609735115896945e-01,-5.475217720669693644e-02,8.476869101482722435e-01,-1.444180509880667318e-01,-3.459210837710548492e-01,8.251230611381739355e-02,-5.985677071254597720e-03,-1.815963020596776320e-02,-1.564344650393051372e-02,-1.100000000000000006e-01,-7.491381838416699690e-01,1.564344650393051372e-02,1.100000000000000006e-01,-6.108618161583301287e-01,2.352023509168378948e-02,-1.258355877326226280e-01,-4.148672583108612422e-01,7.647976490831639995e-02,9.416441226737737313e-02,-3.251327416891388600e-01
+-6.773332858452505434e-01,4.934908311180081358e-02,-1.498575406396548404e-01,-1.673834903915917896e-02,4.945905135244337836e-01,-2.485129274930628768e-02,8.412338040721544230e-01,-1.329767390243494218e-01,-3.118859117684361082e-01,1.008067836222651392e-01,-3.185372749517640344e-03,-1.664499566595028721e-02,-3.090169943740568581e-02,-1.100000000000000006e-01,-7.465739561406810054e-01,3.090169943740568581e-02,1.100000000000000006e-01,-6.134260438593190923e-01,1.542370227633805407e-02,-1.237295995021490680e-01,-4.108629113599216454e-01,8.457629772366176413e-02,9.627040049785093312e-02,-3.291370886400782902e-01
+-6.991592328518489996e-01,7.673188385307384146e-03,-1.516888329904888255e-01,-1.515302578486878160e-02,5.007475828906612358e-01,2.725583434997580663e-03,8.177541401321797299e-01,-1.240306783858530215e-01,-2.714130818283906899e-01,1.190744289965059016e-01,-7.917428048867958951e-04,-1.474786567660489600e-02,-4.539904997387069624e-02,-1.100000000000000006e-01,-7.423704566932157745e-01,4.539904997387069624e-02,1.100000000000000006e-01,-6.176295433067843232e-01,8.178552663102300890e-03,-1.212855429660043838e-01,-4.058523839150733892e-01,9.182144733689753813e-02,9.871445703399561733e-02,-3.341476160849264909e-01
+-7.098632864868846815e-01,-2.963590179846941827e-02,-1.487310921673917208e-01,-1.254818146292473353e-02,4.994660274918822918e-01,2.728787781461300410e-02,7.809684223239230505e-01,-1.178014005988345242e-01,-2.278042664177516163e-01,1.370588412564242298e-01,1.026656369136824979e-03,-1.252216408642149725e-02,-5.877852522917055567e-02,-1.100000000000000006e-01,-7.366311896062853748e-01,5.877852522917055567e-02,1.100000000000000006e-01,-6.233688103937147229e-01,1.963185880727011390e-03,-1.185635989074669411e-01,-3.999590517909957788e-01,9.803681411927286926e-02,1.014364010925330600e-01,-3.400409482090041013e-01
+-7.103901144866114903e-01,-6.161585822184846573e-02,-1.416878746226887531e-01,-9.217067175105803783e-03,4.917885642704064031e-01,4.810022722818909496e-02,7.340487569100814236e-01,-1.146525911131308639e-01,-1.832300851385612883e-01,1.545832616035490437e-01,2.367965080440230952e-03,-1.002054977265519689e-02,-7.071067811858772201e-02,-1.100000000000000006e-01,-7.294974746831053292e-01,7.071067811858772201e-02,1.100000000000000006e-01,-6.305025253168947685e-01,-3.069355112986234257e-03,-1.156307906228722093e-01,-3.933280283834311164e-01,1.030693551129863439e-01,1.043692093771277918e-01,-3.466719716165690413e-01
+-7.018536152212142554e-01,-8.723604095420114946e-02,-1.314589164208502803e-01,-5.483080761107795263e-03,4.787833981385893889e-01,6.436012173368615974e-02,6.803817301689071284e-01,-1.151334353455591292e-01,-1.398613826582975894e-01,1.715712081078102635e-01,3.411449538229650944e-03,-7.290000459090521280e-03,-8.090169943743866221e-02,-1.100000000000000006e-01,-7.211449676605271586e-01,8.090169943743866221e-02,1.100000000000000006e-01,-6.388550323394729391e-01,-6.795152456725780943e-03,-1.125593335856198279e-01,-3.861225914957792660e-01,1.067951524567258559e-01,1.074406664143801732e-01,-3.538774085042208917e-01
+-6.854951399745359275e-01,-1.053548694612208431e-01,-1.190053900479869642e-01,-1.678016517618472229e-03,4.615221586757941030e-01,7.516005639093734092e-02,6.233272708745597468e-01,-1.200377521512735884e-01,-9.974724695741782332e-02,1.880758526935287778e-01,4.366040839589003207e-03,-4.369022085704137547e-03,-8.910065241879350229e-02,-1.100000000000000006e-01,-7.117793349818277715e-01,8.910065241879350229e-02,1.100000000000000006e-01,-6.482206650181723262e-01,-9.122464654676649964e-03,-1.094248572615481585e-01,-3.785201628976875843e-01,1.091224646546766208e-01,1.105751427384518426e-01,-3.614798371023122403e-01
+-6.625800878604121147e-01,-1.146620808150677767e-01,-1.052190971446015227e-01,1.890103040901852617e-03,4.410041489840089146e-01,7.943570573496550047e-02,5.658964679618646576e-01,-1.304791654638851883e-01,-6.461523056290779943e-02,2.043186048996180892e-01,5.419406970878420937e-03,-1.287435098158141739e-03,-9.510565162948571294e-02,-1.100000000000000006e-01,-7.016311896063102127e-01,9.510565162948571294e-02,1.100000000000000006e-01,-6.583688103936898850e-01,-9.993985556618713295e-03,-1.063045428604866283e-01,-3.707079396122557324e-01,1.099939855566187119e-01,1.136954571395133728e-01,-3.692920603877440922e-01
+-6.342675291555139871e-01,-1.136141537209386237e-01,-9.083235139055786944e-02,4.987495030819388483e-03,4.180607698342731493e-01,7.590858215734563874e-02,5.104581687396078093e-01,-1.479745070380040495e-01,-3.567820158608165509e-02,2.207334564716570691e-01,6.698175941154138786e-03,1.929766589083134996e-03,-9.876883405949866968e-02,-1.100000000000000006e-01,-6.909504125528830309e-01,9.876883405949866968e-02,1.100000000000000006e-01,-6.690495874471170668e-01,-9.388255425534258736e-03,-1.032752228787190002e-01,-3.628782845040532390e-01,1.093882554255342920e-01,1.167247771212810009e-01,-3.771217154959465856e-01
+-6.015091030977238740e-01,-1.003892154378870777e-01,-7.639017382005629242e-02,7.536003586163714241e-03,3.932898026093790134e-01,6.304935679366122092e-02,4.585879697263655630e-01,-1.745055716378535460e-01,-1.353823766734102776e-02,2.380022910155826232e-01,8.248665217424989982e-03,5.252174634702711474e-03,-1.000000000000000056e-01,-1.100000000000000006e-01,-6.800000000000675504e-01,1.000000000000000056e-01,1.100000000000000006e-01,-6.799999999999325473e-01,-7.320189347553511527e-03,-1.004114892279328736e-01,-3.552239896669792674e-01,1.073201893475534685e-01,1.195885107720671275e-01,-3.847760103330208903e-01
+-5.650199172976994033e-01,-7.293045398980134431e-02,-6.227748628627634980e-02,9.739606996802851677e-03,3.670525667965717775e-01,3.912876259721776578e-02,4.111058022738662276e-01,-2.124776593388596480e-01,1.772078937232602139e-03,2.570391413964135952e-01,1.003981562871933061e-02,8.624325639676379968e-03,-9.876883405952896489e-02,-1.100000000000000006e-01,-6.690495874472510707e-01,9.876883405952896489e-02,1.100000000000000006e-01,-6.909504125527490270e-01,-3.840709973034359126e-03,-9.778385653479795825e-02,-3.479335292430713045e-01,1.038407099730342675e-01,1.222161434652020429e-01,-3.920664707569287977e-01
+-5.253190287863011010e-01,-2.922878092812202996e-02,-4.877165008310500177e-02,1.225311428516376484e-02,3.395273341133027145e-01,2.497974193605787679e-03,3.682489008910865280e-01,-2.643954788334322847e-01,1.064761765340123574e-02,2.788295816934308058e-01,1.198181587143306616e-02,1.193481551185422186e-02,-9.510565162954534579e-02,-1.100000000000000006e-01,-6.583688103938183378e-01,9.510565162954534579e-02,1.100000000000000006e-01,-7.016311896061817599e-01,9.645063680928864236e-04,-9.545702583683192410e-02,-3.411864185636164226e-01,9.903549363190725097e-02,1.245429741631680770e-01,-3.988135814363834575e-01
+-4.828051591287477740e-01,3.191699582413941305e-02,-3.609134982030227229e-02,1.631742097924458734e-02,3.107876914955789438e-01,-4.768801171403668632e-02,3.298837045301497017e-01,-3.319682847507386958e-01,1.374068819078127536e-02,3.039753575645875450e-01,1.395079121638444740e-02,1.498012027511686113e-02,-8.910065241888111276e-02,-1.100000000000000006e-01,-6.482206650182926744e-01,8.910065241888111276e-02,1.100000000000000006e-01,-7.117793349817074233e-01,6.977139301910503799e-03,-9.348829142812724313e-02,-3.351487938859197824e-01,9.302286069808965441e-02,1.265117085718727441e-01,-4.048512061140800977e-01
+-4.378336598938875057e-01,1.095522403405000400e-01,-2.442778464487679532e-02,2.363195766962329636e-02,2.808774127909450247e-01,-1.102372783050735994e-01,2.956860640218331171e-01,-4.144794111091232303e-01,1.181813277409754330e-02,3.318676187594303273e-01,1.581207081669406753e-02,1.744878856002156017e-02,-8.090169943755250170e-02,-1.100000000000000006e-01,-6.388550323395826291e-01,8.090169943755250170e-02,1.100000000000000006e-01,-7.211449676604174686e-01,1.404913785080347255e-02,-9.192613008368101524e-02,-3.299693215672735436e-01,8.595086214919669954e-02,1.280738699163189720e-01,-4.100306784327263365e-01
+-3.907770986534021551e-01,1.980260120079890551e-01,-1.395745259043414989e-02,3.546144753769125968e-02,2.498681818962157630e-01,-1.798060562162970277e-01,2.652653009988968358e-01,-5.040411986077121265e-01,5.665123502663429317e-03,3.478089728115615342e-01,1.743836329117215075e-02,1.886183327922823227e-02,-7.071067811872418230e-02,-1.100000000000000006e-01,-6.305025253169903587e-01,7.071067811872418230e-02,1.100000000000000006e-01,-7.294974746830097390e-01,2.200636593988087447e-02,-9.080900740030971308e-02,-3.257755374058455833e-01,7.799363406011894373e-02,1.291909925996902742e-01,-4.142244625941544633e-01
+-3.420655581770155607e-01,2.895443045999051002e-01,-4.841596824669622615e-03,5.160187264012516817e-02,2.178979182518693547e-01,-2.492728734049406702e-01,2.382376078107177886e-01,-5.905773675882647344e-01,-3.968751817735914969e-03,3.489874358007225563e-01,1.872202140057755912e-02,1.860051970969829258e-02,-5.877852522932724283e-02,-1.100000000000000006e-01,-6.233688103937943259e-01,5.877852522932724283e-02,1.100000000000000006e-01,-7.366311896062057718e-01,3.065289020506295481e-02,-9.016443064599569124e-02,-3.226707062860623698e-01,6.934710979493685645e-02,1.298355693540043099e-01,-4.173292937139376768e-01
+-2.922088815133044304e-01,3.793666227244337219e-01,2.782043068076384910e-03,7.120691345983255760e-02,1.851921758807987817e-01,-3.145830796543842567e-01,2.142641032480913088e-01,-6.714023036863213667e-01,-1.639386155508785678e-02,3.490610897375451271e-01,1.958198324587977213e-02,1.703940665431819337e-02,-4.539904997404263509e-02,-1.100000000000000006e-01,-6.176295433068457186e-01,4.539904997404263509e-02,1.100000000000000006e-01,-7.423704566931543791e-01,3.977580452277289236e-02,-9.000827143965768606e-02,-3.207312794544364132e-01,6.022419547722732830e-02,1.299917285603423012e-01,-4.192687205455635224e-01
+-2.418044428701070503e-01,4.622966703086869300e-01,8.810760645457452189e-03,9.227356492613021655e-02,1.520718893939608796e-01,-3.717175438092391593e-01,1.930679167302750687e-01,-7.407176961216622724e-01,-3.098756273245662982e-02,3.490656931085965309e-01,1.996643096950581620e-02,1.457753668249701408e-02,-3.090169943758921609e-02,-1.100000000000000006e-01,-6.134260438593608367e-01,3.090169943758921609e-02,1.100000000000000006e-01,-7.465739561406392610e-01,4.915047246529111874e-02,-9.034437493921843032e-02,-3.200050120361510597e-01,5.084952753470910886e-02,1.296556250607815708e-01,-4.199949879638489314e-01
+-1.915338529944929091e-01,5.348385334529359714e-01,1.318858593749661426e-02,1.124415214075082103e-01,1.189504629205792863e-01,-4.184620240908755728e-01,1.744406738136883295e-01,-7.942577162621823339e-01,-4.719277263844224440e-02,3.490659808192872471e-01,1.985221780113039999e-02,1.166413896014021484e-02,-1.564344650412181556e-02,-1.100000000000000006e-01,-6.108618161583513340e-01,1.564344650412181556e-02,1.100000000000000006e-01,-7.491381838416487637e-01,5.854605859513412058e-02,-9.116446516105518316e-02,-3.205097871453878589e-01,4.145394140486610701e-02,1.288355348389448041e-01,-4.194902128546121323e-01
+-1.421519329445136148e-01,5.953693400277152437e-01,1.591602986309189477e-02,1.297194457234972231e-01,8.632316183606228432e-02,-4.543397535387090347e-01,1.582451059999787357e-01,-8.301158477193273377e-01,-6.451373185716056946e-02,3.490659988012054238e-01,1.924197278445895914e-02,8.703821904384678732e-03,-9.986793188020483379e-14,-1.100000000000000006e-01,-6.100000000000000977e-01,9.986793188020483379e-14,1.100000000000000006e-01,-7.500000000000000000e-01,6.773121239962297258e-02,-9.244834876218296915e-02,-3.222331755437048972e-01,3.226878760037683869e-02,1.275516512378170320e-01,-4.177668244562950384e-01
+-9.447163462338346862e-02,6.433256773730239297e-01,1.705646484153755874e-02,1.426945809657856890e-01,5.475217720670890603e-02,-4.797609735115807572e-01,1.444180509880711449e-01,-8.476869101482694679e-01,-8.251230611380826196e-02,3.459210837710665065e-01,1.815963020596777361e-02,5.985677071255691463e-03,1.564344650392383504e-02,-1.100000000000000006e-01,-6.108618161583293515e-01,-1.564344650392383504e-02,1.100000000000000006e-01,-7.491381838416707462e-01,7.647976490831256968e-02,-9.416441226737654047e-02,-3.251327416891373057e-01,2.352023509168724505e-02,1.258355877326234606e-01,-4.148672583108626299e-01
+-4.934908311182042984e-02,6.773332858452389971e-01,1.673834903915958836e-02,1.498575406396529808e-01,2.485129274931925647e-02,-4.945905135244296202e-01,1.329767390243544734e-01,-8.412338040721615284e-01,-1.008067836222563407e-01,3.118859117684517068e-01,1.664499566595109212e-02,3.185372749518767914e-03,3.090169943739925693e-02,-1.100000000000000006e-01,-6.134260438593175380e-01,-3.090169943739925693e-02,1.100000000000000006e-01,-7.465739561406825597e-01,8.457629772365864163e-02,-9.627040049784994780e-02,-3.291370886400764029e-01,1.542370227634154434e-02,1.237295995021500533e-01,-4.108629113599236993e-01
+-7.673188385325172001e-03,6.991592328518425603e-01,1.515302578486964723e-02,1.516888329904893251e-01,-2.725583434986093324e-03,-5.007475828906604587e-01,1.240306783858570738e-01,-8.177541401321938297e-01,-1.190744289964983937e-01,2.714130818284093971e-01,1.474786567660565928e-02,7.917428048876733399e-04,4.539904997386466634e-02,-1.100000000000000006e-01,-6.176295433067822138e-01,-4.539904997386466634e-02,1.100000000000000006e-01,-7.423704566932178839e-01,9.182144733689479033e-02,-9.871445703399450711e-02,-3.341476160849242150e-01,8.178552663105367881e-03,1.212855429660054940e-01,-4.058523839150758872e-01
+2.963590179845378147e-02,7.098632864868822390e-01,1.254818146292603284e-02,1.487310921673938857e-01,-2.728787781460275536e-02,-4.994660274918840681e-01,1.178014005988373414e-01,-7.809684223239408141e-01,-1.370588412564167913e-01,2.278042664177702126e-01,1.252216408642250166e-02,-1.026656369136122200e-03,5.877852522916508088e-02,-1.100000000000000006e-01,-6.233688103937119473e-01,-5.877852522916508088e-02,1.100000000000000006e-01,-7.366311896062881504e-01,9.803681411927056555e-02,-1.014364010925318388e-01,-3.400409482090015478e-01,1.963185880729571842e-03,1.185635989074681623e-01,-3.999590517909986098e-01
+6.161585822183646838e-02,7.103901144866134887e-01,9.217067175107292176e-03,1.416878746226924446e-01,-4.810022722818136504e-02,-4.917885642704109550e-01,1.146525911131308917e-01,-7.340487569101031839e-01,-1.545832616035412721e-01,1.832300851385803009e-01,1.002054977265626201e-02,-2.367965080439706632e-03,7.071067811858293417e-02,-1.100000000000000006e-01,-6.305025253168914379e-01,-7.071067811858293417e-02,1.100000000000000006e-01,-7.294974746831086598e-01,1.030693551129843455e-01,-1.043692093771265011e-01,-3.466719716165658771e-01,-3.069355112984437084e-03,1.156307906228735000e-01,-3.933280283834339475e-01
+8.723604095419201787e-02,7.018536152212203616e-01,5.483080761109391209e-03,1.314589164208554706e-01,-6.436012173368049760e-02,-4.787833981385963833e-01,1.151334353455576165e-01,-6.803817301689319974e-01,-1.715712081078030471e-01,1.398613826583160746e-01,7.290000459091709566e-03,-3.411449538229212493e-03,8.090169943743469316e-02,-1.100000000000000006e-01,-6.388550323394690533e-01,-8.090169943743469316e-02,1.100000000000000006e-01,-7.211449676605310444e-01,1.067951524567244820e-01,-1.074406664143788270e-01,-3.538774085042175055e-01,-6.795152456724538881e-03,1.125593335856211741e-01,-3.861225914957823191e-01
+1.053548694612146397e-01,6.854951399745444762e-01,1.678016517620096147e-03,1.190053900479923626e-01,-7.516005639093387147e-02,-4.615221586758013195e-01,1.200377521512705631e-01,-6.233272708745841717e-01,-1.880758526935217279e-01,9.974724695743222846e-02,4.369022085705429916e-03,-4.366040839588201765e-03,8.910065241879044917e-02,-1.100000000000000006e-01,-6.482206650181681074e-01,-8.910065241879044917e-02,1.100000000000000006e-01,-7.117793349818319903e-01,1.091224646546759547e-01,-1.105751427384504965e-01,-3.614798371023090762e-01,-9.122464654675914442e-03,1.094248572615495047e-01,-3.785201628976910815e-01
+1.146620808150657644e-01,6.625800878604228838e-01,-1.890103040900415615e-03,1.052190971446074624e-01,-7.943570573496512577e-02,-4.410041489840181850e-01,1.304791654638794429e-01,-5.658964679618886384e-01,-2.043186048996112059e-01,6.461523056292185763e-02,1.287435098159480729e-03,-5.419406970878031492e-03,9.510565162948361739e-02,-1.100000000000000006e-01,-6.583688103936853331e-01,-9.510565162948361739e-02,1.100000000000000006e-01,-7.016311896063147646e-01,1.099939855566186564e-01,-1.136954571395120406e-01,-3.692920603877409280e-01,-9.993985556618650845e-03,1.063045428604879605e-01,-3.707079396122592851e-01
+1.136141537209416214e-01,6.342675291555265327e-01,-4.987495030818170708e-03,9.083235139056396179e-02,-7.590858215734892778e-02,-4.180607698342830858e-01,1.479745070379946681e-01,-5.104581687396301248e-01,-2.207334564716490755e-01,3.567820158609229242e-02,-1.929766589081671323e-03,-6.698175941153465714e-03,9.876883405949761496e-02,-1.100000000000000006e-01,-6.690495874471124038e-01,-9.876883405949761496e-02,1.100000000000000006e-01,-6.909504125528876939e-01,1.093882554255348472e-01,-1.167247771212797242e-01,-3.771217154959434215e-01,-9.388255425534862419e-03,1.032752228787202770e-01,-3.628782845040567362e-01
+1.003892154378953905e-01,6.015091030977394171e-01,-7.536003586162664733e-03,7.639017382006263457e-02,-6.304935679366883983e-02,-3.932898026093903932e-01,1.745055716378401955e-01,-4.585879697263876564e-01,-2.380022910155750737e-01,1.353823766734930586e-02,-5.252174634701222214e-03,-8.248665217424231907e-03,1.000000000000000056e-01,-1.100000000000000006e-01,-6.799999999999277733e-01,-1.000000000000000056e-01,1.100000000000000006e-01,-6.800000000000723244e-01,1.073201893475547175e-01,-1.195885107720659341e-01,-3.847760103330175041e-01,-7.320189347554649506e-03,1.004114892279340671e-01,-3.552239896669823205e-01
+7.293045398981608252e-02,5.650199172977166118e-01,-9.739606996801909722e-03,6.227748628628253930e-02,-3.912876259723031130e-02,-3.670525667965838235e-01,2.124776593388409962e-01,-4.111058022738866002e-01,-2.570391413964051575e-01,-1.772078937227108703e-03,-8.624325639674952290e-03,-1.003981562871850836e-02,9.876883405953001960e-02,-1.100000000000000006e-01,-6.909504125527443641e-01,-9.876883405953001960e-02,1.100000000000000006e-01,-6.690495874472557336e-01,1.038407099730361549e-01,-1.222161434652009743e-01,-3.920664707569256335e-01,-3.840709973036059155e-03,9.778385653479902684e-02,-3.479335292430741911e-01
+2.922878092814513995e-02,5.253190287863179764e-01,-1.225311428516249676e-02,4.877165008311046268e-02,-2.497974193624925149e-03,-3.395273341133142053e-01,2.643954788334059169e-01,-3.682489008911028483e-01,-2.788295816934204807e-01,-1.064761765339913846e-02,-1.193481551185284449e-02,-1.198181587143218318e-02,9.510565162954742746e-02,-1.100000000000000006e-01,-7.016311896061773190e-01,-9.510565162954742746e-02,1.100000000000000006e-01,-6.583688103938227787e-01,9.903549363190945753e-02,-1.245429741631671611e-01,-3.988135814363807929e-01,9.645063680904231163e-04,9.545702583683284004e-02,-3.411864185636193092e-01
+-3.191699582410818109e-02,4.828051591287659816e-01,-1.631742097924224200e-02,3.609134982030733074e-02,4.768801171401146344e-02,-3.107876914955912118e-01,3.319682847507047230e-01,-3.298837045301644677e-01,-3.039753575645753880e-01,-1.374068819078146445e-02,-1.498012027511565723e-02,-1.395079121638367892e-02,8.910065241888419363e-02,-1.100000000000000006e-01,-7.117793349817032045e-01,-8.910065241888419363e-02,1.100000000000000006e-01,-6.482206650182968932e-01,9.302286069809231894e-02,-1.265117085718719947e-01,-4.048512061140777663e-01,6.977139301907527014e-03,9.348829142812799253e-02,-3.351487938859223359e-01
+-1.095522403404658868e-01,4.378336598939039370e-01,-2.363195766961932037e-02,2.442778464488079906e-02,1.102372783050461352e-01,-2.808774127909559049e-01,4.144794111090867039e-01,-2.956860640218439418e-01,-3.318676187594197802e-01,-1.181813277409946537e-02,-1.744878856002081424e-02,-1.581207081669341180e-02,8.090169943755606830e-02,-1.100000000000000006e-01,-7.211449676604141379e-01,-8.090169943755606830e-02,1.100000000000000006e-01,-6.388550323395859598e-01,8.595086214919944734e-02,-1.280738699163184724e-01,-4.100306784327246712e-01,1.404913785080073169e-02,9.192613008368152872e-02,-3.299693215672752089e-01
+-1.980260120079512520e-01,3.907770986534236379e-01,-3.546144753768542407e-02,1.395745259043857170e-02,1.798060562162676901e-01,-2.498681818962300849e-01,5.040411986076758222e-01,-2.652653009989101029e-01,-3.478089728115600909e-01,-5.665123502666617739e-03,-1.886183327922804492e-02,-1.743836329117152278e-02,7.071067811872895625e-02,-1.100000000000000006e-01,-7.294974746830064083e-01,-7.071067811872895625e-02,1.100000000000000006e-01,-6.305025253169936894e-01,7.799363406012271849e-02,-1.291909925996898856e-01,-4.142244625941527980e-01,2.200636593987746747e-02,9.080900740031010165e-02,-3.257755374058470821e-01
+-2.895443045998669085e-01,3.420655581770375431e-01,-5.160187264011766722e-02,4.841596824673412985e-03,2.492728734049126649e-01,-2.178979182518837876e-01,5.905773675882295404e-01,-2.382376078107296680e-01,-3.489874358007225008e-01,3.968751817730941517e-03,-1.860051970969880952e-02,-1.872202140057695890e-02,5.877852522933271762e-02,-1.100000000000000006e-01,-7.366311896062029962e-01,-5.877852522933271762e-02,1.100000000000000006e-01,-6.233688103937971015e-01,6.934710979494089489e-02,-1.298355693540041156e-01,-4.173292937139365111e-01,3.065289020505930842e-02,9.016443064599587165e-02,-3.226707062860634245e-01
+-3.793666227243953637e-01,2.922088815133250250e-01,-7.120691345982350928e-02,-2.782043068073618459e-03,3.145830796543572783e-01,-1.851921758808123541e-01,6.714023036862878380e-01,-2.142641032480997743e-01,-3.490610897375451271e-01,1.639386155508166729e-02,-1.703940665431914053e-02,-1.958198324587961947e-02,4.539904997404865805e-02,-1.100000000000000006e-01,-7.423704566931522697e-01,-4.539904997404865805e-02,1.100000000000000006e-01,-6.176295433068478280e-01,6.022419547723111000e-02,-1.299917285603423567e-01,-4.192687205455630228e-01,3.977580452276868045e-02,9.000827143965763055e-02,-3.207312794544370238e-01
+-4.622966703086521800e-01,2.418044428701279780e-01,-9.227356492612090455e-02,-8.810760645455316745e-03,3.717175438092160111e-01,-1.520718893939744798e-01,7.407176961216340727e-01,-1.930679167302827293e-01,-3.490656931085965309e-01,3.098756273244974990e-02,-1.457753668249829083e-02,-1.996643096950572252e-02,3.090169943759564844e-02,-1.100000000000000006e-01,-7.465739561406378177e-01,-3.090169943759564844e-02,1.100000000000000006e-01,-6.134260438593622800e-01,5.084952753471293913e-02,-1.296556250607818206e-01,-4.199949879638488759e-01,4.915047246528684438e-02,9.034437493921818052e-02,-3.200050120361511707e-01
+-5.348385334529097701e-01,1.915338529945107005e-01,-1.124415214075005082e-01,-1.318858593749533924e-02,4.184620240908591415e-01,-1.189504629205911240e-01,7.942577162621634601e-01,-1.744406738136935753e-01,-3.490659808192872471e-01,4.719277263843713044e-02,-1.166413896014145343e-02,-1.985221780113073306e-02,1.564344650412778995e-02,-1.100000000000000006e-01,-7.491381838416480976e-01,-1.564344650412778995e-02,1.100000000000000006e-01,-6.108618161583520001e-01,4.145394140486947931e-02,-1.288355348389452204e-01,-4.194902128546125764e-01,5.854605859513072746e-02,9.116446516105476683e-02,-3.205097871453874703e-01
+-5.953693400276927061e-01,1.421519329445354307e-01,-1.297194457234910336e-01,-1.591602986309102047e-02,4.543397535386966557e-01,-8.632316183607664783e-02,8.301158477193169016e-01,-1.582451059999862852e-01,-3.490659988012054238e-01,6.451373185715184033e-02,-8.703821904385893038e-03,-1.924197278445882384e-02,1.066303343379172641e-13,-1.100000000000000006e-01,-7.500000000000000000e-01,-1.066303343379172641e-13,1.100000000000000006e-01,-6.100000000000000977e-01,3.226878760038091182e-02,-1.275516512378176703e-01,-4.177668244562960931e-01,6.773121239961929496e-02,9.244834876218231690e-02,-3.222331755437039535e-01
+-6.433256773730070543e-01,9.447163462340432694e-02,-1.426945809657815534e-01,-1.705646484153735057e-02,4.797609735115727636e-01,-5.475217720672275606e-02,8.476869101482681357e-01,-1.444180509880774732e-01,-3.459210837710785524e-01,8.251230611380068469e-02,-5.985677071256696735e-03,-1.815963020596829056e-02,-1.564344650391715635e-02,-1.100000000000000006e-01,-7.491381838416714123e-01,1.564344650391715635e-02,1.100000000000000006e-01,-6.108618161583286854e-01,2.352023509169107185e-02,-1.258355877326242656e-01,-4.148672583108641843e-01,7.647976490830911411e-02,9.416441226737572168e-02,-3.251327416891358624e-01
+-6.773332858452263405e-01,4.934908311183852647e-02,-1.498575406396508436e-01,-1.673834903916008449e-02,4.945905135244247908e-01,-2.485129274933126076e-02,8.412338040721674126e-01,-1.329767390243583591e-01,-3.118859117684677495e-01,1.008067836222486108e-01,-3.185372749519920638e-03,-1.664499566595194560e-02,-3.090169943739282110e-02,-1.100000000000000006e-01,-7.465739561406840030e-01,3.090169943739282110e-02,1.100000000000000006e-01,-6.134260438593160947e-01,1.542370227634468072e-02,-1.237295995021510386e-01,-4.108629113599255311e-01,8.457629772365514442e-02,9.627040049784896247e-02,-3.291370886400743490e-01
+-6.991592328518351218e-01,7.673188385341499218e-03,-1.516888329904894639e-01,-1.515302578487052153e-02,5.007475828906592374e-01,2.725583434975038799e-03,8.177541401322061532e-01,-1.240306783858595302e-01,-2.714130818284272162e-01,1.190744289964902891e-01,-7.917428048885956707e-04,-1.474786567660648674e-02,-4.539904997385864338e-02,-1.100000000000000006e-01,-7.423704566932201043e-01,4.539904997385864338e-02,1.100000000000000006e-01,-6.176295433067799934e-01,8.178552663108115683e-03,-1.212855429660066181e-01,-4.058523839150781076e-01,9.182144733689173721e-02,9.871445703399338301e-02,-3.341476160849217725e-01
+-7.098632864868806847e-01,-2.963590179844104167e-02,-1.487310921673960507e-01,-1.254818146292723847e-02,4.994660274918861775e-01,2.728787781459463685e-02,7.809684223239581335e-01,-1.178014005988385071e-01,-2.278042664177887255e-01,1.370588412564104352e-01,1.026656369135458017e-03,-1.252216408642444802e-02,-5.877852522916018896e-02,-1.100000000000000006e-01,-7.366311896062907039e-01,5.877852522916018896e-02,1.100000000000000006e-01,-6.233688103937093938e-01,1.963185880731618815e-03,-1.185635989074692587e-01,-3.999590517910008858e-01,9.803681411926851164e-02,1.014364010925307424e-01,-3.400409482089992719e-01
+-7.103901144866152650e-01,-6.161585822182345795e-02,-1.416878746226963026e-01,-9.217067175108836080e-03,4.917885642704155624e-01,4.810022722817229590e-02,7.340487569101252774e-01,-1.146525911131320991e-01,-1.832300851385995077e-01,1.545832616035337226e-01,2.367965080439227848e-03,-1.002054977265884675e-02,-7.071067811857816021e-02,-1.100000000000000006e-01,-7.294974746831119905e-01,7.071067811857816021e-02,1.100000000000000006e-01,-6.305025253168881072e-01,-3.069355112982445621e-03,-1.156307906228748045e-01,-3.933280283834371116e-01,1.030693551129825414e-01,1.043692093771251966e-01,-3.466719716165630460e-01
+-7.018536152212252466e-01,-8.723604095418213689e-02,-1.314589164208601613e-01,-5.483080761111103381e-03,4.787833981386025450e-01,6.436012173367461342e-02,6.803817301689553121e-01,-1.151334353455569504e-01,-1.398613826583338660e-01,1.715712081077965245e-01,3.411449538228794858e-03,-7.290000459092285494e-03,-8.090169943743071024e-02,-1.100000000000000006e-01,-7.211449676605348191e-01,8.090169943743071024e-02,1.100000000000000006e-01,-6.388550323394652786e-01,-6.795152456723164980e-03,-1.125593335856225063e-01,-3.861225914957856498e-01,1.067951524567232469e-01,1.074406664143774948e-01,-3.538774085042145079e-01
+-6.854951399745531360e-01,-1.053548694612089359e-01,-1.190053900479984689e-01,-1.678016517621702718e-03,4.615221586758104788e-01,7.516005639093074897e-02,6.233272708746093738e-01,-1.200377521512668993e-01,-9.974724695745051939e-02,1.880758526935144559e-01,4.366040839588104620e-03,-4.369022085706743101e-03,-8.910065241878736830e-02,-1.100000000000000006e-01,-7.117793349818362092e-01,8.910065241878736830e-02,1.100000000000000006e-01,-6.482206650181638885e-01,-9.122464654675262186e-03,-1.094248572615508647e-01,-3.785201628976942456e-01,1.091224646546752330e-01,1.105751427384491364e-01,-3.614798371023055790e-01
+-6.625800878604344302e-01,-1.146620808150640297e-01,-1.052190971446136936e-01,1.890103040898984902e-03,4.410041489840277884e-01,7.943570573496497311e-02,5.658964679619137295e-01,-1.304791654638733645e-01,-6.461523056293563827e-02,2.043186048996041282e-01,5.419406970877448625e-03,-1.287435098160829260e-03,-9.510565162948153572e-02,-1.100000000000000006e-01,-7.016311896063192055e-01,9.510565162948153572e-02,1.100000000000000006e-01,-6.583688103936808922e-01,-9.993985556618588395e-03,-1.063045428604892789e-01,-3.707079396122624493e-01,1.099939855566186009e-01,1.136954571395107222e-01,-3.692920603877373198e-01
+-6.342675291555379680e-01,-1.136141537209443275e-01,-9.083235139056936025e-02,4.987495030817091710e-03,4.180607698342920231e-01,7.590858215735218906e-02,5.104581687396505529e-01,-1.479745070379862859e-01,-3.567820158610217340e-02,2.207334564716433023e-01,6.698175941152950501e-03,1.929766589080433598e-03,-9.876883405949665740e-02,-1.100000000000000006e-01,-6.909504125528918017e-01,9.876883405949665740e-02,1.100000000000000006e-01,-6.690495874471082960e-01,-9.388255425535355081e-03,-1.032752228787214149e-01,-3.628782845040595673e-01,1.093882554255353329e-01,1.167247771212785862e-01,-3.771217154959405904e-01
+-6.015091030977537390e-01,-1.003892154379043000e-01,-7.639017382006864365e-02,7.536003586161695890e-03,3.932898026094010513e-01,6.304935679367691670e-02,4.585879697264083621e-01,-1.745055716378262067e-01,-1.353823766735710171e-02,2.380022910155669691e-01,8.248665217423534549e-03,5.252174634699572492e-03,-1.000000000000000056e-01,-1.100000000000000006e-01,-6.800000000000770983e-01,1.000000000000000056e-01,1.100000000000000006e-01,-6.799999999999229994e-01,-7.320189347555912385e-03,-1.004114892279352467e-01,-3.552239896669857067e-01,1.073201893475558555e-01,1.195885107720647544e-01,-3.847760103330144510e-01
+-5.650199172977323769e-01,-7.293045398983169503e-02,-6.227748628628835409e-02,9.739606996801009400e-03,3.670525667965948702e-01,3.912876259724346745e-02,4.111058022739051965e-01,-2.124776593388213453e-01,1.772078937222254947e-03,2.570391413963952765e-01,1.003981562871762885e-02,8.624325639673229710e-03,-9.876883405953107431e-02,-1.100000000000000006e-01,-6.690495874472603965e-01,9.876883405953107431e-02,1.100000000000000006e-01,-6.909504125527397012e-01,-3.840709973037932656e-03,-9.778385653480009543e-02,-3.479335292430774107e-01,1.038407099730378480e-01,1.222161434651999057e-01,-3.920664707569227470e-01
+-5.253190287863364061e-01,-2.922878092816679624e-02,-4.877165008311633299e-02,1.225311428516112112e-02,3.395273341133266953e-01,2.497974193642903823e-03,3.682489008911213335e-01,-2.643954788333813810e-01,1.064761765339624147e-02,2.788295816934107663e-01,1.198181587143125858e-02,1.193481551185144110e-02,-9.510565162954952301e-02,-1.100000000000000006e-01,-6.583688103938273306e-01,9.510565162954952301e-02,1.100000000000000006e-01,-7.016311896061727671e-01,9.645063680882096091e-04,-9.545702583683376985e-02,-3.411864185636219182e-01,9.903549363191191390e-02,1.245429741631662313e-01,-3.988135814363779064e-01
+-4.828051591287856881e-01,3.191699582407947489e-02,-3.609134982031275002e-02,1.631742097923993828e-02,3.107876914956043679e-01,-4.768801171398796834e-02,3.298837045301811211e-01,-3.319682847506739698e-01,1.374068819078078270e-02,3.039753575645646189e-01,1.395079121638285666e-02,1.498012027511443772e-02,-8.910065241888726062e-02,-1.100000000000000006e-01,-6.482206650183011121e-01,8.910065241888726062e-02,1.100000000000000006e-01,-7.117793349816989856e-01,6.977139301904848601e-03,-9.348829142812876969e-02,-3.351487938859246674e-01,9.302286069809531655e-02,1.265117085718712175e-01,-4.048512061140752127e-01
+-4.378336598939228108e-01,1.095522403404295408e-01,-2.442778464488535445e-02,2.363195766961536173e-02,2.808774127909683949e-01,-1.102372783050172417e-01,2.956860640218564318e-01,-4.144794111090490119e-01,1.181813277410186103e-02,3.318676187594066240e-01,1.581207081669274220e-02,1.744878856001978382e-02,-8.090169943756003734e-02,-1.100000000000000006e-01,-6.388550323395898456e-01,8.090169943756003734e-02,1.100000000000000006e-01,-7.211449676604102521e-01,1.404913785079731775e-02,-9.192613008368211158e-02,-3.299693215672773183e-01,8.595086214920252821e-02,1.280738699163178895e-01,-4.100306784327227283e-01
+-3.907770986534433999e-01,1.980260120079110897e-01,-1.395745259044261360e-02,3.546144753767913743e-02,2.498681818962428525e-01,-1.798060562162367426e-01,2.652653009989214272e-01,-5.040411986076362982e-01,5.665123502669997847e-03,3.478089728115584811e-01,1.743836329117085665e-02,1.886183327922786104e-02,-7.071067811873374409e-02,-1.100000000000000006e-01,-6.305025253169970201e-01,7.071067811873374409e-02,1.100000000000000006e-01,-7.294974746830030776e-01,2.200636593987369619e-02,-9.080900740031049023e-02,-3.257755374058487474e-01,7.799363406012613242e-02,1.291909925996894970e-01,-4.142244625941513547e-01
+-3.420655581770582487e-01,2.895443045998259968e-01,-4.841596824676895443e-03,5.160187264010956953e-02,2.178979182518972213e-01,-2.492728734048821893e-01,2.382376078107399653e-01,-5.905773675881912377e-01,-3.968751817726426032e-03,3.489874358007223898e-01,1.872202140057655992e-02,1.860051970969917728e-02,-5.877852522933818546e-02,-1.100000000000000006e-01,-6.233688103937999880e-01,5.877852522933818546e-02,1.100000000000000006e-01,-7.366311896062001097e-01,3.065289020505527345e-02,-9.016443064599603818e-02,-3.226707062860645348e-01,6.934710979494454475e-02,1.298355693540039490e-01,-4.173292937139354564e-01
+-2.922088815133476181e-01,3.793666227243589484e-01,2.782043068070498126e-03,7.120691345981469689e-02,1.851921758808272034e-01,-3.145830796543311325e-01,2.142641032481107100e-01,-6.714023036862559746e-01,-1.639386155507634169e-02,3.490610897375451271e-01,1.958198324587921355e-02,1.703940665431992463e-02,-4.539904997405468795e-02,-1.100000000000000006e-01,-6.176295433068499374e-01,4.539904997405468795e-02,1.100000000000000006e-01,-7.423704566931501603e-01,3.977580452276489875e-02,-9.000827143965760280e-02,-3.207312794544375789e-01,6.022419547723532190e-02,1.299917285603423844e-01,-4.192687205455624122e-01
+-2.418044428701504323e-01,4.622966703086196505e-01,8.810760645452966194e-03,9.227356492611225869e-02,1.520718893939894123e-01,-3.717175438091944728e-01,1.930679167302921106e-01,-7.407176961216090927e-01,-3.098756273244327938e-02,3.490656931085965309e-01,1.996643096950565660e-02,1.457753668249944790e-02,-3.090169943760207732e-02,-1.100000000000000006e-01,-6.134260438593637232e-01,3.090169943760207732e-02,1.100000000000000006e-01,-7.465739561406363745e-01,4.915047246528300717e-02,-9.034437493921793072e-02,-3.200050120361511707e-01,5.084952753471722042e-02,1.296556250607820704e-01,-4.199949879638488204e-01
+-1.915338529945319890e-01,5.348385334528811264e-01,1.318858593749377105e-02,1.124415214074924591e-01,1.189504629206050990e-01,-4.184620240908414890e-01,1.744406738137005974e-01,-7.942577162621449194e-01,-4.719277263842774212e-02,3.490659808192872471e-01,1.985221780113053877e-02,1.166413896014261049e-02,-1.564344650413447210e-02,-1.100000000000000006e-01,-6.108618161583527773e-01,1.564344650413447210e-02,1.100000000000000006e-01,-7.491381838416473204e-01,5.854605859512650862e-02,-9.116446516105432274e-02,-3.205097871453869707e-01,4.145394140487329571e-02,1.288355348389456645e-01,-4.194902128546130204e-01
+-1.421519329445554980e-01,5.953693400276683922e-01,1.591602986309023290e-02,1.297194457234841780e-01,8.632316183609003990e-02,-4.543397535386828334e-01,1.582451059999918086e-01,-8.301158477193042451e-01,-6.451373185714559533e-02,3.490659988012054238e-01,1.924197278445968426e-02,8.703821904387093467e-03,-1.133927367956296944e-13,-1.100000000000000006e-01,-6.100000000000000977e-01,1.133927367956296944e-13,1.100000000000000006e-01,-7.500000000000000000e-01,6.773121239961521489e-02,-9.244834876218167852e-02,-3.222331755437028988e-01,3.226878760038459637e-02,1.275516512378183087e-01,-4.177668244562970368e-01
+-9.447163462342361706e-02,6.433256773729894018e-01,1.705646484153721179e-02,1.426945809657770570e-01,5.475217720673561383e-02,-4.797609735115641039e-01,1.444180509880821361e-01,-8.476869101482654711e-01,-8.251230611379259394e-02,3.459210837710901543e-01,1.815963020596886995e-02,5.985677071257817367e-03,1.564344650391047420e-02,-1.100000000000000006e-01,-6.108618161583279083e-01,-1.564344650391047420e-02,1.100000000000000006e-01,-7.491381838416721894e-01,7.647976490830529772e-02,-9.416441226737488901e-02,-3.251327416891343081e-01,2.352023509169452742e-02,1.258355877326250982e-01,-4.148672583108656275e-01
+-4.934908311185802476e-02,6.773332858452150163e-01,1.673834903916046613e-02,1.498575406396491783e-01,2.485129274934418098e-02,-4.945905135244207940e-01,1.329767390243635772e-01,-8.412338040721749621e-01,-1.008067836222409502e-01,3.118859117684842364e-01,1.664499566595264643e-02,3.185372749521041269e-03,3.090169943738639569e-02,-1.100000000000000006e-01,-6.134260438593146514e-01,-3.090169943738639569e-02,1.100000000000000006e-01,-7.465739561406854463e-01,8.457629772365200804e-02,-9.627040049784797715e-02,-3.291370886400725171e-01,1.542370227634817792e-02,1.237295995021520240e-01,-4.108629113599275851e-01
+-7.673188385359222888e-03,6.991592328518287935e-01,1.515302578487147563e-02,1.516888329904899357e-01,-2.725583434963343293e-03,-5.007475828906585713e-01,1.240306783858635270e-01,-8.177541401322201420e-01,-1.190744289964826147e-01,2.714130818284457014e-01,1.474786567660745298e-02,7.917428048895215793e-04,4.539904997385262042e-02,-1.100000000000000006e-01,-6.176295433067778839e-01,-4.539904997385262042e-02,1.100000000000000006e-01,-7.423704566932222138e-01,9.182144733688897553e-02,-9.871445703399227278e-02,-3.341476160849194965e-01,8.178552663111189613e-03,1.212855429660077283e-01,-4.058523839150806056e-01
+2.963590179842664693e-02,7.098632864868782422e-01,1.254818146292851697e-02,1.487310921673982711e-01,-2.728787781458519301e-02,-4.994660274918882314e-01,1.178014005988397284e-01,-7.809684223239763412e-01,-1.370588412564017478e-01,2.278042664178073218e-01,1.252216408642553222e-02,-1.026656369134825277e-03,5.877852522915471417e-02,-1.100000000000000006e-01,-6.233688103937066183e-01,-5.877852522915471417e-02,1.100000000000000006e-01,-7.366311896062934794e-01,9.803681411926595812e-02,-1.014364010925295212e-01,-3.400409482089963853e-01,1.963185880733922528e-03,1.185635989074704799e-01,-3.999590517910034393e-01
+6.161585822181156469e-02,7.103901144866168194e-01,9.217067175110404270e-03,1.416878746226999386e-01,-4.810022722816531537e-02,-4.917885642704199478e-01,1.146525911131321268e-01,-7.340487569101465937e-01,-1.545832616035265616e-01,1.832300851386181872e-01,1.002054977265854317e-02,-2.367965080438675339e-03,7.071067811857338625e-02,-1.100000000000000006e-01,-6.305025253168847765e-01,-7.071067811857338625e-02,1.100000000000000006e-01,-7.294974746831153212e-01,1.030693551129805569e-01,-1.043692093771239060e-01,-3.466719716165599374e-01,-3.069355112980655387e-03,1.156307906228760951e-01,-3.933280283834399427e-01
+8.723604095417303306e-02,7.018536152212309087e-01,5.483080761112733154e-03,1.314589164208651295e-01,-6.436012173366900679e-02,-4.787833981386087068e-01,1.151334353455554099e-01,-6.803817301689792929e-01,-1.715712081077890583e-01,1.398613826583502695e-01,7.290000459093505004e-03,-3.411449538228250589e-03,8.090169943742674119e-02,-1.100000000000000006e-01,-6.388550323394613928e-01,-8.090169943742674119e-02,1.100000000000000006e-01,-7.211449676605387049e-01,1.067951524567218591e-01,-1.074406664143761486e-01,-3.538774085042111217e-01,-6.795152456721922918e-03,1.125593335856238525e-01,-3.861225914957887029e-01
+1.053548694612026632e-01,6.854951399745614626e-01,1.678016517623354608e-03,1.190053900480041171e-01,-7.516005639092721013e-02,-4.615221586758185279e-01,1.200377521512640960e-01,-6.233272708746341317e-01,-1.880758526935077113e-01,9.974724695746667313e-02,4.369022085708079706e-03,-4.366040839587678746e-03,8.910065241878430131e-02,-1.100000000000000006e-01,-6.482206650181596697e-01,-8.910065241878430131e-02,1.100000000000000006e-01,-7.117793349818404280e-01,1.091224646546745669e-01,-1.105751427384477903e-01,-3.614798371023024148e-01,-9.122464654674533602e-03,1.094248572615522108e-01,-3.785201628976977428e-01
+1.146620808150619619e-01,6.625800878604451993e-01,-1.890103040897567199e-03,1.052190971446196888e-01,-7.943570573496461229e-02,-4.410041489840370588e-01,1.304791654638676746e-01,-5.658964679619378213e-01,-2.043186048995972171e-01,6.461523056294965484e-02,1.287435098162195571e-03,-5.419406970877057445e-03,9.510565162947944018e-02,-1.100000000000000006e-01,-6.583688103936763403e-01,-9.510565162947944018e-02,1.100000000000000006e-01,-7.016311896063237574e-01,1.099939855566185454e-01,-1.136954571395093899e-01,-3.692920603877341557e-01,-9.993985556618532884e-03,1.063045428604906112e-01,-3.707079396122660575e-01
+1.136141537209471031e-01,6.342675291555514017e-01,-4.987495030815912965e-03,9.083235139057566077e-02,-7.590858215735545034e-02,-4.180607698343025147e-01,1.479745070379771543e-01,-5.104581687396737566e-01,-2.207334564716363079e-01,3.567820158611305359e-02,-1.929766589079093524e-03,-6.698175941152365032e-03,9.876883405949560268e-02,-1.100000000000000006e-01,-6.690495874471036331e-01,-9.876883405949560268e-02,1.100000000000000006e-01,-6.909504125528964646e-01,1.093882554255359296e-01,-1.167247771212773094e-01,-3.771217154959370932e-01,-9.388255425535903254e-03,1.032752228787226917e-01,-3.628782845040627314e-01
+1.003892154379126406e-01,6.015091030977691711e-01,-7.536003586160686281e-03,7.639017382007499968e-02,-6.304935679368450785e-02,-3.932898026094123756e-01,1.745055716378126898e-01,-4.585879697264306221e-01,-2.380022910155591975e-01,1.353823766736547696e-02,-5.252174634698122263e-03,-8.248665217422799026e-03,1.000000000000000056e-01,-1.100000000000000006e-01,-6.799999999999183364e-01,-1.000000000000000056e-01,1.100000000000000006e-01,-6.800000000000817613e-01,1.073201893475571184e-01,-1.195885107720635609e-01,-3.847760103330110648e-01,-7.320189347557050363e-03,1.004114892279364402e-01,-3.552239896669887598e-01
+7.293045398984326910e-02,5.650199172977442563e-01,-9.739606996800379696e-03,6.227748628629257294e-02,-3.912876259725330680e-02,-3.670525667966031969e-01,2.124776593388065793e-01,-4.111058022739192963e-01,-2.570391413963884486e-01,-1.772078937218461974e-03,-8.624325639672159385e-03,-1.003981562871708415e-02,9.876883405953180983e-02,-1.100000000000000006e-01,-6.909504125527364815e-01,-9.876883405953180983e-02,1.100000000000000006e-01,-6.690495874472636162e-01,1.038407099730391803e-01,-1.222161434651991702e-01,-3.920664707569205265e-01,-3.840709973039257985e-03,9.778385653480083095e-02,-3.479335292430796311e-01
+2.922878092817411677e-02,5.253190287863404029e-01,-1.225311428516074469e-02,4.877165008311758199e-02,-2.497974193648704738e-03,-3.395273341133294154e-01,2.643954788333722217e-01,-3.682489008911249417e-01,-2.788295816934067695e-01,-1.064761765339595177e-02,-1.193481551185098834e-02,-1.198181587143111113e-02,9.510565162955007812e-02,-1.100000000000000006e-01,-7.016311896061715458e-01,-9.510565162955007812e-02,1.100000000000000006e-01,-6.583688103938285519e-01,9.903549363191241350e-02,-1.245429741631659815e-01,-3.988135814363772957e-01,9.645063680877100087e-04,9.545702583683401965e-02,-3.411864185636225288e-01
+-3.191699582408202840e-02,4.828051591287816913e-01,-1.631742097924015339e-02,3.609134982031163286e-02,4.768801171398990429e-02,-3.107876914956016479e-01,3.319682847506757462e-01,-3.298837045301772908e-01,-3.039753575645650630e-01,-1.374068819078135342e-02,-1.498012027511447936e-02,-1.395079121638304921e-02,8.910065241888677490e-02,-1.100000000000000006e-01,-7.117793349816996518e-01,-8.910065241888677490e-02,1.100000000000000006e-01,-6.482206650183004459e-01,9.302286069809470592e-02,-1.265117085718713563e-01,-4.048512061140757123e-01,6.977139301905438407e-03,9.348829142812864479e-02,-3.351487938859241122e-01
+-1.095522403404453199e-01,4.378336598939144286e-01,-2.363195766961711727e-02,2.442778464488336299e-02,1.102372783050296484e-01,-2.808774127909627882e-01,4.144794111090646105e-01,-2.956860640218512137e-01,-3.318676187594112870e-01,-1.181813277410038304e-02,-1.744878856002012035e-02,-1.581207081669293649e-02,8.090169943755816384e-02,-1.100000000000000006e-01,-7.211449676604120285e-01,-8.090169943755816384e-02,1.100000000000000006e-01,-6.388550323395880692e-01,8.595086214920115431e-02,-1.280738699163181671e-01,-4.100306784327235610e-01,1.404913785079901778e-02,9.192613008368183403e-02,-3.299693215672763191e-01
+-1.980260120079450348e-01,3.907770986534234159e-01,-3.546144753768451507e-02,1.395745259043847109e-02,1.798060562162631937e-01,-2.498681818962296963e-01,5.040411986076674955e-01,-2.652653009989097699e-01,-3.478089728115591472e-01,-5.665123502666237834e-03,-1.886183327922797553e-02,-1.743836329117159217e-02,7.071067811872898401e-02,-1.100000000000000006e-01,-7.294974746830064083e-01,-7.071067811872898401e-02,1.100000000000000006e-01,-6.305025253169936894e-01,7.799363406012273237e-02,-1.291909925996899411e-01,-4.142244625941527980e-01,2.200636593987707543e-02,9.080900740031006002e-02,-3.257755374058472486e-01
+-2.895443045998777887e-01,3.420655581770263853e-01,-5.160187264011961011e-02,4.841596824671430196e-03,2.492728734049202421e-01,-2.178979182518763769e-01,5.905773675882372009e-01,-2.382376078107221185e-01,-3.489874358007223898e-01,3.968751817732747364e-03,-1.860051970969856666e-02,-1.872202140057738912e-02,5.877852522933044166e-02,-1.100000000000000006e-01,-7.366311896062041065e-01,-5.877852522933044166e-02,1.100000000000000006e-01,-6.233688103937959912e-01,6.934710979493888261e-02,-1.298355693540042266e-01,-4.173292937139370662e-01,3.065289020506050538e-02,9.016443064599577450e-02,-3.226707062860630915e-01
+-3.793666227244205658e-01,2.922088815133066508e-01,-7.120691345982928244e-02,-2.782043068076093910e-03,3.145830796543745977e-01,-1.851921758808002805e-01,6.714023036863080440e-01,-2.142641032480895047e-01,-3.490610897375451271e-01,1.639386155508516102e-02,-1.703940665431851256e-02,-1.958198324587982070e-02,4.539904997404425185e-02,-1.100000000000000006e-01,-7.423704566931538240e-01,-4.539904997404425185e-02,1.100000000000000006e-01,-6.176295433068462737e-01,6.022419547722776545e-02,-1.299917285603423289e-01,-4.192687205455635224e-01,3.977580452277160172e-02,9.000827143965767219e-02,-3.207312794544365797e-01
+-4.622966703086933693e-01,2.418044428700995840e-01,-9.227356492613172922e-02,-8.810760645458244958e-03,3.717175438092434892e-01,-1.520718893939558836e-01,7.407176961216654920e-01,-1.930679167302709054e-01,-3.490656931085965309e-01,3.098756273245930823e-02,-1.457753668249691173e-02,-1.996643096950585436e-02,3.090169943758756116e-02,-1.100000000000000006e-01,-7.465739561406397051e-01,-3.090169943758756116e-02,1.100000000000000006e-01,-6.134260438593603926e-01,5.084952753470783904e-02,-1.296556250607814875e-01,-4.199949879638489314e-01,4.915047246529236774e-02,9.034437493921849971e-02,-3.200050120361510597e-01
+-5.348385334529546231e-01,1.915338529944767276e-01,-1.124415214075132896e-01,-1.318858593749779387e-02,4.184620240908867306e-01,-1.189504629205685449e-01,7.942577162621935472e-01,-1.744406738136816959e-01,-3.490659808192872471e-01,4.719277263844851023e-02,-1.166413896013946024e-02,-1.985221780113028203e-02,1.564344650411728793e-02,-1.100000000000000006e-01,-7.491381838416492078e-01,-1.564344650411728793e-02,1.100000000000000006e-01,-6.108618161583508899e-01,4.145394140486316492e-02,-1.288355348389444988e-01,-4.194902128546117992e-01,5.854605859513704880e-02,9.116446516105548847e-02,-3.205097871453882474e-01
+-5.953693400277386694e-01,1.421519329444937974e-01,-1.297194457235038845e-01,-1.591602986309259213e-02,4.543397535387221353e-01,-8.632316183604914206e-02,8.301158477193392171e-01,-1.582451059999732679e-01,-3.490659988012054238e-01,6.451373185716663405e-02,-8.703821904383434935e-03,-1.924197278445794607e-02,9.315451529445831267e-14,-1.100000000000000006e-01,-7.500000000000000000e-01,-9.315451529445831267e-14,1.100000000000000006e-01,-6.100000000000000977e-01,3.226878760037318883e-02,-1.275516512378163658e-01,-4.177668244562940947e-01,6.773121239962701101e-02,9.244834876218362141e-02,-3.222331755437059519e-01
+-6.433256773730487987e-01,9.447163462335605999e-02,-1.426945809657917397e-01,-1.705646484153770792e-02,4.797609735115928031e-01,-5.475217720669153104e-02,8.476869101482724655e-01,-1.444180509880644558e-01,-3.459210837710496866e-01,8.251230611382030788e-02,-5.985677071254229958e-03,-1.815963020596752381e-02,-1.564344650393327193e-02,-1.100000000000000006e-01,-7.491381838416696359e-01,1.564344650393327193e-02,1.100000000000000006e-01,-6.108618161583304618e-01,2.352023509168228721e-02,-1.258355877326222672e-01,-4.148672583108605760e-01,7.647976490831789875e-02,9.416441226737772008e-02,-3.251327416891394706e-01
+-6.773332858452619787e-01,4.934908311178306389e-02,-1.498575406396566445e-01,-1.673834903915880426e-02,4.945905135244381134e-01,-2.485129274929449503e-02,8.412338040721484278e-01,-1.329767390243452307e-01,-3.118859117684220639e-01,1.008067836222732577e-01,-3.185372749516659358e-03,-1.664499566594959332e-02,-3.090169943741172265e-02,-1.100000000000000006e-01,-7.465739561406796732e-01,3.090169943741172265e-02,1.100000000000000006e-01,-6.134260438593204245e-01,1.542370227633493157e-02,-1.237295995021481521e-01,-4.108629113599198135e-01,8.457629772366523357e-02,9.627040049785184905e-02,-3.291370886400802886e-01
+-6.991592328518593247e-01,7.673188385284076402e-03,-1.516888329904889365e-01,-1.515302578486748056e-02,5.007475828906630122e-01,2.725583435013004957e-03,8.177541401321637426e-01,-1.240306783858486916e-01,-2.714130818283685409e-01,1.190744289965182806e-01,-7.917428048857395569e-04,-1.474786567660345965e-02,-4.539904997387888413e-02,-1.100000000000000006e-01,-7.423704566932128879e-01,4.539904997387888413e-02,1.100000000000000006e-01,-6.176295433067872098e-01,8.178552663098345721e-03,-1.212855429660028572e-01,-4.058523839150701695e-01,9.182144733690181249e-02,9.871445703399714389e-02,-3.341476160849299326e-01
+-7.098632864868894554e-01,-2.963590179849603934e-02,-1.487310921673880570e-01,-1.254818146292243503e-02,4.994660274918789056e-01,2.728787781463046930e-02,7.809684223238916312e-01,-1.178014005988311519e-01,-2.278042664177198362e-01,1.370588412564391900e-01,1.026656369137806182e-03,-1.252216408641954742e-02,-5.877852522918028400e-02,-1.100000000000000006e-01,-7.366311896062804898e-01,5.877852522918028400e-02,1.100000000000000006e-01,-6.233688103937196079e-01,1.963185880722688459e-03,-1.185635989074647623e-01,-3.999590517909909493e-01,9.803681411927744893e-02,1.014364010925352388e-01,-3.400409482090092084e-01
+-7.103901144866081596e-01,-6.161585822187450046e-02,-1.416878746226809538e-01,-9.217067175102578933e-03,4.917885642703972437e-01,4.810022722820521401e-02,7.340487569100364595e-01,-1.146525911131298786e-01,-1.832300851385230411e-01,1.545832616035653917e-01,2.367965080441117830e-03,-1.002054977265419249e-02,-7.071067811859774177e-02,-1.100000000000000006e-01,-7.294974746830983348e-01,7.071067811859774177e-02,1.100000000000000006e-01,-6.305025253169017629e-01,-3.069355112990196366e-03,-1.156307906228694893e-01,-3.933280283834248436e-01,1.030693551129902991e-01,1.043692093771305118e-01,-3.466719716165753140e-01
+-7.018536152212010437e-01,-8.723604095422500537e-02,-1.314589164208380956e-01,-5.483080761103690907e-03,4.787833981385730686e-01,6.436012173370120326e-02,6.803817301688471764e-01,-1.151334353455619047e-01,-1.398613826582523756e-01,1.715712081078289708e-01,3.411449538230657084e-03,-7.290000459086820248e-03,-8.090169943744865422e-02,-1.100000000000000006e-01,-7.211449676605176107e-01,8.090169943744865422e-02,1.100000000000000006e-01,-6.388550323394824870e-01,-6.795152456729069979e-03,-1.125593335856164556e-01,-3.861225914957712169e-01,1.067951524567291449e-01,1.074406664143835455e-01,-3.538774085042289408e-01
+-6.854951399745118357e-01,-1.053548694612379544e-01,-1.190053900479705606e-01,-1.678016517613863719e-03,4.615221586757700667e-01,7.516005639094683333e-02,6.233272708744892476e-01,-1.200377521512823731e-01,-9.974724695737002822e-02,1.880758526935484565e-01,4.366040839589812456e-03,-4.369022085700401820e-03,-8.910065241880220366e-02,-1.100000000000000006e-01,-7.117793349818158921e-01,8.910065241880220366e-02,1.100000000000000006e-01,-6.482206650181842056e-01,-9.122464654678599794e-03,-1.094248572615443282e-01,-3.785201628976781474e-01,1.091224646546786470e-01,1.105751427384556729e-01,-3.614798371023220103e-01
+-6.625800878603734789e-01,-1.146620808150743548e-01,-1.052190971445801926e-01,1.890103040906908468e-03,4.410041489839761630e-01,7.943570573496640252e-02,5.658964679617801696e-01,-1.304791654639056442e-01,-6.461523056286039290e-02,2.043186048996425419e-01,5.419406970880094078e-03,-1.287435098153444975e-03,-9.510565162949294327e-02,-1.100000000000000006e-01,-7.016311896062946696e-01,9.510565162949294327e-02,1.100000000000000006e-01,-6.583688103937054281e-01,-9.993985556618914523e-03,-1.063045428604820208e-01,-3.707079396122440196e-01,1.099939855566189201e-01,1.136954571395179803e-01,-3.692920603877561381e-01
+-6.342675291554618067e-01,-1.136141537209274938e-01,-9.083235139053333351e-02,4.987495030824077441e-03,4.180607698342325151e-01,7.590858215733244097e-02,5.104581687395165490e-01,-1.479745070380398542e-01,-3.567820158603855069e-02,2.207334564716838532e-01,6.698175941156455510e-03,1.929766589088480330e-03,-9.876883405950277750e-02,-1.100000000000000006e-01,-6.909504125528648233e-01,9.876883405950277750e-02,1.100000000000000006e-01,-6.690495874471352744e-01,-9.388255425532017473e-03,-1.032752228787140597e-01,-3.628782845040402494e-01,1.093882554255319883e-01,1.167247771212859414e-01,-3.771217154959599083e-01
+-6.015091030976611464e-01,-1.003892154378515922e-01,-7.639017382003036871e-02,7.536003586167914006e-03,3.932898026093328281e-01,6.304935679362891343e-02,4.585879697262756904e-01,-1.745055716379102229e-01,-1.353823766730724576e-02,2.380022910156136540e-01,8.248665217428020544e-03,5.252174634708459480e-03,-1.000000000000000056e-01,-1.100000000000000006e-01,-6.800000000000476774e-01,1.000000000000000056e-01,1.100000000000000006e-01,-6.799999999999524203e-01,-7.320189347548480829e-03,-1.004114892279278914e-01,-3.552239896669656671e-01,1.073201893475484309e-01,1.195885107720721097e-01,-3.847760103330344905e-01
+-5.650199172976237971e-01,-7.293045398973249660e-02,-6.227748628624882321e-02,9.739606996807332467e-03,3.670525667965183203e-01,3.912876259715906968e-02,4.111058022737766326e-01,-2.124776593389464396e-01,1.772078937256396907e-03,2.570391413964529526e-01,1.003981562872310711e-02,8.624325639682912936e-03,-9.876883405952407990e-02,-1.100000000000000006e-01,-6.690495874472294213e-01,9.876883405952407990e-02,1.100000000000000006e-01,-6.909504125527706764e-01,-3.840709973026087964e-03,-9.778385653479301776e-02,-3.479335292430573157e-01,1.038407099730259964e-01,1.222161434652069834e-01,-3.920664707569427865e-01
+-5.253190287862126162e-01,-2.922878092801155930e-02,-4.877165008307686456e-02,1.225311428517017291e-02,3.395273341132422074e-01,2.497974193513909785e-03,3.682489008909990980e-01,-2.643954788335577399e-01,1.064761765341413688e-02,2.788295816934797111e-01,1.198181587143724337e-02,1.193481551186105494e-02,-9.510565162953504847e-02,-1.100000000000000006e-01,-6.583688103937961333e-01,9.510565162953504847e-02,1.100000000000000006e-01,-7.016311896062039644e-01,9.645063681044188653e-04,-9.545702583682734443e-02,-3.411864185636027669e-01,9.903549363189546872e-02,1.245429741631726567e-01,-3.988135814363973353e-01
+-4.828051591286455779e-01,3.191699582429879251e-02,-3.609134982027376037e-02,1.631742097925690041e-02,3.107876914955107206e-01,-4.768801171416617996e-02,3.298837045300646031e-01,-3.319682847509104473e-01,1.374068819078298233e-02,3.039753575646481631e-01,1.395079121638907738e-02,1.498012027512325706e-02,-8.910065241886469534e-02,-1.100000000000000006e-01,-6.482206650182701368e-01,8.910065241886469534e-02,1.100000000000000006e-01,-7.117793349817299609e-01,6.977139301925644466e-03,-9.348829142812314918e-02,-3.351487938859067928e-01,9.302286069807422231e-02,1.265117085718768519e-01,-4.048512061140933094e-01
+-4.378336598937667690e-01,1.095522403407127726e-01,-2.442778464484778381e-02,2.363195766964714881e-02,2.808774127908651996e-01,-1.102372783052429361e-01,2.956860640217473524e-01,-4.144794111093440536e-01,1.181813277408727200e-02,3.318676187595015481e-01,1.581207081669871312e-02,1.744878856002665679e-02,-8.090169943752872905e-02,-1.100000000000000006e-01,-6.388550323395596475e-01,8.090169943752872905e-02,1.100000000000000006e-01,-7.211449676604404502e-01,1.404913785082290839e-02,-9.192613008367754579e-02,-3.299693215672613866e-01,8.595086214917693757e-02,1.280738699163224414e-01,-4.100306784327387155e-01
+-3.907770986532713708e-01,1.980260120082303898e-01,-1.395745259040735015e-02,3.546144753772854236e-02,2.498681818961296652e-01,-1.798060562164835452e-01,2.652653009988180099e-01,-5.040411986079441631e-01,5.665123502641344552e-03,3.478089728115704160e-01,1.743836329117625511e-02,1.886183327922965475e-02,-7.071067811869406750e-02,-1.100000000000000006e-01,-6.305025253169692645e-01,7.071067811869406750e-02,1.100000000000000006e-01,-7.294974746830308332e-01,2.200636593990347098e-02,-9.080900740030732610e-02,-3.257755374058356468e-01,7.799363406009635069e-02,1.291909925996926611e-01,-4.142244625941644554e-01
+-3.420655581768720088e-01,2.895443046001653919e-01,-4.841596824645259291e-03,5.160187264017648823e-02,2.178979182517750135e-01,-2.492728734051345152e-01,2.382376078106431538e-01,-5.905773675885023222e-01,-3.968751817768232867e-03,3.489874358007231114e-01,1.872202140058061570e-02,1.860051970969560375e-02,-5.877852522929049445e-02,-1.100000000000000006e-01,-6.233688103937756742e-01,5.877852522929049445e-02,1.100000000000000006e-01,-7.366311896062244235e-01,3.065289020508875362e-02,-9.016443064599452550e-02,-3.226707062860550423e-01,6.934710979491105765e-02,1.298355693540054756e-01,-4.173292937139450043e-01
+-2.922088815131498873e-01,3.793666227246939582e-01,2.782043068097468305e-03,7.120691345989417498e-02,1.851921758806973628e-01,-3.145830796545683317e-01,2.142641032480202545e-01,-6.714023036865457428e-01,-1.639386155512956994e-02,3.490610897375451827e-01,1.958198324588185033e-02,1.703940665431197959e-02,-4.539904997400025927e-02,-1.100000000000000006e-01,-6.176295433068305085e-01,4.539904997400025927e-02,1.100000000000000006e-01,-7.423704566931695892e-01,3.977580452280100876e-02,-9.000827143965794974e-02,-3.207312794544323609e-01,6.022419547719878863e-02,1.299917285603420514e-01,-4.192687205455676858e-01
+-2.418044428699437365e-01,4.622966703089359530e-01,8.810760645474322375e-03,9.227356492619709361e-02,1.520718893938533545e-01,-3.717175438094053042e-01,1.930679167302096211e-01,-7.407176961218583378e-01,-3.098756273250560106e-02,3.490656931085965309e-01,1.996643096950623253e-02,1.457753668248811842e-02,-3.090169943754128221e-02,-1.100000000000000006e-01,-6.134260438593498455e-01,3.090169943754128221e-02,1.100000000000000006e-01,-7.465739561406502522e-01,4.915047246532135844e-02,-9.034437493922028994e-02,-3.200050120361507267e-01,5.084952753467844588e-02,1.296556250607797112e-01,-4.199949879638492645e-01
+-1.915338529943218515e-01,5.348385334531610136e-01,1.318858593750873824e-02,1.124415214075721037e-01,1.189504629204661684e-01,-4.184620240910146283e-01,1.744406738136272950e-01,-7.942577162623325471e-01,-4.719277263849751963e-02,3.490659808192872471e-01,1.985221780112880058e-02,1.166413896013011008e-02,-1.564344650406922568e-02,-1.100000000000000006e-01,-6.108618161583455608e-01,1.564344650406922568e-02,1.100000000000000006e-01,-7.491381838416545369e-01,5.854605859516573418e-02,-9.116446516105876363e-02,-3.205097871453916891e-01,4.145394140483406320e-02,1.288355348389412236e-01,-4.194902128546083020e-01
+-1.421519329443421131e-01,5.953693400279060910e-01,1.591602986309861162e-02,1.297194457235512077e-01,8.632316183594876402e-02,-4.543397535388165598e-01,1.582451059999256393e-01,-8.301158477194211516e-01,-6.451373185722097947e-02,3.490659988012054793e-01,1.924197278445539255e-02,8.703821904374589580e-03,-4.449458436288291714e-14,-1.100000000000000006e-01,-6.100000000000000977e-01,4.449458436288291714e-14,1.100000000000000006e-01,-7.500000000000000000e-01,6.773121239965471108e-02,-9.244834876218828434e-02,-3.222331755437130574e-01,3.226878760034510019e-02,1.275516512378117029e-01,-4.177668244562868782e-01
+-9.447163462320647132e-02,6.433256773731775846e-01,1.705646484153905060e-02,1.426945809658234088e-01,5.475217720659174975e-02,-4.797609735116552532e-01,1.444180509880232388e-01,-8.476869101482874536e-01,-8.251230611388052361e-02,3.459210837709649766e-01,1.815963020596330843e-02,5.985677071246502633e-03,1.564344650398273584e-02,-1.100000000000000006e-01,-6.108618161583359019e-01,-1.564344650398273584e-02,1.100000000000000006e-01,-7.491381838416641958e-01,7.647976490834468288e-02,-9.416441226738382630e-02,-3.251327416891504063e-01,2.352023509165513879e-02,1.258355877326161609e-01,-4.148672583108494738e-01
+-4.934908311164745015e-02,6.773332858453473548e-01,1.673834903915578931e-02,1.498575406396701615e-01,2.485129274920467105e-02,-4.945905135244695883e-01,1.329767390243129788e-01,-8.412338040720988008e-01,-1.008067836223302260e-01,3.118859117683033255e-01,1.664499566594430935e-02,3.185372749508405543e-03,3.090169943745799813e-02,-1.100000000000000006e-01,-6.134260438593309717e-01,-3.090169943745799813e-02,1.100000000000000006e-01,-7.465739561406691260e-01,8.457629772368893684e-02,-9.627040049785892672e-02,-3.291370886400942219e-01,1.542370227631090912e-02,1.237295995021410744e-01,-4.108629113599056581e-01
+-7.673188385160588376e-03,6.991592328519090627e-01,1.515302578486081055e-02,1.516888329904868549e-01,-2.725583435094811047e-03,-5.007475828906698956e-01,1.240306783858242529e-01,-8.177541401320682635e-01,-1.190744289965742636e-01,2.714130818282372015e-01,1.474786567659690933e-02,7.917428048792922403e-04,4.539904997392223834e-02,-1.100000000000000006e-01,-6.176295433068027529e-01,-4.539904997392223834e-02,1.100000000000000006e-01,-7.423704566931973448e-01,9.182144733692258753e-02,-9.871445703400517913e-02,-3.341476160849467525e-01,8.178552663077272300e-03,1.212855429659948220e-01,-4.058523839150531276e-01
+2.963590179860452201e-02,7.098632864869058867e-01,1.254818146291306925e-02,1.487310921673719588e-01,-2.728787781470154786e-02,-4.994660274918641951e-01,1.178014005988153173e-01,-7.809684223237595146e-01,-1.370588412564924530e-01,2.278042664175800591e-01,1.252216408641236393e-02,-1.026656369142774864e-03,5.877852522921964834e-02,-1.100000000000000006e-01,-6.233688103937397029e-01,-5.877852522921964834e-02,1.100000000000000006e-01,-7.366311896062603948e-01,9.803681411929481004e-02,-1.014364010925440374e-01,-3.400409482090285263e-01,1.963185880705070607e-03,1.185635989074559637e-01,-3.999590517909712983e-01
+6.161585822196484485e-02,7.103901144865949480e-01,9.217067175091440273e-03,1.416878746226535313e-01,-4.810022722826411135e-02,-4.917885642703645477e-01,1.146525911131244663e-01,-7.340487569098781417e-01,-1.545832616036177110e-01,1.832300851383841800e-01,1.002054977264468967e-02,-2.367965080444852689e-03,7.071067811863214481e-02,-1.100000000000000006e-01,-6.305025253169258548e-01,-7.071067811863214481e-02,1.100000000000000006e-01,-7.294974746830742429e-01,1.030693551130038299e-01,-1.043692093771398516e-01,-3.466719716165966858e-01,-3.069355113003914559e-03,1.156307906228601495e-01,-3.933280283834031943e-01
+8.723604095429372818e-02,7.018536152211620749e-01,5.483080761091802847e-03,1.314589164208022909e-01,-6.436012173374359990e-02,-4.787833981385251070e-01,1.151334353455693571e-01,-6.803817301686744257e-01,-1.715712081078800688e-01,1.398613826581218411e-01,7.290000459078703476e-03,-3.411449538233553638e-03,8.090169943747725634e-02,-1.100000000000000006e-01,-6.388550323395101316e-01,-8.090169943747725634e-02,1.100000000000000006e-01,-7.211449676604899661e-01,1.067951524567384847e-01,-1.074406664143932044e-01,-3.538774085042518114e-01,-6.795152456738555447e-03,1.125593335856067967e-01,-3.861225914957480132e-01
+1.053548694612825715e-01,6.854951399744487750e-01,1.678016517601986068e-03,1.190053900479286636e-01,-7.516005639097160518e-02,-4.615221586757103367e-01,1.200377521513062429e-01,-6.233272708743060608e-01,-1.880758526936014696e-01,9.974724695725196988e-02,4.369022085690683899e-03,-4.366040839593244606e-03,8.910065241882493547e-02,-1.100000000000000006e-01,-6.482206650182155139e-01,-8.910065241882493547e-02,1.100000000000000006e-01,-7.117793349817845838e-01,1.091224646546837262e-01,-1.105751427384656788e-01,-3.614798371023464907e-01,-9.122464654683755392e-03,1.094248572615343224e-01,-3.785201628976533339e-01
+1.146620808150881077e-01,6.625800878602937649e-01,-1.890103040917309653e-03,1.052190971445363249e-01,-7.943570573496834542e-02,-4.410041489839087170e-01,1.304791654639478882e-01,-5.658964679616047544e-01,-2.043186048996927795e-01,6.461523056276081978e-02,1.287435098143696697e-03,-5.419406970883674547e-03,9.510565162950797291e-02,-1.100000000000000006e-01,-6.583688103937378466e-01,-9.510565162950797291e-02,1.100000000000000006e-01,-7.016311896062622511e-01,1.099939855566193225e-01,-1.136954571395275421e-01,-3.692920603877802854e-01,-9.993985556619323918e-03,1.063045428604724590e-01,-3.707079396122194836e-01
+1.136141537209063301e-01,6.342675291553673267e-01,-4.987495030832846468e-03,9.083235139048854989e-02,-7.590858215730800218e-02,-4.180607698341586853e-01,1.479745070381071059e-01,-5.104581687393504597e-01,-2.207334564717365333e-01,3.567820158595957913e-02,-1.929766589098719535e-03,-6.698175941160849564e-03,9.876883405951038253e-02,-1.100000000000000006e-01,-6.690495874471689142e-01,-9.876883405951038253e-02,1.100000000000000006e-01,-6.909504125528311835e-01,1.093882554255278666e-01,-1.167247771212951146e-01,-3.771217154959838336e-01,-9.388255425527833320e-03,1.032752228787048865e-01,-3.628782845040159910e-01
+1.003892154377889756e-01,6.015091030975540098e-01,-7.536003586175022903e-03,7.639017381998615408e-02,-6.304935679357247247e-02,-3.932898026092539467e-01,1.745055716380096988e-01,-4.585879697261222021e-01,-2.380022910156708860e-01,1.353823766724961478e-02,-5.252174634719160122e-03,-8.248665217433184815e-03,1.000000000000000056e-01,-1.100000000000000006e-01,-6.799999999999863931e-01,-1.000000000000000056e-01,1.100000000000000006e-01,-6.800000000000137046e-01,1.073201893475398683e-01,-1.195885107720806445e-01,-3.847760103330575276e-01,-7.320189347539800273e-03,1.004114892279193566e-01,-3.552239896669422969e-01
+7.293045398962200165e-02,5.650199172975061135e-01,-9.739606996814092685e-03,6.227748628620616983e-02,-3.912876259706504767e-02,-3.670525667964353311e-01,2.124776593390860779e-01,-4.111058022736375217e-01,-2.570391413965165683e-01,-1.772078937293232893e-03,-8.624325639693529444e-03,-1.003981562872884904e-02,9.876883405951647488e-02,-1.100000000000000006e-01,-6.909504125528043161e-01,-9.876883405951647488e-02,1.100000000000000006e-01,-6.690495874471957816e-01,1.038407099730132149e-01,-1.222161434652146994e-01,-3.920664707569644913e-01,-3.840709973013112233e-03,9.778385653478530171e-02,-3.479335292430353332e-01
+2.922878092784851611e-02,5.253190287860856067e-01,-1.225311428517957858e-02,4.877165008303636917e-02,-2.497974193378981259e-03,-3.395273341131551659e-01,2.643954788337434247e-01,-3.682489008908739203e-01,-2.788295816935535409e-01,-1.064761765343218841e-02,-1.193481551187123256e-02,-1.198181587144324552e-02,9.510565162952000495e-02,-1.100000000000000006e-01,-7.016311896062363829e-01,-9.510565162952000495e-02,1.100000000000000006e-01,-6.583688103937637148e-01,9.903549363187875987e-02,-1.245429741631793458e-01,-3.988135814364170972e-01,9.645063681213567053e-04,9.545702583682065534e-02,-3.411864185635827829e-01
+-3.191699582452062200e-02,4.828051591285057453e-01,-1.631742097927398744e-02,3.609134982023482624e-02,4.768801171434688263e-02,-3.107876914954170178e-01,3.319682847511497559e-01,-3.298837045299489734e-01,-3.039753575647334283e-01,-1.374068819078432153e-02,-1.498012027513210762e-02,-1.395079121639531891e-02,8.910065241884196352e-02,-1.100000000000000006e-01,-7.117793349817612691e-01,-8.910065241884196352e-02,1.100000000000000006e-01,-6.482206650182388286e-01,9.302286069805340563e-02,-1.265117085718824863e-01,-4.048512061141111285e-01,6.977139301946731764e-03,9.348829142811750093e-02,-3.351487938858887516e-01
+-1.095522403409776163e-01,4.378336598936243274e-01,-2.363195766967677441e-02,2.442778464481346751e-02,1.102372783054542948e-01,-2.808774127907708307e-01,4.144794111096221090e-01,-2.956860640216478209e-01,-3.318676187595920868e-01,-1.181813277407433964e-02,-1.744878856003314813e-02,-1.581207081670414280e-02,8.090169943750012693e-02,-1.100000000000000006e-01,-7.211449676604679837e-01,-8.090169943750012693e-02,1.100000000000000006e-01,-6.388550323395321140e-01,8.595086214915372003e-02,-1.280738699163266048e-01,-4.100306784327532039e-01,1.404913785084644512e-02,9.192613008367338245e-02,-3.299693215672467317e-01
+-1.980260120085127473e-01,3.907770986531236002e-01,-3.546144753777221575e-02,1.395745259037704973e-02,1.798060562167019538e-01,-2.498681818960323542e-01,5.040411986082183882e-01,-2.652653009987303023e-01,-3.478089728115816293e-01,-5.665123502615685390e-03,-1.886183327923134784e-02,-1.743836329118081049e-02,7.071067811865965058e-02,-1.100000000000000006e-01,-7.294974746830549250e-01,-7.071067811865965058e-02,1.100000000000000006e-01,-6.305025253169451727e-01,7.799363406007070454e-02,-1.291909925996954089e-01,-4.142244625941756686e-01,2.200636593992947795e-02,9.080900740030457829e-02,-3.257755374058242115e-01
+-2.895443046004523846e-01,3.420655581767208520e-01,-5.160187264023349818e-02,4.841596824619637425e-03,2.492728734053482609e-01,-2.178979182516760649e-01,5.905773675887692198e-01,-2.382376078105666872e-01,-3.489874358007238331e-01,3.968751817802638505e-03,-1.860051970969249513e-02,-1.872202140058379718e-02,5.877852522925112316e-02,-1.100000000000000006e-01,-7.366311896062444076e-01,-5.877852522925112316e-02,1.100000000000000006e-01,-6.233688103937556901e-01,6.934710979488362126e-02,-1.298355693540066969e-01,-4.173292937139527758e-01,3.065289020511658552e-02,9.016443064599329038e-02,-3.226707062860471598e-01
+-3.793666227249671286e-01,2.922088815129959549e-01,-7.120691345995940058e-02,-2.782043068118432438e-03,3.145830796547623986e-01,-1.851921758805964158e-01,6.714023036867858840e-01,-2.142641032479522811e-01,-3.490610897375452382e-01,1.639386155517088758e-02,-1.703940665430539805e-02,-1.958198324588375505e-02,4.539904997395690506e-02,-1.100000000000000006e-01,-7.423704566931850213e-01,-4.539904997395690506e-02,1.100000000000000006e-01,-6.176295433068150764e-01,6.022419547717022814e-02,-1.299917285603417738e-01,-4.192687205455717936e-01,3.977580452282998558e-02,9.000827143965822730e-02,-3.207312794544281975e-01
+-4.622966703091794805e-01,2.418044428697881942e-01,-9.227356492626266615e-02,-8.810760645490368567e-03,3.717175438095682294e-01,-1.520718893937511029e-01,7.407176961220524047e-01,-1.930679167301491139e-01,-3.490656931085965309e-01,3.098756273255526966e-02,-1.457753668247972235e-02,-1.996643096950690907e-02,3.090169943749500672e-02,-1.100000000000000006e-01,-7.465739561406607994e-01,-3.090169943749500672e-02,1.100000000000000006e-01,-6.134260438593392983e-01,5.084952753464945518e-02,-1.296556250607779071e-01,-4.199949879638495975e-01,4.915047246535075853e-02,9.034437493922209406e-02,-3.200050120361503936e-01
+-5.348385334533733992e-01,1.915338529941626178e-01,-1.124415214076325692e-01,-1.318858593752010935e-02,4.184620240911458011e-01,-1.189504629203609748e-01,7.942577162624748777e-01,-1.744406738135721169e-01,-3.490659808192872471e-01,4.719277263855330140e-02,-1.166413896012058124e-02,-1.985221780112772505e-02,1.564344650401976178e-02,-1.100000000000000006e-01,-7.491381838416600880e-01,-1.564344650401976178e-02,1.100000000000000006e-01,-6.108618161583400097e-01,4.145394140480452433e-02,-1.288355348389378652e-01,-4.194902128546047493e-01,5.854605859519568245e-02,9.116446516106212206e-02,-3.205097871453952418e-01
+-5.953693400280795078e-01,1.421519329441871815e-01,-1.297194457236000575e-01,-1.591602986310477336e-02,4.543397535389139819e-01,-8.632316183584626268e-02,8.301158477195067498e-01,-1.582451059998785936e-01,-3.490659988012054238e-01,6.451373185728023762e-02,-8.703821904365492690e-03,-1.924197278445268985e-02,-5.586432040212672135e-15,-1.100000000000000006e-01,-7.500000000000000000e-01,5.586432040212672135e-15,1.100000000000000006e-01,-6.100000000000000977e-01,3.226878760031658827e-02,-1.275516512378069012e-01,-4.177668244562794952e-01,6.773121239968360463e-02,9.244834876219308606e-02,-3.222331755437205514e-01
+-6.433256773733038170e-01,9.447163462306289172e-02,-1.426945809658548281e-01,-1.705646484154020592e-02,4.797609735117165930e-01,-5.475217720649656894e-02,8.476869101483037738e-01,-1.444180509879847696e-01,-3.459210837708809883e-01,8.251230611393722825e-02,-5.985677071238783113e-03,-1.815963020595920754e-02,-1.564344650403079809e-02,-1.100000000000000006e-01,-7.491381838416588668e-01,1.564344650403079809e-02,1.100000000000000006e-01,-6.108618161583412309e-01,2.352023509162912140e-02,-1.258355877326102212e-01,-4.148672583108388157e-01,7.647976490837106456e-02,9.416441226738976600e-02,-3.251327416891612310e-01
+-6.773332858454339522e-01,4.934908311151364746e-02,-1.498575406396840115e-01,-1.673834903915265987e-02,4.945905135245016182e-01,-2.485129274911608566e-02,8.412338040720508392e-01,-1.329767390242819480e-01,-3.118859117681838100e-01,1.008067836223833086e-01,-3.185372749499890653e-03,-1.664499566593817537e-02,-3.090169943750427708e-02,-1.100000000000000006e-01,-7.465739561406585789e-01,3.090169943750427708e-02,1.100000000000000006e-01,-6.134260438593415188e-01,1.542370227628721280e-02,-1.237295995021339967e-01,-4.108629113598917248e-01,8.457629772371295929e-02,9.627040049786600440e-02,-3.291370886401083218e-01
+-6.991592328519592447e-01,7.673188385038621703e-03,-1.516888329904848565e-01,-1.515302578485426370e-02,5.007475828906771120e-01,2.725583435175474821e-03,8.177541401319733394e-01,-1.240306783858013129e-01,-2.714130818281038637e-01,1.190744289966304825e-01,-7.917428048726008697e-04,-1.474786567659225160e-02,-4.539904997396559255e-02,-1.100000000000000006e-01,-7.423704566931819127e-01,4.539904997396559255e-02,1.100000000000000006e-01,-6.176295433068181850e-01,8.178552663056476435e-03,-1.212855429659868006e-01,-4.058523839150363077e-01,9.182144733694366789e-02,9.871445703401320049e-02,-3.341476160849638499e-01
+-7.098632864869229842e-01,-2.963590179871169322e-02,-1.487310921673561104e-01,-1.254818146290370175e-02,4.994660274918500398e-01,2.728787781477180763e-02,7.809684223236283973e-01,-1.178014005988013563e-01,-2.278042664174425580e-01,1.370588412565477143e-01,1.026656369147555762e-03,-1.252216408640497748e-02,-5.877852522925901962e-02,-1.100000000000000006e-01,-7.366311896062404108e-01,5.877852522925901962e-02,1.100000000000000006e-01,-6.233688103937596869e-01,1.963185880687702556e-03,-1.185635989074471791e-01,-3.999590517909519805e-01,9.803681411931242096e-02,1.014364010925528220e-01,-3.400409482090481772e-01
+-7.103901144865817363e-01,-6.161585822205661866e-02,-1.416878746226255537e-01,-9.217067175080046609e-03,4.917885642703311300e-01,4.810022722832324460e-02,7.340487569097164933e-01,-1.146525911131209968e-01,-1.832300851382437645e-01,1.545832616036742768e-01,2.367965080448401066e-03,-1.002054977263626412e-02,-7.071067811866756092e-02,-1.100000000000000006e-01,-7.294974746830493739e-01,7.071067811866756092e-02,1.100000000000000006e-01,-6.305025253169507238e-01,-3.069355113017833980e-03,-1.156307906228505461e-01,-3.933280283833811564e-01,1.030693551130179436e-01,1.043692093771494550e-01,-3.466719716166189458e-01
+-7.018536152211218848e-01,-8.723604095436365835e-02,-1.314589164207657368e-01,-5.483080761079638966e-03,4.787833981384764792e-01,6.436012173378698187e-02,6.803817301684964569e-01,-1.151334353455780585e-01,-1.398613826579887531e-01,1.715712081079342477e-01,3.411449538236513944e-03,-7.290000459069607454e-03,-8.090169943750669113e-02,-1.100000000000000006e-01,-7.211449676604616554e-01,8.090169943750669113e-02,1.100000000000000006e-01,-6.388550323395384423e-01,-6.795152456748172753e-03,-1.125593335855968741e-01,-3.861225914957244765e-01,1.067951524567482546e-01,1.074406664144031270e-01,-3.538774085042756812e-01
+-6.854951399743871576e-01,-1.053548694613255371e-01,-1.190053900478875298e-01,-1.678016517590481598e-03,4.615221586756511618e-01,7.516005639099536395e-02,6.233272708741269819e-01,-1.200377521513295159e-01,-9.974724695713453604e-02,1.880758526936514297e-01,4.366040839596237871e-03,-4.369022085681565325e-03,-8.910065241884702891e-02,-1.100000000000000006e-01,-7.117793349817542747e-01,8.910065241884702891e-02,1.100000000000000006e-01,-6.482206650182458230e-01,-9.122464654688695884e-03,-1.094248572615245940e-01,-3.785201628976295196e-01,1.091224646546887361e-01,1.105751427384754071e-01,-3.614798371023706380e-01
+-6.625800878602132737e-01,-1.146620808151016524e-01,-1.052190971444921241e-01,1.890103040927678529e-03,4.410041489838404938e-01,7.943570573497014953e-02,5.658964679614275628e-01,-1.304791654639904097e-01,-6.461523056266048337e-02,2.043186048997429061e-01,5.419406970887385988e-03,-1.287435098133918494e-03,-9.510565162952301643e-02,-1.100000000000000006e-01,-7.016311896062298326e-01,9.510565162952301643e-02,1.100000000000000006e-01,-6.583688103937702651e-01,-9.993985556619740251e-03,-1.063045428604628972e-01,-3.707079396121953363e-01,1.099939855566197389e-01,1.136954571395371039e-01,-3.692920603878048214e-01
+-6.342675291552715144e-01,-1.136141537208851110e-01,-9.083235139044354423e-02,4.987495030841602485e-03,4.180607698340841893e-01,7.590858215728338299e-02,5.104581687391827050e-01,-1.479745070381741912e-01,-3.567820158587982349e-02,2.207334564717884362e-01,6.698175941165238415e-03,1.929766589108948332e-03,-9.876883405951800143e-02,-1.100000000000000006e-01,-6.909504125527975438e-01,9.876883405951800143e-02,1.100000000000000006e-01,-6.690495874472025539e-01,-9.388255425523697739e-03,-1.032752228786957271e-01,-3.628782845039920657e-01,1.093882554255236755e-01,1.167247771213042740e-01,-3.771217154960080920e-01
+-6.015091030974458741e-01,-1.003892154377273443e-01,-7.639017381994157863e-02,7.536003586182150014e-03,3.932898026091745658e-01,6.304935679351640621e-02,4.585879697259672705e-01,-1.745055716381079258e-01,-1.353823766719136970e-02,2.380022910157253979e-01,8.248665217438451436e-03,5.252174634729319530e-03,-1.000000000000000056e-01,-1.100000000000000006e-01,-6.799999999999796207e-01,1.000000000000000056e-01,1.100000000000000006e-01,-6.800000000000204770e-01,-7.320189347531230739e-03,-1.004114892279108079e-01,-3.552239896669192043e-01,1.073201893475311669e-01,1.195885107720891932e-01,-3.847760103330809534e-01
+-5.650199172973835449e-01,-7.293045398951079894e-02,-6.227748628616171234e-02,9.739606996821118315e-03,3.670525667963490113e-01,3.912876259697044973e-02,4.111058022734922490e-01,-2.124776593392264656e-01,1.772078937332076387e-03,2.570391413965797400e-01,1.003981562873494486e-02,8.624325639703797272e-03,-9.876883405950864780e-02,-1.100000000000000006e-01,-6.690495874471611426e-01,9.876883405950864780e-02,1.100000000000000006e-01,-6.909504125528389551e-01,-3.840709972999942212e-03,-9.778385653477737749e-02,-3.479335292430130178e-01,1.038407099729998506e-01,1.222161434652226236e-01,-3.920664707569871399e-01
+-5.253190287859531571e-01,-2.922878092768380065e-02,-4.877165008299420845e-02,1.225311428518916120e-02,3.395273341130648492e-01,2.497974193242349233e-03,3.682489008907430250e-01,-2.643954788339302198e-01,1.064761765345128078e-02,2.788295816936284810e-01,1.198181587144969348e-02,1.193481551188177968e-02,-9.510565162950451734e-02,-1.100000000000000006e-01,-6.583688103937304081e-01,9.510565162950451734e-02,1.100000000000000006e-01,-7.016311896062696896e-01,9.645063681385582233e-04,-9.545702583681378584e-02,-3.411864185635624658e-01,9.903549363186132937e-02,1.245429741631862153e-01,-3.988135814364376919e-01
+-4.828051591283695765e-01,3.191699582473594282e-02,-3.609134982019690518e-02,1.631742097929067895e-02,3.107876914953258685e-01,-4.768801171452199950e-02,3.298837045298360082e-01,-3.319682847513823476e-01,1.374068819078588799e-02,3.039753575648160289e-01,1.395079121640135575e-02,1.498012027514083674e-02,-8.910065241881987008e-02,-1.100000000000000006e-01,-6.482206650182085195e-01,8.910065241881987008e-02,1.100000000000000006e-01,-7.117793349817915782e-01,6.977139301966944762e-03,-9.348829142811200532e-02,-3.351487938858714322e-01,9.302286069803292201e-02,1.265117085718879819e-01,-4.048512061141287255e-01
+-4.378336598934817747e-01,1.095522403412401424e-01,-2.442778464477918937e-02,2.363195766970620226e-02,2.808774127906767393e-01,-1.102372783056635164e-01,2.956860640215483449e-01,-4.144794111098972222e-01,1.181813277406172473e-02,3.318676187596786287e-01,1.581207081670948922e-02,1.744878856003945211e-02,-8.090169943747152481e-02,-1.100000000000000006e-01,-6.388550323395045805e-01,8.090169943747152481e-02,1.100000000000000006e-01,-7.211449676604955172e-01,1.404913785086966266e-02,-9.192613008366921912e-02,-3.299693215672322433e-01,8.595086214913018330e-02,1.280738699163307681e-01,-4.100306784327678589e-01
+-3.907770986529752189e-01,1.980260120087945497e-01,-1.395745259034676146e-02,3.546144753781590303e-02,2.498681818959351264e-01,-1.798060562169198628e-01,2.652653009986419841e-01,-5.040411986084928353e-01,5.665123502591351556e-03,3.478089728115927870e-01,1.743836329118521322e-02,1.886183327923291603e-02,-7.071067811862524755e-02,-1.100000000000000006e-01,-6.305025253169210808e-01,7.071067811862524755e-02,1.100000000000000006e-01,-7.294974746830790169e-01,2.200636593995512064e-02,-9.080900740030184437e-02,-3.257755374058129427e-01,7.799363406004469756e-02,1.291909925996981567e-01,-4.142244625941871039e-01
+-3.420655581765668640e-01,2.895443046007349364e-01,-4.841596824593438764e-03,5.160187264028925219e-02,2.178979182515750623e-01,-2.492728734055581763e-01,2.382376078104865291e-01,-5.905773675890300112e-01,-3.968751817836553217e-03,3.489874358007244992e-01,1.872202140058723888e-02,1.860051970968944549e-02,-5.877852522921176576e-02,-1.100000000000000006e-01,-6.233688103937355951e-01,5.877852522921176576e-02,1.100000000000000006e-01,-7.366311896062645026e-01,3.065289020514402538e-02,-9.016443064599204138e-02,-3.226707062860393882e-01,6.934710979485578242e-02,1.298355693540079459e-01,-4.173292937139606584e-01
+-2.922088815128340844e-01,3.793666227252415757e-01,2.782043068140495519e-03,7.120691346002444577e-02,1.851921758804899454e-01,-3.145830796549565211e-01,2.142641032478785068e-01,-6.714023036870230277e-01,-1.639386155521516120e-02,3.490610897375452937e-01,1.958198324588578815e-02,1.703940665429888243e-02,-4.539904997391228103e-02,-1.100000000000000006e-01,-6.176295433067992002e-01,4.539904997391228103e-02,1.100000000000000006e-01,-7.423704566932008975e-01,3.977580452285939261e-02,-9.000827143965851873e-02,-3.207312794544239232e-01,6.022419547714041171e-02,1.299917285603414685e-01,-4.192687205455760679e-01
+-2.418044428696254911e-01,4.622966703094257834e-01,8.810760645507280386e-03,9.227356492632847462e-02,1.520718893936437166e-01,-3.717175438097319318e-01,1.930679167300836663e-01,-7.407176961222455835e-01,-3.098756273260520888e-02,3.490656931085965309e-01,1.996643096950734969e-02,1.457753668247091169e-02,-3.090169943744737469e-02,-1.100000000000000006e-01,-6.134260438593285292e-01,3.090169943744737469e-02,1.100000000000000006e-01,-7.465739561406715685e-01,4.915047246538059578e-02,-9.034437493922393980e-02,-3.200050120361500605e-01,5.084952753461920161e-02,1.296556250607760474e-01,-4.199949879638499306e-01
+-1.915338529940068535e-01,5.348385334535790125e-01,1.318858593753120985e-02,1.124415214076910779e-01,1.189504629202580571e-01,-4.184620240912732547e-01,1.744406738135169388e-01,-7.942577162626125453e-01,-4.719277263860496840e-02,3.490659808192872471e-01,1.985221780112658360e-02,1.166413896011140108e-02,-1.564344650397169953e-02,-1.100000000000000006e-01,-6.108618161583346806e-01,1.564344650397169953e-02,1.100000000000000006e-01,-7.491381838416654171e-01,5.854605859522438172e-02,-9.116446516106539721e-02,-3.205097871453986835e-01,4.145394140477542261e-02,1.288355348389345900e-01,-4.194902128546013076e-01
+-1.421519329440361912e-01,5.953693400282473736e-01,1.591602986311068182e-02,1.297194457236473808e-01,8.632316183574667567e-02,-4.543397535390083508e-01,1.582451059998315757e-01,-8.301158477195899055e-01,-6.451373185733520754e-02,3.490659988012054238e-01,1.924197278445089962e-02,8.703821904356510292e-03,5.424636297178806293e-14,-1.100000000000000006e-01,-6.100000000000000977e-01,-5.424636297178806293e-14,1.100000000000000006e-01,-7.500000000000000000e-01,6.773121239971130469e-02,-9.244834876219774900e-02,-3.222331755437276568e-01,3.226878760028850657e-02,1.275516512378022382e-01,-4.177668244562722788e-01
+-9.447163462291852110e-02,6.433256773734292722e-01,1.705646484154138900e-02,1.426945809658857478e-01,5.475217720640100649e-02,-4.797609735117774887e-01,1.444180509879449681e-01,-8.476869101483187618e-01,-8.251230611399119896e-02,3.459210837707948905e-01,1.815963020595523156e-02,5.985677071230988133e-03,1.564344650407886034e-02,-1.100000000000000006e-01,-6.108618161583465600e-01,-1.564344650407886034e-02,1.100000000000000006e-01,-7.491381838416535377e-01,7.647976490839708541e-02,-9.416441226739571957e-02,-3.251327416891719446e-01,2.352023509160273973e-02,1.258355877326042815e-01,-4.148672583108279910e-01
+-4.934908311137790882e-02,6.773332858455191063e-01,1.673834903914958594e-02,1.498575406396974452e-01,2.485129274902618188e-02,-4.945905135245330930e-01,1.329767390242492242e-01,-8.412338040720009902e-01,-1.008067836224395969e-01,3.118859117680650717e-01,1.664499566593278385e-02,3.185372749491622961e-03,3.090169943755055604e-02,-1.100000000000000006e-01,-6.134260438593519549e-01,-3.090169943755055604e-02,1.100000000000000006e-01,-7.465739561406481428e-01,8.457629772373664867e-02,-9.627040049787308207e-02,-3.291370886401222551e-01,1.542370227626318341e-02,1.237295995021269190e-01,-4.108629113598776250e-01
+-7.673188384911234020e-03,6.991592328520104260e-01,1.515302578484741154e-02,1.516888329904827470e-01,-2.725583435259631461e-03,-5.007475828906841064e-01,1.240306783857761663e-01,-8.177541401318759728e-01,-1.190744289966898101e-01,2.714130818279706925e-01,1.474786567658549138e-02,7.917428048660724547e-04,4.539904997401021658e-02,-1.100000000000000006e-01,-6.176295433068340612e-01,-4.539904997401021658e-02,1.100000000000000006e-01,-7.423704566931660365e-01,9.182144733696506744e-02,-9.871445703402147165e-02,-3.341476160849811694e-01,8.178552663034785453e-03,1.212855429659785295e-01,-4.058523839150187107e-01
+2.963590179882333309e-02,7.098632864869404147e-01,1.254818146289410699e-02,1.487310921673397901e-01,-2.728787781484499561e-02,-4.994660274918352738e-01,1.178014005987857715e-01,-7.809684223234937273e-01,-1.370588412566059178e-01,2.278042664173023923e-01,1.252216408639732388e-02,-1.026656369152396941e-03,5.877852522929952889e-02,-1.100000000000000006e-01,-6.233688103937803371e-01,-5.877852522929952889e-02,1.100000000000000006e-01,-7.366311896062197606e-01,9.803681411933030942e-02,-1.014364010925618842e-01,-3.400409482090680502e-01,1.963185880669571226e-03,1.185635989074381169e-01,-3.999590517909317744e-01
+6.161585822214687980e-02,7.103901144865687467e-01,9.217067175068909685e-03,1.416878746225984365e-01,-4.810022722838145498e-02,-4.917885642702985449e-01,1.146525911131158898e-01,-7.340487569095590636e-01,-1.545832616037274565e-01,1.832300851381066520e-01,1.002054977262815082e-02,-2.367965080452028373e-03,7.071067811870196396e-02,-1.100000000000000006e-01,-6.305025253169748156e-01,-7.071067811870196396e-02,1.100000000000000006e-01,-7.294974746830252821e-01,1.030693551130314745e-01,-1.043692093771587948e-01,-3.466719716166403176e-01,-3.069355113031559112e-03,1.156307906228412063e-01,-3.933280283833595070e-01
+8.723604095443250606e-02,7.018536152210821388e-01,5.483080761067769988e-03,1.314589164207298766e-01,-6.436012173382968382e-02,-4.787833981384287951e-01,1.151334353455851917e-01,-6.803817301683225960e-01,-1.715712081079850682e-01,1.398613826578572195e-01,7.290000459060924295e-03,-3.411449538239645553e-03,8.090169943753529325e-02,-1.100000000000000006e-01,-6.388550323395659758e-01,-8.090169943753529325e-02,1.100000000000000006e-01,-7.211449676604341219e-01,1.067951524567575944e-01,-1.074406664144127860e-01,-3.538774085042985518e-01,-6.795152456757651283e-03,1.125593335855872151e-01,-3.861225914957012728e-01
+1.053548694613690578e-01,6.854951399743257623e-01,1.678016517578886490e-03,1.190053900478462157e-01,-7.516005639101953906e-02,-4.615221586755913763e-01,1.200377521513520673e-01,-6.233272708739481249e-01,-1.880758526937013619e-01,9.974724695701470134e-02,4.369022085672294095e-03,-4.366040839599024705e-03,8.910065241886910847e-02,-1.100000000000000006e-01,-6.482206650182761321e-01,-8.910065241886910847e-02,1.100000000000000006e-01,-7.117793349817239656e-01,1.091224646546936766e-01,-1.105751427384851354e-01,-3.614798371023944523e-01,-9.122464654693705766e-03,1.094248572615148657e-01,-3.785201628976053723e-01
+1.146620808151154053e-01,6.625800878601337818e-01,-1.890103040938148019e-03,1.052190971444482703e-01,-7.943570573497209242e-02,-4.410041489837731032e-01,1.304791654640325149e-01,-5.658964679612524806e-01,-2.043186048997930049e-01,6.461523056256113229e-02,1.287435098124097357e-03,-5.419406970890973396e-03,9.510565162953804608e-02,-1.100000000000000006e-01,-6.583688103938025726e-01,-9.510565162953804608e-02,1.100000000000000006e-01,-7.016311896061975251e-01,1.099939855566201552e-01,-1.136954571395466657e-01,-3.692920603878289687e-01,-9.993985556620149646e-03,1.063045428604533355e-01,-3.707079396121708559e-01
+1.136141537208634894e-01,6.342675291551745920e-01,-4.987495030850522433e-03,9.083235139039749773e-02,-7.590858215725820868e-02,-4.180607698340082501e-01,1.479745070382432748e-01,-5.104581687390118416e-01,-2.207334564718416714e-01,3.567820158579864537e-02,-1.929766589119286634e-03,-6.698175941169707930e-03,9.876883405952584238e-02,-1.100000000000000006e-01,-6.690495874472371929e-01,-9.876883405952584238e-02,1.100000000000000006e-01,-6.909504125527629048e-01,1.093882554255194151e-01,-1.167247771213137109e-01,-3.771217154960326834e-01,-9.388255425519388686e-03,1.032752228786862903e-01,-3.628782845039671412e-01
+1.003892154376639090e-01,6.015091030973359620e-01,-7.536003586189580702e-03,7.639017381989603173e-02,-6.304935679345914645e-02,-3.932898026090934640e-01,1.745055716382090116e-01,-4.585879697258095633e-01,-2.380022910157834348e-01,1.353823766713217573e-02,-5.252174634740166756e-03,-8.248665217443803058e-03,1.000000000000000056e-01,-1.100000000000000006e-01,-6.800000000000555600e-01,-1.000000000000000056e-01,1.100000000000000006e-01,-6.799999999999445377e-01,1.073201893475223545e-01,-1.195885107720979779e-01,-3.847760103331047121e-01,-7.320189347522286505e-03,1.004114892279020232e-01,-3.552239896668951125e-01
+7.293045398940087298e-02,5.650199172972660833e-01,-9.739606996828003432e-03,6.227748628611909365e-02,-3.912876259687689262e-02,-3.670525667962662997e-01,2.124776593393652713e-01,-4.111058022733533601e-01,-2.570391413966428562e-01,-1.772078937368850356e-03,-8.624325639714269798e-03,-1.003981562874076139e-02,9.876883405950102890e-02,-1.100000000000000006e-01,-6.909504125528725949e-01,-9.876883405950102890e-02,1.100000000000000006e-01,-6.690495874471275028e-01,1.038407099729870692e-01,-1.222161434652303258e-01,-3.920664707570087892e-01,-3.840709972986966481e-03,9.778385653476967532e-02,-3.479335292429910353e-01
+2.922878092751963336e-02,5.253190287858268137e-01,-1.225311428519862411e-02,4.877165008295382409e-02,-2.497974193106277524e-03,-3.395273341129783629e-01,2.643954788341177364e-01,-3.682489008906189021e-01,-2.788295816937020888e-01,-1.064761765346888302e-02,-1.193481551189190179e-02,-1.198181587145576328e-02,9.510565162948948770e-02,-1.100000000000000006e-01,-7.016311896063021081e-01,-9.510565162948948770e-02,1.100000000000000006e-01,-6.583688103936979896e-01,9.903549363184462051e-02,-1.245429741631929044e-01,-3.988135814364574538e-01,9.645063681555030022e-04,9.545702583680709674e-02,-3.411864185635424263e-01
+-3.191699582495480941e-02,4.828051591282352950e-01,-1.631742097930753005e-02,3.609134982015942822e-02,4.768801171469995437e-02,-3.107876914952358849e-01,3.319682847516196578e-01,-3.298837045297257631e-01,-3.039753575648987405e-01,-1.374068819078677617e-02,-1.498012027514942883e-02,-1.395079121640725207e-02,8.910065241879777664e-02,-1.100000000000000006e-01,-7.117793349818218873e-01,-8.910065241879777664e-02,1.100000000000000006e-01,-6.482206650181782104e-01,9.302286069801271595e-02,-1.265117085718934775e-01,-4.048512061141460450e-01,6.977139301987428377e-03,9.348829142810650972e-02,-3.351487938858538351e-01
+-1.095522403415047918e-01,4.378336598933396107e-01,-2.363195766973593195e-02,2.442778464474494940e-02,1.102372783058747086e-01,-2.808774127905827034e-01,4.144794111101752776e-01,-2.956860640214493685e-01,-3.318676187597693339e-01,-1.181813277404846103e-02,-1.744878856004593998e-02,-1.581207081671492931e-02,8.090169943744292269e-02,-1.100000000000000006e-01,-7.211449676605230508e-01,-8.090169943744292269e-02,1.100000000000000006e-01,-6.388550323394770469e-01,8.595086214910696576e-02,-1.280738699163349592e-01,-4.100306784327823473e-01,1.404913785089319245e-02,9.192613008366504190e-02,-3.299693215672175883e-01
+-1.980260120090825415e-01,3.907770986528220081e-01,-3.546144753786034665e-02,1.395745259031535429e-02,1.798060562171427679e-01,-2.498681818958343737e-01,5.040411986087713903e-01,-2.652653009985500021e-01,-3.478089728116038892e-01,-5.665123502565243101e-03,-1.886183327923465422e-02,-1.743836329119007739e-02,7.071067811858983143e-02,-1.100000000000000006e-01,-7.294974746831037749e-01,-7.071067811858983143e-02,1.100000000000000006e-01,-6.305025253168963228e-01,7.799363406001830201e-02,-1.291909925997009601e-01,-4.142244625941987057e-01,2.200636593998188048e-02,9.080900740029902718e-02,-3.257755374058011744e-01
+-2.895443046010261479e-01,3.420655581764095454e-01,-5.160187264034670623e-02,4.841596824566674583e-03,2.492728734057744477e-01,-2.178979182514718116e-01,5.905773675892980190e-01,-2.382376078104055661e-01,-3.489874358007252209e-01,3.968751817873805536e-03,-1.860051970968637156e-02,-1.872202140059083322e-02,5.877852522917124262e-02,-1.100000000000000006e-01,-7.366311896062850417e-01,-5.877852522917124262e-02,1.100000000000000006e-01,-6.233688103937150560e-01,6.934710979482754112e-02,-1.298355693540092226e-01,-4.173292937139687075e-01,3.065289020517266219e-02,9.016443064599076462e-02,-3.226707062860312281e-01
+-3.793666227255130252e-01,2.922088815126792083e-01,-7.120691346008907463e-02,-2.782043068161607971e-03,3.145830796551488673e-01,-1.851921758803882212e-01,6.714023036872606154e-01,-2.142641032478095620e-01,-3.490610897375452937e-01,1.639386155525757519e-02,-1.703940665429245355e-02,-1.958198324588773798e-02,4.539904997386892682e-02,-1.100000000000000006e-01,-7.423704566932164406e-01,-4.539904997386892682e-02,1.100000000000000006e-01,-6.176295433067836571e-01,6.022419547711184429e-02,-1.299917285603411909e-01,-4.192687205455801758e-01,3.977580452288836249e-02,9.000827143965879629e-02,-3.207312794544197598e-01
+-4.622966703096702545e-01,2.418044428694708092e-01,-9.227356492639429697e-02,-8.810760645523132290e-03,3.717175438098951901e-01,-1.520718893935422422e-01,7.407176961224408718e-01,-1.930679167300236032e-01,-3.490656931085965309e-01,3.098756273265057537e-02,-1.457753668246229359e-02,-1.996643096950743296e-02,3.090169943740109920e-02,-1.100000000000000006e-01,-7.465739561406821156e-01,-3.090169943740109920e-02,1.100000000000000006e-01,-6.134260438593179821e-01,5.084952753459021785e-02,-1.296556250607742433e-01,-4.199949879638503192e-01,4.915047246540999587e-02,9.034437493922574391e-02,-3.200050120361496719e-01
+-5.348385334537879565e-01,1.915338529938538648e-01,-1.124415214077509190e-01,-1.318858593754195126e-02,4.184620240914027622e-01,-1.189504629201575958e-01,7.942577162627550980e-01,-1.744406738134648693e-01,-3.490659808192872471e-01,4.719277263865755134e-02,-1.166413896010194684e-02,-1.985221780112588971e-02,1.564344650392364075e-02,-1.100000000000000006e-01,-7.491381838416707462e-01,-1.564344650392364075e-02,1.100000000000000006e-01,-6.108618161583293515e-01,4.145394140474673028e-02,-1.288355348389313149e-01,-4.194902128545978659e-01,5.854605859525348344e-02,9.116446516106867237e-02,-3.205097871454021807e-01
+-5.953693400284167936e-01,1.421519329438863666e-01,-1.297194457236952869e-01,-1.591602986311656254e-02,4.543397535391036635e-01,-8.632316183564756051e-02,8.301158477196743934e-01,-1.582451059997860565e-01,-3.490659988012054793e-01,6.451373185738869254e-02,-8.703821904347553914e-03,-1.924197278444772508e-02,-1.029062939033634648e-13,-1.100000000000000006e-01,-7.500000000000000000e-01,1.029062939033634648e-13,1.100000000000000006e-01,-6.100000000000000977e-01,3.226878760026080650e-02,-1.275516512377975753e-01,-4.177668244562651179e-01,6.773121239973939334e-02,9.244834876220241193e-02,-3.222331755437348733e-01
+-6.433256773735589462e-01,9.447163462277055612e-02,-1.426945809659178055e-01,-1.705646484154259290e-02,4.797609735118405494e-01,-5.475217720630281421e-02,8.476869101483350821e-01,-1.444180509879054164e-01,-3.459210837707100694e-01,8.251230611405142856e-02,-5.985677071223304176e-03,-1.815963020595096414e-02,-1.564344650412832424e-02,-1.100000000000000006e-01,-7.491381838416479866e-01,1.564344650412832424e-02,1.100000000000000006e-01,-6.108618161583521111e-01,2.352023509157596254e-02,-1.258355877325981476e-01,-4.148672583108170553e-01,7.647976490842423036e-02,9.416441226740183967e-02,-3.251327416891830469e-01
+-6.773332858456075911e-01,4.934908311123963054e-02,-1.498575406397116283e-01,-1.673834903914644609e-02,4.945905135245659001e-01,-2.485129274893462664e-02,8.412338040719512522e-01,-1.329767390242178049e-01,-3.118859117679457782e-01,1.008067836224997849e-01,-3.185372749483197409e-03,-1.664499566592680599e-02,-3.090169943759818461e-02,-1.100000000000000006e-01,-7.465739561406372626e-01,3.090169943759818461e-02,1.100000000000000006e-01,-6.134260438593628351e-01,1.542370227623880014e-02,-1.237295995021196332e-01,-4.108629113598633031e-01,8.457629772376137889e-02,9.627040049788036791e-02,-3.291370886401367990e-01
+-6.991592328520604971e-01,7.673188384789152855e-03,-1.516888329904806931e-01,-1.515302578484074326e-02,5.007475828906913229e-01,2.725583435340179009e-03,8.177541401317811598e-01,-1.240306783857532680e-01,-2.714130818278392421e-01,1.190744289967448910e-01,-7.917428048595197537e-04,-1.474786567657751513e-02,-4.539904997405357079e-02,-1.100000000000000006e-01,-7.423704566931504933e-01,4.539904997405357079e-02,1.100000000000000006e-01,-6.176295433068496044e-01,8.178552663014003465e-03,-1.212855429659704942e-01,-4.058523839150018908e-01,9.182144733698616168e-02,9.871445703402950689e-02,-3.341476160849982668e-01
+-7.098632864869570680e-01,-2.963590179893045920e-02,-1.487310921673237474e-01,-1.254818146288475336e-02,4.994660274918207299e-01,2.728787781491516864e-02,7.809684223233616107e-01,-1.178014005987714774e-01,-2.278042664171630594e-01,1.370588412566597081e-01,1.026656369157328543e-03,-1.252216408639008315e-02,-5.877852522933890017e-02,-1.100000000000000006e-01,-7.366311896061997766e-01,5.877852522933890017e-02,1.100000000000000006e-01,-6.233688103938003211e-01,1.963185880652203175e-03,-1.185635989074293323e-01,-3.999590517909124565e-01,9.803681411934792034e-02,1.014364010925706688e-01,-3.400409482090877011e-01
+-7.103901144865553130e-01,-6.161585822223625275e-02,-1.416878746225708752e-01,-9.217067175057845618e-03,4.917885642702655713e-01,4.810022722843834697e-02,7.340487569094006348e-01,-1.146525911131115183e-01,-1.832300851379680129e-01,1.545832616037794427e-01,2.367965080455683869e-03,-1.002054977262164560e-02,-7.071067811873636699e-02,-1.100000000000000006e-01,-7.294974746830011902e-01,7.071067811873636699e-02,1.100000000000000006e-01,-6.305025253169989075e-01,-3.069355113045083017e-03,-1.156307906228318666e-01,-3.933280283833381352e-01,1.030693551130451857e-01,1.043692093771681345e-01,-3.466719716166620224e-01
+-7.018536152210433920e-01,-8.723604095450043783e-02,-1.314589164206944882e-01,-5.483080761055911419e-03,4.787833981383816107e-01,6.436012173387208046e-02,6.803817301681498453e-01,-1.151334353455936987e-01,-1.398613826577283226e-01,1.715712081080378315e-01,3.411449538242646191e-03,-7.290000459051398062e-03,-8.090169943756389537e-02,-1.100000000000000006e-01,-7.211449676604065884e-01,8.090169943756389537e-02,1.100000000000000006e-01,-6.388550323395935093e-01,-6.795152456767004912e-03,-1.125593335855775701e-01,-3.861225914956784022e-01,1.067951524567670729e-01,1.074406664144224310e-01,-3.538774085043216999e-01
+-6.854951399742624796e-01,-1.053548694614131892e-01,-1.190053900478040549e-01,-1.678016517566983251e-03,4.615221586755310912e-01,7.516005639104392233e-02,6.233272708737644940e-01,-1.200377521513764506e-01,-9.974724695689554665e-02,1.880758526937541253e-01,4.366040839602174962e-03,-4.369022085662636022e-03,-8.910065241889185417e-02,-1.100000000000000006e-01,-7.117793349816926574e-01,8.910065241889185417e-02,1.100000000000000006e-01,-6.482206650183074403e-01,-9.122464654698791975e-03,-1.094248572615048459e-01,-3.785201628975808363e-01,1.091224646546988253e-01,1.105751427384951552e-01,-3.614798371024193213e-01
+-6.625800878600516253e-01,-1.146620808151294912e-01,-1.052190971444031120e-01,1.890103040948832615e-03,4.410041489837036033e-01,7.943570573497404919e-02,5.658964679610717363e-01,-1.304791654640762577e-01,-6.461523056245878360e-02,2.043186048998449633e-01,5.419406970894532181e-03,-1.287435098114085835e-03,-9.510565162955353369e-02,-1.100000000000000006e-01,-7.016311896061641074e-01,9.510565162955353369e-02,1.100000000000000006e-01,-6.583688103938359903e-01,-9.993985556620579858e-03,-1.063045428604434961e-01,-3.707079396121459869e-01,1.099939855566205854e-01,1.136954571395565050e-01,-3.692920603878541708e-01
+-6.342675291550790018e-01,-1.136141537208425617e-01,-9.083235139035249206e-02,4.987495030859271511e-03,4.180607698339338096e-01,7.590858215723367275e-02,5.104581687388445310e-01,-1.479745070383100547e-01,-3.567820158571916034e-02,2.207334564718924641e-01,6.698175941174077698e-03,1.929766589129378387e-03,-9.876883405953344741e-02,-1.100000000000000006e-01,-6.909504125527292651e-01,9.876883405953344741e-02,1.100000000000000006e-01,-6.690495874472708326e-01,-9.388255425515260044e-03,-1.032752228786771309e-01,-3.628782845039432159e-01,1.093882554255152378e-01,1.167247771213228702e-01,-3.771217154960569418e-01
+-6.015091030972276043e-01,-1.003892154376017226e-01,-7.639017381985147015e-02,7.536003586196690467e-03,3.932898026090139165e-01,6.304935679340302468e-02,4.585879697256542986e-01,-1.745055716383079325e-01,-1.353823766707386647e-02,2.380022910158391680e-01,8.248665217449034984e-03,5.252174634750435452e-03,-1.000000000000000056e-01,-1.100000000000000006e-01,-6.799999999999104539e-01,1.000000000000000056e-01,1.100000000000000006e-01,-6.800000000000896438e-01,-7.320189347513716971e-03,-1.004114892278934884e-01,-3.552239896668720198e-01,1.073201893475136670e-01,1.195885107721065127e-01,-3.847760103331281378e-01
+-5.650199172971474004e-01,-7.293045398929137724e-02,-6.227748628607603087e-02,9.739606996834789671e-03,3.670525667961826444e-01,3.912876259678362001e-02,4.111058022732130279e-01,-2.124776593395037438e-01,1.772078937406153850e-03,2.570391413967065830e-01,1.003981562874657965e-02,8.624325639725042431e-03,-9.876883405949342387e-02,-1.100000000000000006e-01,-6.690495874470938631e-01,9.876883405949342387e-02,1.100000000000000006e-01,-6.909504125529062346e-01,-3.840709972974171160e-03,-9.778385653476195927e-02,-3.479335292429693860e-01,1.038407099729740934e-01,1.222161434652380418e-01,-3.920664707570307717e-01
+-5.253190287856986940e-01,-2.922878092735815142e-02,-4.877165008291301646e-02,1.225311428520796733e-02,3.395273341128908218e-01,2.497974192972551161e-03,3.682489008904926697e-01,-2.643954788343015339e-01,1.064761765348729190e-02,2.788295816937738647e-01,1.198181587146187992e-02,1.193481551190166481e-02,-9.510565162947445805e-02,-1.100000000000000006e-01,-6.583688103936655711e-01,9.510565162947445805e-02,1.100000000000000006e-01,-7.016311896063345266e-01,9.645063681722049198e-04,-9.545702583680042153e-02,-3.411864185635226643e-01,9.903549363182767573e-02,1.245429741631995796e-01,-3.988135814364774379e-01
+-4.828051591280940746e-01,3.191699582517383560e-02,-3.609134982012014714e-02,1.631742097932448524e-02,3.107876914951412939e-01,-4.768801171487832558e-02,3.298837045296083015e-01,-3.319682847518553581e-01,1.374068819078869824e-02,3.039753575649828954e-01,1.395079121641350575e-02,1.498012027515842511e-02,-8.910065241877503095e-02,-1.100000000000000006e-01,-6.482206650181469021e-01,8.910065241877503095e-02,1.100000000000000006e-01,-7.117793349818531956e-01,6.977139302008238120e-03,-9.348829142810086146e-02,-3.351487938858360160e-01,9.302286069799162171e-02,1.265117085718991397e-01,-4.048512061141640861e-01
+-4.378336598931914514e-01,1.095522403417712176e-01,-2.442778464470924185e-02,2.363195766976584899e-02,2.808774127904845597e-01,-1.102372783060870526e-01,2.956860640213446745e-01,-4.144794111104529444e-01,1.181813277403589643e-02,3.318676187598575411e-01,1.581207081672069553e-02,1.744878856005222315e-02,-8.090169943741348790e-02,-1.100000000000000006e-01,-6.388550323394486252e-01,8.090169943741348790e-02,1.100000000000000006e-01,-7.211449676605514725e-01,1.404913785091709000e-02,-9.192613008366075367e-02,-3.299693215672026558e-01,8.595086214908274902e-02,1.280738699163392336e-01,-4.100306784327974463e-01
+-3.907770986526729606e-01,1.980260120093625120e-01,-1.395745259028483357e-02,3.546144753790374249e-02,2.498681818957364242e-01,-1.798060562173592614e-01,2.652653009984605181e-01,-5.040411986090428398e-01,5.665123502541153863e-03,3.478089728116149359e-01,1.743836329119464665e-02,1.886183327923633343e-02,-7.071067811855542840e-02,-1.100000000000000006e-01,-6.305025253168722310e-01,7.071067811855542840e-02,1.100000000000000006e-01,-7.294974746831278667e-01,2.200636594000752316e-02,-9.080900740029627938e-02,-3.257755374057899056e-01,7.799363405999229504e-02,1.291909925997037079e-01,-4.142244625942101410e-01
+-3.420655581762563902e-01,2.895443046013103094e-01,-4.841596824540693629e-03,5.160187264040314720e-02,2.178979182513716695e-01,-2.492728734059863338e-01,2.382376078103264627e-01,-5.905773675895611419e-01,-3.968751817906587473e-03,3.489874358007258870e-01,1.872202140059409797e-02,1.860051970968334967e-02,-5.877852522913187827e-02,-1.100000000000000006e-01,-6.233688103936949609e-01,5.877852522913187827e-02,1.100000000000000006e-01,-7.366311896063051368e-01,3.065289020520010899e-02,-9.016443064598951562e-02,-3.226707062860234565e-01,6.934710979479970228e-02,1.298355693540104716e-01,-4.173292937139765901e-01
+-2.922088815125237771e-01,3.793666227257835866e-01,2.782043068182641493e-03,7.120691346015357859e-02,1.851921758802864137e-01,-3.145830796553408248e-01,2.142641032477398677e-01,-6.714023036874974260e-01,-1.639386155529775832e-02,3.490610897375453492e-01,1.958198324588941372e-02,1.703940665428579568e-02,-4.539904997382557261e-02,-1.100000000000000006e-01,-6.176295433067682250e-01,4.539904997382557261e-02,1.100000000000000006e-01,-7.423704566932318727e-01,3.977580452291692992e-02,-9.000827143965907384e-02,-3.207312794544156520e-01,6.022419547708287441e-02,1.299917285603409134e-01,-4.192687205455843946e-01
+-2.418044428693137682e-01,4.622966703099113950e-01,8.810760645539358893e-03,9.227356492645907848e-02,1.520718893934388249e-01,-3.717175438100561169e-01,1.930679167299612364e-01,-7.407176961226316081e-01,-3.098756273269836700e-02,3.490656931085965864e-01,1.996643096950783541e-02,1.457753668245372232e-02,-3.090169943735482025e-02,-1.100000000000000006e-01,-6.134260438593074349e-01,3.090169943735482025e-02,1.100000000000000006e-01,-7.465739561406926628e-01,4.915047246543897963e-02,-9.034437493922753415e-02,-3.200050120361493389e-01,5.084952753456081775e-02,1.296556250607724670e-01,-4.199949879638506522e-01
+-1.915338529936931600e-01,5.348385334539975666e-01,1.318858593755347329e-02,1.124415214078105379e-01,1.189504629200515140e-01,-4.184620240915324363e-01,1.744406738134083590e-01,-7.942577162628936538e-01,-4.719277263871414496e-02,3.490659808192872471e-01,1.985221780112509521e-02,1.166413896009260362e-02,-1.564344650387417685e-02,-1.100000000000000006e-01,-6.108618161583239115e-01,1.564344650387417685e-02,1.100000000000000006e-01,-7.491381838416761862e-01,5.854605859528301537e-02,-9.116446516107203080e-02,-3.205097871454057334e-01,4.145394140471678202e-02,1.288355348389279564e-01,-4.194902128545942577e-01
+-1.421519329437295476e-01,5.953693400285881010e-01,1.591602986312275897e-02,1.297194457237433873e-01,8.632316183554374078e-02,-4.543397535392000863e-01,1.582451059997367626e-01,-8.301158477197572161e-01,-6.451373185744693761e-02,3.490659988012054238e-01,1.924197278444487319e-02,8.703821904338489984e-03,1.529873103064590619e-13,-1.100000000000000006e-01,-6.100000000000000977e-01,-1.529873103064590619e-13,1.100000000000000006e-01,-7.500000000000000000e-01,6.773121239976789831e-02,-9.244834876220721365e-02,-3.222331755437422562e-01,3.226878760023189907e-02,1.275516512377927736e-01,-4.177668244562576794e-01
+-9.447163462262542222e-02,6.433256773736841794e-01,1.705646484154386272e-02,1.426945809659487807e-01,5.475217720620675910e-02,-4.797609735119013341e-01,1.444180509878653651e-01,-8.476869101483499591e-01,-8.251230611410784177e-02,3.459210837706256370e-01,1.815963020594702285e-02,5.985677071215634096e-03,1.564344650417638302e-02,-1.100000000000000006e-01,-6.108618161583574402e-01,-1.564344650417638302e-02,1.100000000000000006e-01,-7.491381838416426575e-01,7.647976490845023734e-02,-9.416441226740777937e-02,-3.251327416891937050e-01,2.352023509154957739e-02,1.258355877325922079e-01,-4.148672583108062306e-01
+-4.934908311110430823e-02,6.773332858456928562e-01,1.673834903914329930e-02,1.498575406397250342e-01,2.485129274884503858e-02,-4.945905135245973194e-01,1.329767390241852199e-01,-8.412338040719012922e-01,-1.008067836225541997e-01,3.118859117678249304e-01,1.664499566592146651e-02,3.185372749474751474e-03,3.090169943764446703e-02,-1.100000000000000006e-01,-6.134260438593733822e-01,-3.090169943764446703e-02,1.100000000000000006e-01,-7.465739561406267155e-01,8.457629772378506827e-02,-9.627040049788744558e-02,-3.291370886401506768e-01,1.542370227621477075e-02,1.237295995021125555e-01,-4.108629113598492033e-01
+-7.673188384665774117e-03,6.991592328521101241e-01,1.515302578483410101e-02,1.516888329904785282e-01,-2.725583435421626011e-03,-5.007475828906982063e-01,1.240306783857285933e-01,-8.177541401316856806e-01,-1.190744289967990838e-01,2.714130818277060708e-01,1.474786567657128226e-02,7.917428048529226003e-04,4.539904997409693194e-02,-1.100000000000000006e-01,-6.176295433068650365e-01,-4.539904997409693194e-02,1.100000000000000006e-01,-7.423704566931350612e-01,9.182144733700695061e-02,-9.871445703403754213e-02,-3.341476160850150867e-01,8.178552662992916167e-03,1.212855429659624590e-01,-4.058523839149847934e-01
+2.963590179903900432e-02,7.098632864869738324e-01,1.254818146287539453e-02,1.487310921673078434e-01,-2.728787781498631659e-02,-4.994660274918061860e-01,1.178014005987558788e-01,-7.809684223232303824e-01,-1.370588412567143588e-01,2.278042664170252807e-01,1.252216408638276608e-02,-1.026656369162168639e-03,5.877852522937826452e-02,-1.100000000000000006e-01,-6.233688103938203051e-01,-5.877852522937826452e-02,1.100000000000000006e-01,-7.366311896061797926e-01,9.803681411936529533e-02,-1.014364010925794674e-01,-3.400409482091070190e-01,1.963185880634585323e-03,1.185635989074205338e-01,-3.999590517908928611e-01
+6.161585822232912985e-02,7.103901144865424344e-01,9.217067175046337463e-03,1.416878746225431474e-01,-4.810022722849891658e-02,-4.917885642702324311e-01,1.146525911131065917e-01,-7.340487569092397635e-01,-1.545832616038356755e-01,1.832300851378286799e-01,1.002054977261161196e-02,-2.367965080459264772e-03,7.071067811877178311e-02,-1.100000000000000006e-01,-6.305025253170236654e-01,-7.071067811877178311e-02,1.100000000000000006e-01,-7.294974746829764323e-01,1.030693551130591190e-01,-1.043692093771777518e-01,-3.466719716166840048e-01,-3.069355113059196727e-03,1.156307906228222493e-01,-3.933280283833158197e-01
+8.723604095457114516e-02,7.018536152210033130e-01,5.483080761043659934e-03,1.314589164206580452e-01,-6.436012173391568447e-02,-4.787833981383333715e-01,1.151334353456015952e-01,-6.803817301679722096e-01,-1.715712081080912332e-01,1.398613826575960395e-01,7.290000459042925672e-03,-3.411449538245717953e-03,8.090169943759334403e-02,-1.100000000000000006e-01,-6.388550323396219310e-01,-8.090169943759334403e-02,1.100000000000000006e-01,-7.211449676603781667e-01,1.067951524567767041e-01,-1.074406664144323675e-01,-3.538774085043452922e-01,-6.795152456776760996e-03,1.125593335855676336e-01,-3.861225914956545879e-01
+1.053548694614566961e-01,6.854951399742015283e-01,1.678016517555433679e-03,1.190053900477629628e-01,-7.516005639106811131e-02,-4.615221586754714722e-01,1.200377521513991824e-01,-6.233272708735861922e-01,-1.880758526938045017e-01,9.974724695678015285e-02,4.369022085653376936e-03,-4.366040839605415426e-03,8.910065241891394761e-02,-1.100000000000000006e-01,-6.482206650183377494e-01,-8.910065241891394761e-02,1.100000000000000006e-01,-7.117793349816623483e-01,1.091224646547037658e-01,-1.105751427385048696e-01,-3.614798371024430801e-01,-9.122464654703801856e-03,1.094248572614951315e-01,-3.785201628975567445e-01
+1.146620808151431886e-01,6.625800878599716892e-01,-1.890103040959343521e-03,1.052190971443591055e-01,-7.943570573497595044e-02,-4.410041489836357687e-01,1.304791654641184184e-01,-5.658964679608956549e-01,-2.043186048998951454e-01,6.461523056235865536e-02,1.287435098104216559e-03,-5.419406970898139539e-03,9.510565162956856333e-02,-1.100000000000000006e-01,-6.583688103938682978e-01,-9.510565162956856333e-02,1.100000000000000006e-01,-7.016311896061317999e-01,1.099939855566209879e-01,-1.136954571395660807e-01,-3.692920603878783181e-01,-9.993985556620989252e-03,1.063045428604339204e-01,-3.707079396121215065e-01
+1.136141537208211622e-01,6.342675291549842997e-01,-4.987495030867966812e-03,9.083235139030769456e-02,-7.590858215720888702e-02,-4.180607698338597578e-01,1.479745070383774730e-01,-5.104581687386778865e-01,-2.207334564719444225e-01,3.567820158563986266e-02,-1.929766589139581814e-03,-6.698175941178465681e-03,9.876883405954106632e-02,-1.100000000000000006e-01,-6.690495874473044724e-01,-9.876883405954106632e-02,1.100000000000000006e-01,-6.909504125526956253e-01,1.093882554255111161e-01,-1.167247771213320434e-01,-3.771217154960808671e-01,-9.388255425511068952e-03,1.032752228786679577e-01,-3.628782845039189575e-01
+1.003892154375394252e-01,6.015091030971205788e-01,-7.536003586203895641e-03,7.639017381980721388e-02,-6.304935679334666698e-02,-3.932898026089350907e-01,1.745055716384070754e-01,-4.585879697255009768e-01,-2.380022910158951233e-01,1.353823766701632916e-02,-5.252174634760870681e-03,-8.248665217454240889e-03,1.000000000000000056e-01,-1.100000000000000006e-01,-6.800000000001237277e-01,-1.000000000000000056e-01,1.100000000000000006e-01,-6.799999999998763700e-01,1.073201893475050905e-01,-1.195885107721150614e-01,-3.847760103331511750e-01,-7.320189347505029476e-03,1.004114892278849397e-01,-3.552239896668486496e-01
+7.293045398917953615e-02,5.650199172970260530e-01,-9.739606996841837852e-03,6.227748628603189951e-02,-3.912876259668818246e-02,-3.670525667960970462e-01,2.124776593396446311e-01,-4.111058022730690875e-01,-2.570391413967694216e-01,-1.772078937444397997e-03,-8.624325639735402199e-03,-1.003981562875267027e-02,9.876883405948558292e-02,-1.100000000000000006e-01,-6.909504125529408736e-01,-9.876883405948558292e-02,1.100000000000000006e-01,-6.690495874470592241e-01,1.038407099729609095e-01,-1.222161434652459661e-01,-3.920664707570530871e-01,-3.840709972960820728e-03,9.778385653475403505e-02,-3.479335292429467374e-01
+2.922878092719160756e-02,5.253190287855676877e-01,-1.225311428521763148e-02,4.877165008287112635e-02,-2.497974192834657992e-03,-3.395273341128012823e-01,2.643954788344908824e-01,-3.682489008903633287e-01,-2.788295816938493044e-01,-1.064761765350605641e-02,-1.193481551191200724e-02,-1.198181587146834350e-02,9.510565162945898432e-02,-1.100000000000000006e-01,-7.016311896063678333e-01,-9.510565162945898432e-02,1.100000000000000006e-01,-6.583688103936322644e-01,9.903549363181048115e-02,-1.245429741632064630e-01,-3.988135814364978105e-01,9.645063681896423602e-04,9.545702583679353814e-02,-3.411864185635020696e-01
+-3.191699582539193891e-02,4.828051591279592381e-01,-1.631742097934130165e-02,3.609134982008257997e-02,4.768801171505562125e-02,-3.107876914950508662e-01,3.319682847520915026e-01,-3.298837045294970571e-01,-3.039753575650663286e-01,-1.374068819078984142e-02,-1.498012027516700158e-02,-1.395079121641943504e-02,8.910065241875293751e-02,-1.100000000000000006e-01,-7.117793349818835047e-01,-8.910065241875293751e-02,1.100000000000000006e-01,-6.482206650181165930e-01,9.302286069797141566e-02,-1.265117085719046075e-01,-4.048512061141814056e-01,6.977139302028728673e-03,9.348829142809537973e-02,-3.351487938858184190e-01
+-1.095522403420352009e-01,4.378336598930492873e-01,-2.363195766979545032e-02,2.442778464467498106e-02,1.102372783062975509e-01,-2.808774127903905793e-01,4.144794111107299450e-01,-2.956860640212455871e-01,-3.318676187599482463e-01,-1.181813277402219385e-02,-1.744878856005873530e-02,-1.581207081672621889e-02,8.090169943738488578e-02,-1.100000000000000006e-01,-7.211449676605790060e-01,-8.090169943738488578e-02,1.100000000000000006e-01,-6.388550323394210917e-01,8.595086214905954536e-02,-1.280738699163433969e-01,-4.100306784328119347e-01,1.404913785094062673e-02,9.192613008365659033e-02,-3.299693215671879454e-01
+-1.980260120096468679e-01,3.907770986525259671e-01,-3.546144753794779753e-02,1.395745259025472917e-02,1.798060562175791133e-01,-2.498681818956396405e-01,5.040411986093201735e-01,-2.652653009983737542e-01,-3.478089728116261492e-01,-5.665123502516476554e-03,-1.886183327923786346e-02,-1.743836329119898346e-02,7.071067811852102536e-02,-1.100000000000000006e-01,-7.294974746831519585e-01,-7.071067811852102536e-02,1.100000000000000006e-01,-6.305025253168481392e-01,7.799363405996666276e-02,-1.291909925997064557e-01,-4.142244625942214098e-01,2.200636594003352320e-02,9.080900740029354545e-02,-3.257755374057784703e-01
+-2.895443046015960253e-01,3.420655581761045672e-01,-5.160187264045969918e-02,4.841596824514878342e-03,2.492728734061986084e-01,-2.178979182512717494e-01,5.905773675898259301e-01,-2.382376078102488304e-01,-3.489874358007266086e-01,3.968751817940548154e-03,-1.860051970968030349e-02,-1.872202140059725517e-02,5.877852522909252087e-02,-1.100000000000000006e-01,-7.366311896063251208e-01,-5.877852522909252087e-02,1.100000000000000006e-01,-6.233688103936749769e-01,6.934710979477226589e-02,-1.298355693540117206e-01,-4.173292937139844172e-01,3.065289020522793742e-02,9.016443064598826662e-02,-3.226707062860155739e-01
+-3.793666227260595880e-01,2.922088815123638494e-01,-7.120691346021904011e-02,-2.782043068204532836e-03,3.145830796555361131e-01,-1.851921758801814422e-01,6.714023036877364570e-01,-2.142641032476683693e-01,-3.490610897375454047e-01,1.639386155534321154e-02,-1.703940665427922108e-02,-1.958198324589173478e-02,4.539904997378094165e-02,-1.100000000000000006e-01,-7.423704566932477489e-01,-4.539904997378094165e-02,1.100000000000000006e-01,-6.176295433067523488e-01,6.022419547705346737e-02,-1.299917285603406358e-01,-4.192687205455886135e-01,3.977580452294673941e-02,9.000827143965936528e-02,-3.207312794544113776e-01
+-4.622966703101597519e-01,2.418044428691528691e-01,-9.227356492652571962e-02,-8.810760645556010504e-03,3.717175438102217622e-01,-1.520718893933329929e-01,7.407176961228274514e-01,-1.930679167298979815e-01,-3.490656931085965864e-01,3.098756273275104361e-02,-1.457753668244499839e-02,-1.996643096950866808e-02,3.090169943730719168e-02,-1.100000000000000006e-01,-7.465739561407034319e-01,-3.090169943730719168e-02,1.100000000000000006e-01,-6.134260438592966658e-01,5.084952753453098051e-02,-1.296556250607706073e-01,-4.199949879638509853e-01,4.915047246546923321e-02,9.034437493922937989e-02,-3.200050120361490058e-01
+-5.348385334542057334e-01,1.915338529935387835e-01,-1.124415214078698100e-01,-1.318858593756440899e-02,4.184620240916612777e-01,-1.189504629199496788e-01,7.942577162630344301e-01,-1.744406738133549017e-01,-3.490659808192872471e-01,4.719277263876651279e-02,-1.166413896008327081e-02,-1.985221780112393641e-02,1.564344650382611460e-02,-1.100000000000000006e-01,-7.491381838416815153e-01,-1.564344650382611460e-02,1.100000000000000006e-01,-6.108618161583185824e-01,4.145394140468808969e-02,-1.288355348389246813e-01,-4.194902128545908160e-01,5.854605859531212403e-02,9.116446516107530595e-02,-3.205097871454092306e-01
+-5.953693400287574100e-01,1.421519329435798062e-01,-1.297194457237912657e-01,-1.591602986312870213e-02,4.543397535392953435e-01,-8.632316183544447297e-02,8.301158477198418151e-01,-1.582451059996913545e-01,-3.490659988012054238e-01,6.451373185750150507e-02,-8.703821904329597792e-03,-1.924197278444206641e-02,-2.016472412380344385e-13,-1.100000000000000006e-01,-7.500000000000000000e-01,2.016472412380344385e-13,1.100000000000000006e-01,-6.100000000000000977e-01,3.226878760020420595e-02,-1.275516512377881106e-01,-4.177668244562505739e-01,6.773121239979600083e-02,9.244834876221187658e-02,-3.222331755437495282e-01
+-6.433256773738108558e-01,9.447163462248246713e-02,-1.426945809659802555e-01,-1.705646484154500070e-02,4.797609735119629515e-01,-5.475217720611207789e-02,8.476869101483670566e-01,-1.444180509878271457e-01,-3.459210837705398722e-01,8.251230611416232597e-02,-5.985677071207787074e-03,-1.815963020594308502e-02,-1.564344650422444527e-02,-1.100000000000000006e-01,-7.491381838416373284e-01,1.564344650422444527e-02,1.100000000000000006e-01,-6.108618161583627693e-01,2.352023509152356348e-02,-1.258355877325862682e-01,-4.148672583107955725e-01,7.647976490847663289e-02,9.416441226741371906e-02,-3.251327416892045297e-01
+-6.773332858457790095e-01,4.934908311097002676e-02,-1.498575406397387455e-01,-1.673834903914030170e-02,4.945905135246292383e-01,-2.485129274875615829e-02,8.412338040718528864e-01,-1.329767390241544112e-01,-3.118859117677069692e-01,1.008067836226137493e-01,-3.185372749466354111e-03,-1.664499566591767094e-02,-3.090169943769074598e-02,-1.100000000000000006e-01,-7.465739561406161684e-01,3.090169943769074598e-02,1.100000000000000006e-01,-6.134260438593839293e-01,1.542370227619107442e-02,-1.237295995021054779e-01,-4.108629113598352700e-01,8.457629772380909072e-02,9.627040049789452325e-02,-3.291370886401648321e-01
+-6.991592328521621935e-01,7.673188384539883500e-03,-1.516888329904766131e-01,-1.515302578482726620e-02,5.007475828907057558e-01,2.725583435504821614e-03,8.177541401315890912e-01,-1.240306783857050149e-01,-2.714130818275732326e-01,1.190744289968586056e-01,-7.917428048463767297e-04,-1.474786567656449429e-02,-4.539904997414154902e-02,-1.100000000000000006e-01,-7.423704566931191851e-01,4.539904997414154902e-02,1.100000000000000006e-01,-6.176295433068809126e-01,8.178552662971516618e-03,-1.212855429659541878e-01,-4.058523839149674739e-01,9.182144733702862771e-02,9.871445703404581329e-02,-3.341476160850326282e-01
+-7.098632864869917070e-01,-2.963590179914941253e-02,-1.487310921672916897e-01,-1.254818146286576334e-02,4.994660274917916420e-01,2.728787781505870313e-02,7.809684223230959343e-01,-1.178014005987416957e-01,-2.278042664168854481e-01,1.370588412567729786e-01,1.026656369166968619e-03,-1.252216408637505524e-02,-5.877852522941878766e-02,-1.100000000000000006e-01,-7.366311896061591424e-01,5.877852522941878766e-02,1.100000000000000006e-01,-6.233688103938409553e-01,1.963185880616703793e-03,-1.185635989074114854e-01,-3.999590517908729326e-01,9.803681411938341972e-02,1.014364010925885157e-01,-3.400409482091272251e-01
+-7.103901144865292228e-01,-6.161585822241843341e-02,-1.416878746225158081e-01,-9.217067175035205742e-03,4.917885642701997906e-01,4.810022722855644001e-02,7.340487569090817788e-01,-1.146525911131027753e-01,-1.832300851376907069e-01,1.545832616038897434e-01,2.367965080462886875e-03,-1.002054977260343101e-02,-7.071067811880620002e-02,-1.100000000000000006e-01,-7.294974746829523404e-01,7.071067811880620002e-02,1.100000000000000006e-01,-6.305025253170477573e-01,-3.069355113072727570e-03,-1.156307906228129095e-01,-3.933280283832944479e-01,1.030693551130728303e-01,1.043692093771870916e-01,-3.466719716167056542e-01
+-7.018536152209640111e-01,-8.723604095463906305e-02,-1.314589164206223237e-01,-5.483080761031867284e-03,4.787833981382860205e-01,6.436012173395803948e-02,6.803817301677990148e-01,-1.151334353456099358e-01,-1.398613826574656716e-01,1.715712081081438023e-01,3.411449538248714688e-03,-7.290000459033519134e-03,-8.090169943762193228e-02,-1.100000000000000006e-01,-7.211449676603506331e-01,8.090169943762193228e-02,1.100000000000000006e-01,-6.388550323396494646e-01,-6.795152456786100748e-03,-1.125593335855579746e-01,-3.861225914956317173e-01,1.067951524567861687e-01,1.074406664144420265e-01,-3.538774085043684403e-01
+-6.854951399741393558e-01,-1.053548694614996895e-01,-1.190053900477216070e-01,-1.678016517543829463e-03,4.615221586754121308e-01,7.516005639109189784e-02,6.233272708734062251e-01,-1.200377521514224832e-01,-9.974724695666160879e-02,1.880758526938554331e-01,4.366040839608540530e-03,-4.369022085643909682e-03,-8.910065241893604104e-02,-1.100000000000000006e-01,-7.117793349816319282e-01,8.910065241893604104e-02,1.100000000000000006e-01,-6.482206650183681695e-01,-9.122464654708742349e-03,-1.094248572614854031e-01,-3.785201628975329302e-01,1.091224646547087895e-01,1.105751427385145980e-01,-3.614798371024672274e-01
+-6.625800878598916421e-01,-1.146620808151567611e-01,-1.052190971443151130e-01,1.890103040969741671e-03,4.410041489835679340e-01,7.943570573497778231e-02,5.658964679607194626e-01,-1.304791654641608845e-01,-6.461523056225895734e-02,2.043186048999454940e-01,5.419406970901713937e-03,-1.287435098094460691e-03,-9.510565162958360685e-02,-1.100000000000000006e-01,-7.016311896060993814e-01,9.510565162958360685e-02,1.100000000000000006e-01,-6.583688103939007163e-01,-9.993985556621405586e-03,-1.063045428604243586e-01,-3.707079396120973591e-01,1.099939855566214042e-01,1.136954571395756425e-01,-3.692920603879028540e-01
+-6.342675291548862671e-01,-1.136141537207998042e-01,-9.083235139026142602e-02,4.987495030876988242e-03,4.180607698337833744e-01,7.590858215718390700e-02,5.104581687385059130e-01,-1.479745070384459460e-01,-3.567820158555829596e-02,2.207334564719974079e-01,6.698175941182946472e-03,1.929766589149982565e-03,-9.876883405954889339e-02,-1.100000000000000006e-01,-6.909504125526609863e-01,9.876883405954889339e-02,1.100000000000000006e-01,-6.690495874473391114e-01,-9.388255425506822349e-03,-1.032752228786585208e-01,-3.628782845038943661e-01,1.093882554255068001e-01,1.167247771213414803e-01,-3.771217154961058471e-01
+-6.015091030970094454e-01,-1.003892154374765172e-01,-7.639017381976134780e-02,7.536003586211215306e-03,3.932898026088533783e-01,6.304935679328964315e-02,4.585879697253419374e-01,-1.745055716385074118e-01,-1.353823766695656100e-02,2.380022910159517724e-01,8.248665217459648022e-03,5.252174634771445555e-03,-1.000000000000000056e-01,-1.100000000000000006e-01,-6.799999999998413980e-01,1.000000000000000056e-01,1.100000000000000006e-01,-6.800000000001586997e-01,-7.320189347496210142e-03,-1.004114892278761551e-01,-3.552239896668248909e-01,1.073201893474961532e-01,1.195885107721238461e-01,-3.847760103331752668e-01
+-5.650199172969074812e-01,-7.293045398907048449e-02,-6.227748628598889918e-02,9.739606996848599804e-03,3.670525667960134464e-01,3.912876259659541639e-02,4.111058022729288663e-01,-2.124776593397824931e-01,1.772078937481659858e-03,2.570391413968322603e-01,1.003981562875849200e-02,8.624325639745826153e-03,-9.876883405947796402e-02,-1.100000000000000006e-01,-6.690495874470255844e-01,9.876883405947796402e-02,1.100000000000000006e-01,-6.909504125529745133e-01,-3.840709972948025408e-03,-9.778385653474633288e-02,-3.479335292429250881e-01,1.038407099729479477e-01,1.222161434652536682e-01,-3.920664707570750696e-01
+-5.253190287854393459e-01,-2.922878092703014297e-02,-4.877165008283032566e-02,1.225311428522707184e-02,3.395273341127134636e-01,2.497974192700451110e-03,3.682489008902365413e-01,-2.643954788346746798e-01,1.064761765352469081e-02,2.788295816939181937e-01,1.198181587147435605e-02,1.193481551192114923e-02,-9.510565162944394080e-02,-1.100000000000000006e-01,-6.583688103935998459e-01,9.510565162944394080e-02,1.100000000000000006e-01,-7.016311896064002518e-01,9.645063682063512167e-04,-9.545702583678686293e-02,-3.411864185634823077e-01,9.903549363179353637e-02,1.245429741632131382e-01,-3.988135814365177945e-01
+-4.828051591278234023e-01,3.191699582560891812e-02,-3.609134982004478381e-02,1.631742097935811459e-02,3.107876914949601610e-01,-4.768801171523232019e-02,3.298837045293848691e-01,-3.319682847523268698e-01,1.374068819079153625e-02,3.039753575651495954e-01,1.395079121642537126e-02,1.498012027517585734e-02,-8.910065241873085795e-02,-1.100000000000000006e-01,-6.482206650180861729e-01,8.910065241873085795e-02,1.100000000000000006e-01,-7.117793349819139248e-01,6.977139302048934733e-03,-9.348829142808988413e-02,-3.351487938858010995e-01,9.302286069795093204e-02,1.265117085719101031e-01,-4.048512061141990026e-01
+-4.378336598929064016e-01,1.095522403422985319e-01,-2.442778464464067170e-02,2.363195766982495449e-02,2.808774127902961548e-01,-1.102372783065075912e-01,2.956860640211458335e-01,-4.144794111110063906e-01,1.181813277401014099e-02,3.318676187600361205e-01,1.581207081673147857e-02,1.744878856006518153e-02,-8.090169943735628366e-02,-1.100000000000000006e-01,-6.388550323393935582e-01,8.090169943735628366e-02,1.100000000000000006e-01,-7.211449676606065395e-01,1.404913785096383733e-02,-9.192613008365242699e-02,-3.299693215671735125e-01,8.595086214903599475e-02,1.280738699163475602e-01,-4.100306784328265897e-01
+-3.907770986523715351e-01,1.980260120099315846e-01,-1.395745259022315027e-02,3.546144753799176930e-02,2.498681818955384992e-01,-1.798060562177992150e-01,2.652653009982805510e-01,-5.040411986095948427e-01,5.665123502490514683e-03,3.478089728116372514e-01,1.743836329120387538e-02,1.886183327923959818e-02,-7.071067811848560924e-02,-1.100000000000000006e-01,-6.305025253168232702e-01,7.071067811848560924e-02,1.100000000000000006e-01,-7.294974746831768275e-01,2.200636594005991875e-02,-9.080900740029072826e-02,-3.257755374057668685e-01,7.799363405993990639e-02,1.291909925997092590e-01,-4.142244625942331782e-01
+-3.420655581759452502e-01,2.895443046018842392e-01,-4.841596824487731654e-03,5.160187264051659811e-02,2.178979182511671941e-01,-2.492728734064131590e-01,2.382376078101655359e-01,-5.905773675900902742e-01,-3.968751817976941786e-03,3.489874358007273303e-01,1.872202140060098136e-02,1.860051970967729548e-02,-5.877852522905199772e-02,-1.100000000000000006e-01,-6.233688103936544378e-01,5.877852522905199772e-02,1.100000000000000006e-01,-7.366311896063456599e-01,3.065289020525618566e-02,-9.016443064598698987e-02,-3.226707062860075248e-01,6.934710979474362214e-02,1.298355693540129974e-01,-4.173292937139925218e-01
+-2.922088815122071415e-01,3.793666227263294277e-01,2.782043068225844781e-03,7.120691346028339141e-02,1.851921758800784690e-01,-3.145830796557277376e-01,2.142641032475971763e-01,-6.714023036879720463e-01,-1.639386155538435919e-02,3.490610897375454602e-01,1.958198324589357012e-02,1.703940665427287199e-02,-4.539904997373758744e-02,-1.100000000000000006e-01,-6.176295433067369167e-01,4.539904997373758744e-02,1.100000000000000006e-01,-7.423704566932631810e-01,3.977580452297530683e-02,-9.000827143965964283e-02,-3.207312794544072698e-01,6.022419547702449749e-02,1.299917285603403583e-01,-4.192687205455927768e-01
+-2.418044428689957448e-01,4.622966703104013919e-01,8.810760645572212821e-03,9.227356492659062603e-02,1.520718893932297144e-01,-3.717175438103828555e-01,1.930679167298354759e-01,-7.407176961230190759e-01,-3.098756273279878667e-02,3.490656931085965864e-01,1.996643096950912952e-02,1.457753668243653468e-02,-3.090169943726091273e-02,-1.100000000000000006e-01,-6.134260438592861187e-01,3.090169943726091273e-02,1.100000000000000006e-01,-7.465739561407139790e-01,4.915047246549821697e-02,-9.034437493923118401e-02,-3.200050120361486172e-01,5.084952753450158042e-02,1.296556250607688032e-01,-4.199949879638513739e-01
+-1.915338529933841571e-01,5.348385334544125680e-01,1.318858593757527703e-02,1.124415214079288738e-01,1.189504629198474828e-01,-4.184620240917895639e-01,1.744406738133006118e-01,-7.942577162631744292e-01,-4.719277263881434259e-02,3.490659808192872471e-01,1.985221780112211842e-02,1.166413896007390330e-02,-1.564344650377805582e-02,-1.100000000000000006e-01,-6.108618161583132533e-01,1.564344650377805582e-02,1.100000000000000006e-01,-7.491381838416868444e-01,5.854605859534081636e-02,-9.116446516107858111e-02,-3.205097871454126723e-01,4.145394140465898797e-02,1.288355348389214061e-01,-4.194902128545873188e-01
+-1.421519329434287326e-01,5.953693400289254978e-01,1.591602986313460019e-02,1.297194457238387277e-01,8.632316183534459453e-02,-4.543397535393899900e-01,1.582451059996441700e-01,-8.301158477199251928e-01,-6.451373185755382433e-02,3.490659988012054238e-01,1.924197278443937759e-02,8.703821904320469677e-03,2.503071721696097899e-13,-1.100000000000000006e-01,-6.100000000000000977e-01,-2.503071721696097899e-13,1.100000000000000006e-01,-7.500000000000000000e-01,6.773121239982368702e-02,-9.244834876221653952e-02,-3.222331755437566336e-01,3.226878760017611730e-02,1.275516512377834477e-01,-4.177668244562433020e-01
+-9.447163462233290621e-02,6.433256773739393086e-01,1.705646484154623582e-02,1.426945809660119524e-01,5.475217720601355947e-02,-4.797609735120251795e-01,1.444180509877857621e-01,-8.476869101483817115e-01,-8.251230611422148697e-02,3.459210837704552732e-01,1.815963020593883495e-02,5.985677071200053677e-03,1.564344650427390918e-02,-1.100000000000000006e-01,-6.108618161583682094e-01,-1.564344650427390918e-02,1.100000000000000006e-01,-7.491381838416318883e-01,7.647976490850340314e-02,-9.416441226741983916e-02,-3.251327416892154654e-01,2.352023509149641506e-02,1.258355877325801619e-01,-4.148672583107844147e-01
+-4.934908311083012478e-02,6.773332858458669392e-01,1.673834903913723471e-02,1.498575406397527621e-01,2.485129274866344426e-02,-4.945905135246618234e-01,1.329767390241210490e-01,-8.412338040718023713e-01,-1.008067836226739511e-01,3.118859117675871762e-01,1.664499566591218921e-02,3.185372749458012694e-03,3.090169943773837455e-02,-1.100000000000000006e-01,-6.134260438593946985e-01,-3.090169943773837455e-02,1.100000000000000006e-01,-7.465739561406053992e-01,8.457629772383348787e-02,-9.627040049790179521e-02,-3.291370886401791540e-01,1.542370227616635114e-02,1.237295995020982059e-01,-4.108629113598207261e-01
+-7.673188384416301799e-03,6.991592328522115984e-01,1.515302578482069333e-02,1.516888329904744204e-01,-2.725583435586533161e-03,-5.007475828907124171e-01,1.240306783856807565e-01,-8.177541401314932790e-01,-1.190744289969165454e-01,2.714130818274415047e-01,1.474786567655967696e-02,7.917428048398587230e-04,4.539904997418490323e-02,-1.100000000000000006e-01,-6.176295433068964558e-01,-4.539904997418490323e-02,1.100000000000000006e-01,-7.423704566931036419e-01,9.182144733704941664e-02,-9.871445703405384853e-02,-3.341476160850495036e-01,8.178552662950429319e-03,1.212855429659461526e-01,-4.058523839149503765e-01
+2.963590179925787438e-02,7.098632864870084713e-01,1.254818146285642186e-02,1.487310921672757302e-01,-2.728787781512978516e-02,-4.994660274917772091e-01,1.178014005987262358e-01,-7.809684223229644839e-01,-1.370588412568277958e-01,2.278042664167476139e-01,1.252216408636773991e-02,-1.026656369171811533e-03,5.877852522945814506e-02,-1.100000000000000006e-01,-6.233688103938609393e-01,-5.877852522945814506e-02,1.100000000000000006e-01,-7.366311896061391584e-01,9.803681411940079471e-02,-1.014364010925973142e-01,-3.400409482091465430e-01,1.963185880599085942e-03,1.185635989074026869e-01,-3.999590517908532816e-01
+6.161585822250859740e-02,7.103901144865159001e-01,9.217067175024056674e-03,1.416878746224883856e-01,-4.810022722861385935e-02,-4.917885642701669280e-01,1.146525911130976405e-01,-7.340487569089234610e-01,-1.545832616039412855e-01,1.832300851375517625e-01,1.002054977259686334e-02,-2.367965080466587907e-03,7.071067811884060306e-02,-1.100000000000000006e-01,-6.305025253170718491e-01,-7.071067811884060306e-02,1.100000000000000006e-01,-7.294974746829282486e-01,1.030693551130863472e-01,-1.043692093771964313e-01,-3.466719716167270260e-01,-3.069355113086445763e-03,1.156307906228035698e-01,-3.933280283832727986e-01
+8.723604095470795239e-02,7.018536152209243761e-01,5.483080761019987898e-03,1.314589164205864635e-01,-6.436012173400057490e-02,-4.787833981382378923e-01,1.151334353456169163e-01,-6.803817301676251539e-01,-1.715712081081939289e-01,1.398613826573299745e-01,7.290000459025512518e-03,-3.411449538251574813e-03,8.090169943765053440e-02,-1.100000000000000006e-01,-6.388550323396769981e-01,-8.090169943765053440e-02,1.100000000000000006e-01,-7.211449676603230996e-01,1.067951524567955224e-01,-1.074406664144516715e-01,-3.538774085043913109e-01,-6.795152456795586215e-03,1.125593335855483296e-01,-3.861225914956085137e-01
+1.053548694615431686e-01,6.854951399740780715e-01,1.678016517532245847e-03,1.190053900476809728e-01,-7.516005639111604519e-02,-4.615221586753541216e-01,1.200377521514452706e-01,-6.233272708732280343e-01,-1.880758526939052822e-01,9.974724695654285656e-02,4.369022085634726056e-03,-4.366040839611357721e-03,8.910065241895813448e-02,-1.100000000000000006e-01,-6.482206650183984786e-01,-8.910065241895813448e-02,1.100000000000000006e-01,-7.117793349816016191e-01,1.091224646547137300e-01,-1.105751427385243263e-01,-3.614798371024910417e-01,-9.122464654713752230e-03,1.094248572614756748e-01,-3.785201628975087829e-01
+1.146620808151709164e-01,6.625800878598100407e-01,-1.890103040980480910e-03,1.052190971442700518e-01,-7.943570573497979459e-02,-4.410041489834987671e-01,1.304791654642045440e-01,-5.658964679605397174e-01,-2.043186048999974247e-01,6.461523056215720540e-02,1.287435098084398211e-03,-5.419406970905354254e-03,9.510565162959908059e-02,-1.100000000000000006e-01,-6.583688103939340230e-01,-9.510565162959908059e-02,1.100000000000000006e-01,-7.016311896060660747e-01,1.099939855566218344e-01,-1.136954571395854818e-01,-3.692920603879277230e-01,-9.993985556621828859e-03,1.063045428604145193e-01,-3.707079396120721015e-01
+1.136141537207785018e-01,6.342675291547915650e-01,-4.987495030885719105e-03,9.083235139021657301e-02,-7.590858215715923230e-02,-4.180607698337094336e-01,1.479745070385133088e-01,-5.104581687383398236e-01,-2.207334564720492831e-01,3.567820158547921339e-02,-1.929766589160141323e-03,-6.698175941187384762e-03,9.876883405955649842e-02,-1.100000000000000006e-01,-6.690495874473727511e-01,-9.876883405955649842e-02,1.100000000000000006e-01,-6.909504125526273466e-01,1.093882554255026784e-01,-1.167247771213506397e-01,-3.771217154961297169e-01,-9.388255425502638196e-03,1.032752228786493615e-01,-3.628782845038701077e-01
+1.003892154374143308e-01,6.015091030969023089e-01,-7.536003586218337214e-03,7.639017381971714704e-02,-6.304935679323339648e-02,-3.932898026087744414e-01,1.745055716386064160e-01,-4.585879697251883380e-01,-2.380022910160076999e-01,1.353823766689886236e-02,-5.252174634781831344e-03,-8.248665217464763721e-03,1.000000000000000056e-01,-1.100000000000000006e-01,-6.800000000001927836e-01,-1.000000000000000056e-01,1.100000000000000006e-01,-6.799999999998073141e-01,1.073201893474875906e-01,-1.195885107721323948e-01,-3.847760103331983594e-01,-7.320189347487529585e-03,1.004114892278676063e-01,-3.552239896668014651e-01
+7.293045398895979525e-02,5.650199172967899086e-01,-9.739606996855436349e-03,6.227748628594625968e-02,-3.912876259650145683e-02,-3.670525667959305682e-01,2.124776593399223534e-01,-4.111058022727896999e-01,-2.570391413968954319e-01,-1.772078937518501481e-03,-8.624325639756140818e-03,-1.003981562876424434e-02,9.876883405947035899e-02,-1.100000000000000006e-01,-6.909504125530081531e-01,-9.876883405947035899e-02,1.100000000000000006e-01,-6.690495874469919446e-01,1.038407099729351524e-01,-1.222161434652613843e-01,-3.920664707570967744e-01,-3.840709972935049676e-03,9.778385653473861683e-02,-3.479335292429030502e-01
+2.922878092686601037e-02,5.253190287853127804e-01,-1.225311428523646710e-02,4.877165008278992742e-02,-2.497974192564823490e-03,-3.395273341126269773e-01,2.643954788348619189e-01,-3.682489008901125849e-01,-2.788295816939928007e-01,-1.064761765354202416e-02,-1.193481551193146736e-02,-1.198181587148043972e-02,9.510565162942891115e-02,-1.100000000000000006e-01,-7.016311896064326703e-01,-9.510565162942891115e-02,1.100000000000000006e-01,-6.583688103935674274e-01,9.903549363177682752e-02,-1.245429741632198134e-01,-3.988135814365375564e-01,9.645063682232890567e-04,9.545702583678018771e-02,-3.411864185634623237e-01
+-3.191699582582625816e-02,4.828051591276886212e-01,-1.631742097937482344e-02,3.609134982000716113e-02,4.768801171540924810e-02,-3.107876914948697333e-01,3.319682847525618485e-01,-3.298837045292736803e-01,-3.039753575652328621e-01,-1.374068819079263433e-02,-1.498012027518454657e-02,-1.395079121643137687e-02,8.910065241870876451e-02,-1.100000000000000006e-01,-7.117793349819442339e-01,-8.910065241870876451e-02,1.100000000000000006e-01,-6.482206650180558638e-01,9.302286069793072598e-02,-1.265117085719155987e-01,-4.048512061142163221e-01,6.977139302069425286e-03,9.348829142808438852e-02,-3.351487938857835580e-01
+-1.095522403425676083e-01,4.378336598927596302e-01,-2.363195766985516297e-02,2.442778464460524518e-02,1.102372783067222112e-01,-2.808774127901988438e-01,4.144794111112876100e-01,-2.956860640210429159e-01,-3.318676187601278804e-01,-1.181813277399648178e-02,-1.744878856007173185e-02,-1.581207081673721357e-02,8.090169943732684887e-02,-1.100000000000000006e-01,-7.211449676606349612e-01,-8.090169943732684887e-02,1.100000000000000006e-01,-6.388550323393651365e-01,8.595086214901209720e-02,-1.280738699163518624e-01,-4.100306784328414667e-01,1.404913785098806100e-02,9.192613008364812488e-02,-3.299693215671584134e-01
+-1.980260120102152466e-01,3.907770986522234868e-01,-3.546144753803571331e-02,1.395745259019277179e-02,1.798060562180186506e-01,-2.498681818954407441e-01,5.040411986098709551e-01,-2.652653009981923438e-01,-3.478089728116484092e-01,-5.665123502465633544e-03,-1.886183327924126699e-02,-1.743836329120834056e-02,7.071067811845120621e-02,-1.100000000000000006e-01,-7.294974746832009194e-01,-7.071067811845120621e-02,1.100000000000000006e-01,-6.305025253167991783e-01,7.799363405991426024e-02,-1.291909925997120068e-01,-4.142244625942444469e-01,2.200636594008592573e-02,9.080900740028798046e-02,-3.257755374057554332e-01
+-2.895443046021695110e-01,3.420655581757932051e-01,-5.160187264057301826e-02,4.841596824461877335e-03,2.492728734066252949e-01,-2.178979182510672463e-01,5.905773675903543962e-01,-2.382376078100877370e-01,-3.489874358007279964e-01,3.968751818011879984e-03,-1.860051970967427012e-02,-1.872202140060429468e-02,5.877852522901262644e-02,-1.100000000000000006e-01,-7.366311896063657549e-01,-5.877852522901262644e-02,1.100000000000000006e-01,-6.233688103936343428e-01,6.934710979471618575e-02,-1.298355693540142464e-01,-4.173292937140002934e-01,3.065289020528401756e-02,9.016443064598574086e-02,-3.226707062859996422e-01
+-3.793666227266023205e-01,2.922088815120531535e-01,-7.120691346034839497e-02,-2.782043068246722612e-03,3.145830796559209719e-01,-1.851921758799775219e-01,6.714023036882118545e-01,-2.142641032475293417e-01,-3.490610897375455157e-01,1.639386155542584683e-02,-1.703940665426615514e-02,-1.958198324589535688e-02,4.539904997369423323e-02,-1.100000000000000006e-01,-7.423704566932787241e-01,-4.539904997369423323e-02,1.100000000000000006e-01,-6.176295433067213736e-01,6.022419547699593007e-02,-1.299917285603400530e-01,-4.192687205455968846e-01,3.977580452300427671e-02,9.000827143965993427e-02,-3.207312794544030510e-01
+-4.622966703106459740e-01,2.418044428688412850e-01,-9.227356492665654553e-02,-8.810760645588151460e-03,3.717175438105463914e-01,-1.520718893931279070e-01,7.407176961232145862e-01,-1.930679167297759125e-01,-3.490656931085965864e-01,3.098756273284532237e-02,-1.457753668242781769e-02,-1.996643096950933768e-02,3.090169943721463031e-02,-1.100000000000000006e-01,-7.465739561407245262e-01,-3.090169943721463031e-02,1.100000000000000006e-01,-6.134260438592755715e-01,5.084952753447258972e-02,-1.296556250607669991e-01,-4.199949879638517070e-01,4.915047246552761706e-02,9.034437493923298812e-02,-3.200050120361482842e-01
+-5.348385334546199577e-01,1.915338529932302802e-01,-1.124415214079880071e-01,-1.318858593758626997e-02,4.184620240919179612e-01,-1.189504629197461472e-01,7.942577162633140953e-01,-1.744406738132479040e-01,-3.490659808192872471e-01,4.719277263886891699e-02,-1.166413896006456008e-02,-1.985221780112163270e-02,1.564344650372999357e-02,-1.100000000000000006e-01,-7.491381838416921735e-01,-1.564344650372999357e-02,1.100000000000000006e-01,-6.108618161583079242e-01,4.145394140463028870e-02,-1.288355348389181310e-01,-4.194902128545838771e-01,5.854605859536991808e-02,9.116446516108185627e-02,-3.205097871454161140e-01
+-5.953693400290988036e-01,1.421519329432738010e-01,-1.297194457238876053e-01,-1.591602986314073764e-02,4.543397535394875786e-01,-8.632316183524207931e-02,8.301158477200109020e-01,-1.582451059995970133e-01,-3.490659988012054238e-01,6.451373185761291595e-02,-8.703821904311495952e-03,-1.924197278443665754e-02,-3.003881885727054375e-13,-1.100000000000000006e-01,-7.500000000000000000e-01,3.003881885727054375e-13,1.100000000000000006e-01,-6.100000000000000977e-01,3.226878760014760539e-02,-1.275516512377786460e-01,-4.177668244562359745e-01,6.773121239985259445e-02,9.244834876222134123e-02,-3.222331755437640721e-01
+-6.433256773740659851e-01,9.447163462218936825e-02,-1.426945809660433717e-01,-1.705646484154735645e-02,4.797609735120868524e-01,-5.475217720591842030e-02,8.476869101483986979e-01,-1.444180509877474872e-01,-3.459210837703716179e-01,8.251230611427860795e-02,-5.985677071192382730e-03,-1.815963020593472366e-02,-1.564344650432197142e-02,-1.100000000000000006e-01,-7.491381838416265593e-01,1.564344650432197142e-02,1.100000000000000006e-01,-6.108618161583735384e-01,2.352023509147040115e-02,-1.258355877325741945e-01,-4.148672583107737566e-01,7.647976490852978482e-02,9.416441226742579274e-02,-3.251327416892262900e-01
+-6.773332858459530925e-01,4.934908311069610004e-02,-1.498575406397664733e-01,-1.673834903913410527e-02,4.945905135246936868e-01,-2.485129274857444948e-02,8.412338040717536325e-01,-1.329767390240904346e-01,-3.118859117674693260e-01,1.008067836227296843e-01,-3.185372749449662602e-03,-1.664499566590585053e-02,-3.090169943778465350e-02,-1.100000000000000006e-01,-7.465739561405948521e-01,3.090169943778465350e-02,1.100000000000000006e-01,-6.134260438594052456e-01,1.542370227614265482e-02,-1.237295995020911282e-01,-4.108629113598067928e-01,8.457629772385752420e-02,9.627040049790887288e-02,-3.291370886401933094e-01
+-6.991592328522616695e-01,7.673188384294458292e-03,-1.516888329904725052e-01,-1.515302578481410138e-02,5.007475828907195226e-01,2.725583435666977493e-03,8.177541401313983549e-01,-1.240306783856578998e-01,-2.714130818273081114e-01,1.190744289969712794e-01,-7.917428048332017217e-04,-1.474786567655345451e-02,-4.539904997422826438e-02,-1.100000000000000006e-01,-7.423704566930882098e-01,4.539904997422826438e-02,1.100000000000000006e-01,-6.176295433069118879e-01,8.178552662929647332e-03,-1.212855429659381173e-01,-4.058523839149335566e-01,9.182144733707051087e-02,9.871445703406188377e-02,-3.341476160850666011e-01
+-7.098632864870253467e-01,-2.963590179936508376e-02,-1.487310921672597985e-01,-1.254818146284705262e-02,4.994660274917627762e-01,2.728787781520003106e-02,7.809684223228330335e-01,-1.178014005987118307e-01,-2.278042664166083087e-01,1.370588412568813641e-01,1.026656369176730992e-03,-1.252216408636049744e-02,-5.877852522949751635e-02,-1.100000000000000006e-01,-7.366311896061191744e-01,5.877852522949751635e-02,1.100000000000000006e-01,-6.233688103938809233e-01,1.963185880581710951e-03,-1.185635989073938884e-01,-3.999590517908339637e-01,9.803681411941841950e-02,1.014364010926061127e-01,-3.400409482091661939e-01
+-7.103901144865029105e-01,-6.161585822259789402e-02,-1.416878746224611851e-01,-9.217067175012954444e-03,4.917885642701342874e-01,4.810022722867141748e-02,7.340487569087658093e-01,-1.146525911130935466e-01,-1.832300851374148165e-01,1.545832616039947705e-01,2.367965080470111131e-03,-1.002054977258872749e-02,-7.071067811887500609e-02,-1.100000000000000006e-01,-7.294974746829041568e-01,7.071067811887500609e-02,1.100000000000000006e-01,-6.305025253170959409e-01,-3.069355113099962729e-03,-1.156307906227942439e-01,-3.933280283832514268e-01,1.030693551131000724e-01,1.043692093772057572e-01,-3.466719716167487308e-01
+-7.018536152208842971e-01,-8.723604095477786868e-02,-1.314589164205499927e-01,-5.483080761007862181e-03,4.787833981381894310e-01,6.436012173404391523e-02,6.803817301674476292e-01,-1.151334353456258813e-01,-1.398613826572003560e-01,1.715712081082484963e-01,3.411449538254676065e-03,-7.290000459016463333e-03,-8.090169943767998306e-02,-1.100000000000000006e-01,-7.211449676602946779e-01,8.090169943767998306e-02,1.100000000000000006e-01,-6.388550323397054198e-01,-6.795152456805210461e-03,-1.125593335855383931e-01,-3.861225914955849770e-01,1.067951524568052785e-01,1.074406664144616080e-01,-3.538774085044151807e-01
+-6.854951399740150109e-01,-1.053548694615873277e-01,-1.190053900476385484e-01,-1.678016517520374701e-03,4.615221586752930594e-01,7.516005639114047010e-02,6.233272708730444034e-01,-1.200377521514694734e-01,-9.974724695642209205e-02,1.880758526939577124e-01,4.366040839614239964e-03,-4.369022085625124362e-03,-8.910065241898086630e-02,-1.100000000000000006e-01,-7.117793349815704218e-01,8.910065241898086630e-02,1.100000000000000006e-01,-6.482206650184296759e-01,-9.122464654718838439e-03,-1.094248572614656551e-01,-3.785201628974842469e-01,1.091224646547188787e-01,1.105751427385343461e-01,-3.614798371025159107e-01
+-6.625800878597297716e-01,-1.146620808151845028e-01,-1.052190971442259620e-01,1.890103040990787986e-03,4.410041489834308770e-01,7.943570573498165421e-02,5.658964679603633030e-01,-1.304791654642470378e-01,-6.461523056205731308e-02,2.043186049000481341e-01,5.419406970908953805e-03,-1.287435098074736451e-03,-9.510565162961411023e-02,-1.100000000000000006e-01,-7.016311896060336561e-01,9.510565162961411023e-02,1.100000000000000006e-01,-6.583688103939664416e-01,-9.993985556622245192e-03,-1.063045428604049575e-01,-3.707079396120479542e-01,1.099939855566222507e-01,1.136954571395950436e-01,-3.692920603879522035e-01
+-6.342675291546958638e-01,-1.136141537207573243e-01,-9.083235139017153958e-02,4.987495030894489867e-03,4.180607698336348821e-01,7.590858215713459922e-02,5.104581687381719579e-01,-1.479745070385805328e-01,-3.567820158539956182e-02,2.207334564721012415e-01,6.698175941191795296e-03,1.929766589170388551e-03,-9.876883405956411732e-02,-1.100000000000000006e-01,-6.909504125525937068e-01,9.876883405956411732e-02,1.100000000000000006e-01,-6.690495874474063909e-01,-9.388255425498509554e-03,-1.032752228786402021e-01,-3.628782845038461824e-01,1.093882554254984873e-01,1.167247771213597990e-01,-3.771217154961539753e-01
+-6.015091030967941732e-01,-1.003892154373521584e-01,-7.639017381967266873e-02,7.536003586225534581e-03,3.932898026086950605e-01,6.304935679317706654e-02,4.585879697250334619e-01,-1.745055716387053923e-01,-1.353823766684069362e-02,2.380022910160637661e-01,8.248665217469957484e-03,5.252174634792380198e-03,-1.000000000000000056e-01,-1.100000000000000006e-01,-6.799999999997732303e-01,1.000000000000000056e-01,1.100000000000000006e-01,-6.800000000002268674e-01,-7.320189347478953112e-03,-1.004114892278590715e-01,-3.552239896667783725e-01,1.073201893474788893e-01,1.195885107721409296e-01,-3.847760103332217851e-01
+-5.650199172966707817e-01,-7.293045398885106279e-02,-6.227748628590313446e-02,9.739606996862246874e-03,3.670525667958467464e-01,3.912876259640854504e-02,4.111058022726488681e-01,-2.124776593400599101e-01,1.772078937555986687e-03,2.570391413969585481e-01,1.003981562877011117e-02,8.624325639766819776e-03,-9.876883405946274008e-02,-1.100000000000000006e-01,-6.690495874469583049e-01,9.876883405946274008e-02,1.100000000000000006e-01,-6.909504125530417928e-01,-3.840709972922261295e-03,-9.778385653473091466e-02,-3.479335292428814008e-01,1.038407099729221628e-01,1.222161434652690865e-01,-3.920664707571187568e-01
+-5.253190287851806639e-01,-2.922878092670124633e-02,-4.877165008274784996e-02,1.225311428524611911e-02,3.395273341125366606e-01,2.497974192428011053e-03,3.682489008899818561e-01,-2.643954788350490470e-01,1.064761765356117551e-02,2.788295816940670191e-01,1.198181587148678361e-02,1.193481551194180978e-02,-9.510565162941342354e-02,-1.100000000000000006e-01,-6.583688103935341207e-01,9.510565162941342354e-02,1.100000000000000006e-01,-7.016311896064659770e-01,9.645063682404905747e-04,-9.545702583677330433e-02,-3.411864185634419511e-01,9.903549363175939702e-02,1.245429741632266968e-01,-3.988135814365581511e-01
+-4.828051591275475674e-01,3.191699582604599905e-02,-3.609134981996788699e-02,1.631742097939188271e-02,3.107876914947753089e-01,-4.768801171558798013e-02,3.298837045291563852e-01,-3.319682847527986591e-01,1.374068819079433436e-02,3.039753575653167394e-01,1.395079121643768433e-02,1.498012027519330693e-02,-8.910065241868603270e-02,-1.100000000000000006e-01,-6.482206650180246665e-01,8.910065241868603270e-02,1.100000000000000006e-01,-7.117793349819754312e-01,6.977139302090228090e-03,-9.348829142807874026e-02,-3.351487938857657389e-01,9.302286069790963174e-02,1.265117085719212608e-01,-4.048512061142344187e-01
+-4.378336598926159118e-01,1.095522403428289271e-01,-2.442778464457073112e-02,2.363195766988452490e-02,2.808774127901039752e-01,-1.102372783069306694e-01,2.956860640209418856e-01,-4.144794111115612245e-01,1.181813277398399351e-02,3.318676187602151439e-01,1.581207081674264672e-02,1.744878856007801848e-02,-8.090169943729824675e-02,-1.100000000000000006e-01,-6.388550323393376029e-01,8.090169943729824675e-02,1.100000000000000006e-01,-7.211449676606624948e-01,1.404913785101127160e-02,-9.192613008364396154e-02,-3.299693215671439250e-01,8.595086214898857435e-02,1.280738699163560257e-01,-4.100306784328561771e-01
+-3.907770986520750500e-01,1.980260120104970212e-01,-1.395745259016247831e-02,3.546144753807946998e-02,2.498681818953435163e-01,-1.798060562182366706e-01,2.652653009981038590e-01,-5.040411986101451802e-01,5.665123502441816658e-03,3.478089728116596224e-01,1.743836329121279186e-02,1.886183327924294967e-02,-7.071067811841678930e-02,-1.100000000000000006e-01,-6.305025253167751975e-01,7.071067811841678930e-02,1.100000000000000006e-01,-7.294974746832249002e-01,2.200636594011156841e-02,-9.080900740028524654e-02,-3.257755374057441644e-01,7.799363405988825326e-02,1.291909925997147546e-01,-4.142244625942558822e-01
+-3.420655581756403829e-01,2.895443046024540057e-01,-4.841596824435974444e-03,5.160187264062952167e-02,2.178979182509672707e-01,-2.492728734068372920e-01,2.382376078100090777e-01,-5.905773675906179632e-01,-3.968751818045315044e-03,3.489874358007287181e-01,1.872202140060749004e-02,1.860051970967127946e-02,-5.877852522897325516e-02,-1.100000000000000006e-01,-6.233688103936143587e-01,5.877852522897325516e-02,1.100000000000000006e-01,-7.366311896063857390e-01,3.065289020531145742e-02,-9.016443064598449186e-02,-3.226707062859918151e-01,6.934710979468834691e-02,1.298355693540154954e-01,-4.173292937140081760e-01
+-2.922088815118968341e-01,3.793666227268713276e-01,2.782043068268002031e-03,7.120691346041239933e-02,1.851921758798749651e-01,-3.145830796561118747e-01,2.142641032474586482e-01,-6.714023036884457785e-01,-1.639386155546768489e-02,3.490610897375455157e-01,1.958198324589729630e-02,1.703940665425979217e-02,-4.539904997365087902e-02,-1.100000000000000006e-01,-6.176295433067059415e-01,4.539904997365087902e-02,1.100000000000000006e-01,-7.423704566932941562e-01,3.977580452303284414e-02,-9.000827143966021182e-02,-3.207312794543989432e-01,6.022419547696696018e-02,1.299917285603397754e-01,-4.192687205456010480e-01
+-2.418044428686785541e-01,4.622966703108922215e-01,8.810760645604995625e-03,9.227356492672260380e-02,1.520718893930206594e-01,-3.717175438107107599e-01,1.930679167297103538e-01,-7.407176961234075430e-01,-3.098756273289519914e-02,3.490656931085965864e-01,1.996643096950975402e-02,1.457753668241925336e-02,-3.090169943716700174e-02,-1.100000000000000006e-01,-6.134260438592646913e-01,3.090169943716700174e-02,1.100000000000000006e-01,-7.465739561407354064e-01,4.915047246555746124e-02,-9.034437493923483387e-02,-3.200050120361479511e-01,5.084952753444234308e-02,1.296556250607651672e-01,-4.199949879638520400e-01
+-1.915338529930692979e-01,5.348385334548306780e-01,1.318858593759772435e-02,1.124415214080478342e-01,1.189504629196398017e-01,-4.184620240920481349e-01,1.744406738131906720e-01,-7.942577162634544274e-01,-4.719277263892306812e-02,3.490659808192873026e-01,1.985221780112020676e-02,1.166413896005516655e-02,-1.564344650368052966e-02,-1.100000000000000006e-01,-6.108618161583023731e-01,1.564344650368052966e-02,1.100000000000000006e-01,-7.491381838416977246e-01,5.854605859539945695e-02,-9.116446516108521470e-02,-3.205097871454196667e-01,4.145394140460034738e-02,1.288355348389147725e-01,-4.194902128545802689e-01
+-1.421519329431221723e-01,5.953693400292662252e-01,1.591602986314679183e-02,1.297194457239347620e-01,8.632316183514170127e-02,-4.543397535395816700e-01,1.582451059995495513e-01,-8.301158477200928365e-01,-6.451373185766751117e-02,3.490659988012054238e-01,1.924197278443410403e-02,8.703821904302600290e-03,3.490481195042808141e-13,-1.100000000000000006e-01,-6.100000000000000977e-01,-3.490481195042808141e-13,1.100000000000000006e-01,-7.500000000000000000e-01,6.773121239988028064e-02,-9.244834876222601805e-02,-3.222331755437712331e-01,3.226878760011951675e-02,1.275516512377739831e-01,-4.177668244562287025e-01
+-9.447163462204492823e-02,6.433256773741913292e-01,1.705646484154857076e-02,1.426945809660743192e-01,5.475217720582284398e-02,-4.797609735121476926e-01,1.444180509877076579e-01,-8.476869101484136859e-01,-8.251230611433262030e-02,3.459210837702850760e-01,1.815963020593081012e-02,5.985677071184704844e-03,1.564344650437003020e-02,-1.100000000000000006e-01,-6.108618161583788675e-01,-1.564344650437003020e-02,1.100000000000000006e-01,-7.491381838416212302e-01,7.647976490855580567e-02,-9.416441226743173243e-02,-3.251327416892369482e-01,2.352023509144401600e-02,1.258355877325682548e-01,-4.148672583107629319e-01
+-4.934908311056060426e-02,6.773332858460383576e-01,1.673834903913104868e-02,1.498575406397799070e-01,2.485129274848494815e-02,-4.945905135247251061e-01,1.329767390240576275e-01,-8.412338040717040055e-01,-1.008067836227853342e-01,3.118859117673485337e-01,1.664499566590159005e-02,3.185372749441310776e-03,3.090169943783093245e-02,-1.100000000000000006e-01,-6.134260438594157927e-01,-3.090169943783093245e-02,1.100000000000000006e-01,-7.465739561405843050e-01,8.457629772388119971e-02,-9.627040049791595056e-02,-3.291370886402071871e-01,1.542370227611862543e-02,1.237295995020840506e-01,-4.108629113597926930e-01
+-7.673188384170869653e-03,6.991592328523112965e-01,1.515302578480737933e-02,1.516888329904702848e-01,-2.725583435748087091e-03,-5.007475828907264059e-01,1.240306783856332529e-01,-8.177541401313033198e-01,-1.190744289970269570e-01,2.714130818271766055e-01,1.474786567654695277e-02,7.917428048266838235e-04,4.539904997427161859e-02,-1.100000000000000006e-01,-6.176295433069273200e-01,-4.539904997427161859e-02,1.100000000000000006e-01,-7.423704566930727777e-01,9.182144733709129980e-02,-9.871445703406991901e-02,-3.341476160850834209e-01,8.178552662908566973e-03,1.212855429659300821e-01,-4.058523839149164592e-01
+2.963590179947667158e-02,7.098632864870428882e-01,1.254818146283740235e-02,1.487310921672435338e-01,-2.728787781527319128e-02,-4.994660274917479548e-01,1.178014005986963431e-01,-7.809684223226981414e-01,-1.370588412569395398e-01,2.278042664164683373e-01,1.252216408635276577e-02,-1.026656369181621611e-03,5.877852522953803949e-02,-1.100000000000000006e-01,-6.233688103939015734e-01,-5.877852522953803949e-02,1.100000000000000006e-01,-7.366311896060985243e-01,9.803681411943629409e-02,-1.014364010926151610e-01,-3.400409482091860669e-01,1.963185880563586561e-03,1.185635989073848401e-01,-3.999590517908137577e-01
+6.161585822269086132e-02,7.103901144864899209e-01,9.217067175001536494e-03,1.416878746224333185e-01,-4.810022722873205647e-02,-4.917885642701010362e-01,1.146525911130885644e-01,-7.340487569086044939e-01,-1.545832616040513641e-01,1.832300851372748451e-01,1.002054977257886385e-02,-2.367965080473719789e-03,7.071067811891042221e-02,-1.100000000000000006e-01,-6.305025253171206989e-01,-7.071067811891042221e-02,1.100000000000000006e-01,-7.294974746828793988e-01,1.030693551131139918e-01,-1.043692093772153745e-01,-3.466719716167707133e-01,-3.069355113114083378e-03,1.156307906227846266e-01,-3.933280283832291113e-01
+8.723604095484661924e-02,7.018536152208454393e-01,5.483080760995945498e-03,1.314589164205144101e-01,-6.436012173408658943e-02,-4.787833981381420245e-01,1.151334353456332227e-01,-6.803817301672747675e-01,-1.715712081082999552e-01,1.398613826570681284e-01,7.290000459007611906e-03,-3.411449538257570451e-03,8.090169943770858518e-02,-1.100000000000000006e-01,-6.388550323397329533e-01,-8.090169943770858518e-02,1.100000000000000006e-01,-7.211449676602671444e-01,1.067951524568146321e-01,-1.074406664144712531e-01,-3.538774085044380513e-01,-6.795152456814695929e-03,1.125593335855287480e-01,-3.861225914955617733e-01
+1.053548694616308484e-01,6.854951399739531714e-01,1.678016517508791085e-03,1.190053900475974424e-01,-7.516005639116463133e-02,-4.615221586752343286e-01,1.200377521514920942e-01,-6.233272708728651024e-01,-1.880758526940077280e-01,9.974724695630471372e-02,4.369022085615851397e-03,-4.366040839617555888e-03,8.910065241900294586e-02,-1.100000000000000006e-01,-6.482206650184600960e-01,-8.910065241900294586e-02,1.100000000000000006e-01,-7.117793349815400017e-01,1.091224646547238053e-01,-1.105751427385440744e-01,-3.614798371025397250e-01,-9.122464654723848321e-03,1.094248572614559267e-01,-3.785201628974600996e-01
+1.146620808151982140e-01,6.625800878596499466e-01,-1.890103041001295857e-03,1.052190971441820666e-01,-7.943570573498356935e-02,-4.410041489833632089e-01,1.304791654642892818e-01,-5.658964679601874437e-01,-2.043186049000985660e-01,6.461523056195715708e-02,1.287435098065008122e-03,-5.419406970912577642e-03,9.510565162962915375e-02,-1.100000000000000006e-01,-6.583688103939988601e-01,-9.510565162962915375e-02,1.100000000000000006e-01,-7.016311896060012376e-01,1.099939855566226532e-01,-1.136954571396046193e-01,-3.692920603879763508e-01,-9.993985556622654587e-03,1.063045428603953818e-01,-3.707079396120234738e-01
+1.136141537207361885e-01,6.342675291546012728e-01,-4.987495030903144402e-03,9.083235139012682535e-02,-7.590858215711006329e-02,-4.180607698335609967e-01,1.479745070386476180e-01,-5.104581687380056465e-01,-2.207334564721530334e-01,3.567820158532048619e-02,-1.929766589180471632e-03,-6.698175941196126901e-03,9.876883405957172235e-02,-1.100000000000000006e-01,-6.690495874474400306e-01,-9.876883405957172235e-02,1.100000000000000006e-01,-6.909504125525600671e-01,1.093882554254943518e-01,-1.167247771213689722e-01,-3.771217154961779006e-01,-9.388255425494318462e-03,1.032752228786310289e-01,-3.628782845038219240e-01
+1.003892154372886397e-01,6.015091030966839281e-01,-7.536003586232908023e-03,7.639017381962706632e-02,-6.304935679311959862e-02,-3.932898026086137366e-01,1.745055716388065059e-01,-4.585879697248754772e-01,-2.380022910161208038e-01,1.353823766678136087e-02,-5.252174634803003644e-03,-8.248665217475319514e-03,1.000000000000000056e-01,-1.100000000000000006e-01,-6.800000000002619505e-01,-1.000000000000000056e-01,1.100000000000000006e-01,-6.799999999997381472e-01,1.073201893474700769e-01,-1.195885107721497143e-01,-3.847760103332455439e-01,-7.320189347470015817e-03,1.004114892278502869e-01,-3.552239896667542807e-01
+7.293045398873880536e-02,5.650199172965496563e-01,-9.739606996869308933e-03,6.227748628585906554e-02,-3.912876259631285769e-02,-3.670525667957612592e-01,2.124776593402013247e-01,-4.111058022725054273e-01,-2.570391413970234407e-01,-1.772078937594073842e-03,-8.624325639777741595e-03,-1.003981562877616189e-02,9.876883405945491301e-02,-1.100000000000000006e-01,-6.909504125530764318e-01,-9.876883405945491301e-02,1.100000000000000006e-01,-6.690495874469236659e-01,1.038407099729090066e-01,-1.222161434652770107e-01,-3.920664707571410723e-01,-3.840709972908903924e-03,9.778385653472299044e-02,-3.479335292428587523e-01
+2.922878092653797416e-02,5.253190287850538764e-01,-1.225311428525546233e-02,4.877165008270731988e-02,-2.497974192292804971e-03,-3.395273341124500077e-01,2.643954788352351204e-01,-3.682489008898571226e-01,-2.788295816941412375e-01,-1.064761765357897551e-02,-1.193481551195196312e-02,-1.198181587149298351e-02,9.510565162939838002e-02,-1.100000000000000006e-01,-7.016311896064983955e-01,-9.510565162939838002e-02,1.100000000000000006e-01,-6.583688103935017022e-01,9.903549363174268816e-02,-1.245429741632333720e-01,-3.988135814365779130e-01,9.645063682574353536e-04,9.545702583676662911e-02,-3.411864185634219671e-01
+-3.191699582626464360e-02,4.828051591274130083e-01,-1.631742097940867137e-02,3.609134981993040309e-02,4.768801171576594888e-02,-3.107876914946852143e-01,3.319682847530356362e-01,-3.298837045290459180e-01,-3.039753575654020046e-01,-1.374068819079529019e-02,-1.498012027520248535e-02,-1.395079121644353035e-02,8.910065241866393926e-02,-1.100000000000000006e-01,-7.117793349820058513e-01,-8.910065241866393926e-02,1.100000000000000006e-01,-6.482206650179942464e-01,9.302286069788942569e-02,-1.265117085719267565e-01,-4.048512061142517382e-01,6.977139302110718644e-03,9.348829142807324466e-02,-3.351487938857481419e-01
+-1.095522403430949226e-01,4.378336598924750245e-01,-2.363195766991426847e-02,2.442778464453676177e-02,1.102372783071428192e-01,-2.808774127900107720e-01,4.144794111118411672e-01,-2.956860640208444635e-01,-3.318676187603056271e-01,-1.181813277397066042e-02,-1.744878856008454451e-02,-1.581207081674800355e-02,8.090169943726964463e-02,-1.100000000000000006e-01,-7.211449676606900283e-01,-8.090169943726964463e-02,1.100000000000000006e-01,-6.388550323393100694e-01,8.595086214896535681e-02,-1.280738699163601890e-01,-4.100306784328706655e-01,1.404913785103480833e-02,9.192613008363979821e-02,-3.299693215671292146e-01
+-1.980260120107794064e-01,3.907770986519272793e-01,-3.546144753812311562e-02,1.395745259013221606e-02,1.798060562184553290e-01,-2.498681818952465106e-01,5.040411986104195163e-01,-2.652653009980161514e-01,-3.478089728116707802e-01,-5.665123502416524390e-03,-1.886183327924468092e-02,-1.743836329121734377e-02,7.071067811838238626e-02,-1.100000000000000006e-01,-7.294974746832489920e-01,-7.071067811838238626e-02,1.100000000000000006e-01,-6.305025253167511057e-01,7.799363405986262099e-02,-1.291909925997175024e-01,-4.142244625942671510e-01,2.200636594013757538e-02,9.080900740028249873e-02,-3.257755374057327291e-01
+-2.895443046027449951e-01,3.420655581754828978e-01,-5.160187264068707980e-02,4.841596824409178171e-03,2.492728734070537300e-01,-2.178979182508637980e-01,5.905773675908857490e-01,-2.382376078099279204e-01,-3.489874358007294397e-01,3.968751818081916842e-03,-1.860051970966817778e-02,-1.872202140061101847e-02,5.877852522893274589e-02,-1.100000000000000006e-01,-7.366311896064063891e-01,-5.877852522893274589e-02,1.100000000000000006e-01,-6.233688103935937086e-01,6.934710979466010561e-02,-1.298355693540167721e-01,-4.173292937140162251e-01,3.065289020534009770e-02,9.016443064598321511e-02,-3.226707062859837105e-01
+-3.793666227271484392e-01,2.922088815117364624e-01,-7.120691346047833270e-02,-2.782043068289935875e-03,3.145830796563083842e-01,-1.851921758797694939e-01,6.714023036886869189e-01,-2.142641032473865115e-01,-3.490610897375456267e-01,1.639386155551239913e-02,-1.703940665425327308e-02,-1.958198324589945777e-02,4.539904997360625499e-02,-1.100000000000000006e-01,-7.423704566933100324e-01,-4.539904997360625499e-02,1.100000000000000006e-01,-6.176295433066900653e-01,6.022419547693755315e-02,-1.299917285603394979e-01,-4.192687205456053223e-01,3.977580452306266057e-02,9.000827143966048938e-02,-3.207312794543946688e-01
+-4.622966703111353604e-01,2.418044428685231784e-01,-9.227356492678791267e-02,-8.810760645620996714e-03,3.717175438108728525e-01,-1.520718893929183801e-01,7.407176961236008328e-01,-1.930679167296499854e-01,-3.490656931085965864e-01,3.098756273294367425e-02,-1.457753668241056760e-02,-1.996643096951009055e-02,3.090169943712072279e-02,-1.100000000000000006e-01,-7.465739561407458424e-01,-3.090169943712072279e-02,1.100000000000000006e-01,-6.134260438592542553e-01,5.084952753441335238e-02,-1.296556250607633631e-01,-4.199949879638523731e-01,4.915047246558685440e-02,9.034437493923663798e-02,-3.200050120361476180e-01
+-5.348385334550390668e-01,1.915338529929160871e-01,-1.124415214081075365e-01,-1.318858593760854556e-02,4.184620240921773648e-01,-1.189504629195387714e-01,7.942577162635963139e-01,-1.744406738131383805e-01,-3.490659808192873026e-01,4.719277263897387470e-02,-1.166413896004562904e-02,-1.985221780111902368e-02,1.564344650363247088e-02,-1.100000000000000006e-01,-7.491381838417030536e-01,-1.564344650363247088e-02,1.100000000000000006e-01,-6.108618161582970441e-01,4.145394140457164811e-02,-1.288355348389114974e-01,-4.194902128545768272e-01,5.854605859542855867e-02,9.116446516108848985e-02,-3.205097871454231639e-01
+-5.953693400294362004e-01,1.421519329429730694e-01,-1.297194457239829735e-01,-1.591602986315254764e-02,4.543397535396776488e-01,-8.632316183504300244e-02,8.301158477201786567e-01,-1.582451059995046705e-01,-3.490659988012054238e-01,6.451373185772091290e-02,-8.703821904293451359e-03,-1.924197278443141521e-02,-3.977080504358561907e-13,-1.100000000000000006e-01,-7.500000000000000000e-01,3.977080504358561907e-13,1.100000000000000006e-01,-6.100000000000000977e-01,3.226878760009183056e-02,-1.275516512377693201e-01,-4.177668244562215971e-01,6.773121239990836928e-02,9.244834876223068099e-02,-3.222331755437784495e-01
+-6.433256773743176726e-01,9.447163462190159844e-02,-1.426945809661056275e-01,-1.705646484154976425e-02,4.797609735122090879e-01,-5.475217720572726765e-02,8.476869101484298952e-01,-1.444180509876695218e-01,-3.459210837702010877e-01,8.251230611438968576e-02,-5.985677071176916803e-03,-1.815963020592674046e-02,-1.564344650441809245e-02,-1.100000000000000006e-01,-7.491381838416159011e-01,1.564344650441809245e-02,1.100000000000000006e-01,-6.108618161583841966e-01,2.352023509141800209e-02,-1.258355877325623151e-01,-4.148672583107522738e-01,7.647976490858218734e-02,9.416441226743767212e-02,-3.251327416892477729e-01
+-6.773332858461268424e-01,4.934908311042228435e-02,-1.498575406397940346e-01,-1.673834903912786720e-02,4.945905135247579132e-01,-2.485129274839303903e-02,8.412338040716541565e-01,-1.329767390240259306e-01,-3.118859117672292403e-01,1.008067836228445230e-01,-3.185372749432813233e-03,-1.664499566589496687e-02,-3.090169943787856102e-02,-1.100000000000000006e-01,-7.465739561405735358e-01,3.090169943787856102e-02,1.100000000000000006e-01,-6.134260438594265619e-01,1.542370227609424216e-02,-1.237295995020767647e-01,-4.108629113597783711e-01,8.457629772390592993e-02,9.627040049792323639e-02,-3.291370886402217311e-01
+-6.991592328523634770e-01,7.673188384044946075e-03,-1.516888329904684252e-01,-1.515302578480061738e-02,5.007475828907339555e-01,2.725583435831282694e-03,8.177541401312067304e-01,-1.240306783856100770e-01,-2.714130818270439338e-01,1.190744289970874087e-01,-7.917428048201491202e-04,-1.474786567654033306e-02,-4.539904997431624262e-02,-1.100000000000000006e-01,-7.423704566930569015e-01,4.539904997431624262e-02,1.100000000000000006e-01,-6.176295433069431962e-01,8.178552662887167424e-03,-1.212855429659218109e-01,-4.058523839148991397e-01,9.182144733711299078e-02,9.871445703407819017e-02,-3.341476160851010180e-01
+-7.098632864870597636e-01,-2.963590179958393647e-02,-1.487310921672277131e-01,-1.254818146282813372e-02,4.994660274917336329e-01,2.728787781534348922e-02,7.809684223225671351e-01,-1.178014005986821044e-01,-2.278042664163307529e-01,1.370588412569946346e-01,1.026656369186373235e-03,-1.252216408634551810e-02,-5.877852522957739689e-02,-1.100000000000000006e-01,-7.366311896060785402e-01,5.877852522957739689e-02,1.100000000000000006e-01,-6.233688103939215575e-01,1.963185880546218509e-03,-1.185635989073760416e-01,-3.999590517907944398e-01,9.803681411945391888e-02,1.014364010926239595e-01,-3.400409482092057178e-01
+-7.103901144864764872e-01,-6.161585822278013019e-02,-1.416878746224059515e-01,-9.217067174990432529e-03,4.917885642700682292e-01,4.810022722878885132e-02,7.340487569084461761e-01,-1.146525911130843456e-01,-1.832300851371362616e-01,1.545832616041032392e-01,2.367965080477470695e-03,-1.002054977257229619e-02,-7.071067811894482524e-02,-1.100000000000000006e-01,-7.294974746828553069e-01,7.071067811894482524e-02,1.100000000000000006e-01,-6.305025253171447908e-01,-3.069355113127607282e-03,-1.156307906227752869e-01,-3.933280283832077950e-01,1.030693551131277030e-01,1.043692093772247143e-01,-3.466719716167923626e-01
+-7.018536152208053602e-01,-8.723604095491478694e-02,-1.314589164204784666e-01,-5.483080760984137235e-03,4.787833981380941184e-01,6.436012173412884729e-02,6.803817301671002404e-01,-1.151334353456410081e-01,-1.398613826569362617e-01,1.715712081083509699e-01,3.411449538260682545e-03,-7.290000458998970381e-03,-8.090169943773717343e-02,-1.100000000000000006e-01,-7.211449676602396108e-01,8.090169943773717343e-02,1.100000000000000006e-01,-6.388550323397604869e-01,-6.795152456824042619e-03,-1.125593335855190891e-01,-3.861225914955389027e-01,1.067951524568241106e-01,1.074406664144809120e-01,-3.538774085044612550e-01
+-6.854951399738916651e-01,-1.053548694616737169e-01,-1.190053900475564475e-01,-1.678016517497302228e-03,4.615221586751752092e-01,7.516005639118839010e-02,6.233272708726861344e-01,-1.200377521515155893e-01,-9.974724695618729375e-02,1.880758526940581876e-01,4.366040839620499714e-03,-4.369022085606451798e-03,-8.910065241902503930e-02,-1.100000000000000006e-01,-7.117793349815096926e-01,8.910065241902503930e-02,1.100000000000000006e-01,-6.482206650184904051e-01,-9.122464654728781874e-03,-1.094248572614461984e-01,-3.785201628974363408e-01,1.091224646547288291e-01,1.105751427385538027e-01,-3.614798371025638168e-01
+-6.625800878595675680e-01,-1.146620808152122167e-01,-1.052190971441366862e-01,1.890103041012013846e-03,4.410041489832934314e-01,7.943570573498545673e-02,5.658964679600062553e-01,-1.304791654643328858e-01,-6.461523056185430880e-02,2.043186049001500804e-01,5.419406970916044487e-03,-1.287435098054819224e-03,-9.510565162964462749e-02,-1.100000000000000006e-01,-7.016311896059679309e-01,9.510565162964462749e-02,1.100000000000000006e-01,-6.583688103940321668e-01,-9.993985556623077859e-03,-1.063045428603855425e-01,-3.707079396119986048e-01,1.099939855566230834e-01,1.136954571396144587e-01,-3.692920603880015529e-01
+-6.342675291545031291e-01,-1.136141537207147056e-01,-9.083235139008047354e-02,4.987495030912109453e-03,4.180607698334845024e-01,7.590858215708516654e-02,5.104581687378335619e-01,-1.479745070387163131e-01,-3.567820158523880153e-02,2.207334564722065462e-01,6.698175941200610294e-03,1.929766589190806680e-03,-9.876883405957956330e-02,-1.100000000000000006e-01,-6.909504125525254281e-01,9.876883405957956330e-02,1.100000000000000006e-01,-6.690495874474746696e-01,-9.388255425490064920e-03,-1.032752228786216059e-01,-3.628782845037973326e-01,1.093882554254900497e-01,1.167247771213783952e-01,-3.771217154962028806e-01
+-6.015091030965761254e-01,-1.003892154372270640e-01,-7.639017381958260189e-02,7.536003586240069829e-03,3.932898026085344667e-01,6.304935679306382379e-02,4.585879697247207676e-01,-1.745055716389045386e-01,-1.353823766672317130e-02,2.380022910161762040e-01,8.248665217480523684e-03,5.252174634813400710e-03,-1.000000000000000056e-01,-1.100000000000000006e-01,-6.799999999997041744e-01,1.000000000000000056e-01,1.100000000000000006e-01,-6.800000000002959233e-01,-7.320189347461446283e-03,-1.004114892278417381e-01,-3.552239896667312435e-01,1.073201893474613894e-01,1.195885107721582630e-01,-3.847760103332689141e-01
+-5.650199172964310845e-01,-7.293045398862943451e-02,-6.227748628581612073e-02,9.739606996876142009e-03,3.670525667956778815e-01,3.912876259621973080e-02,4.111058022723650951e-01,-2.124776593403396863e-01,1.772078937631440219e-03,2.570391413970863903e-01,1.003981562878198536e-02,8.624325639788260958e-03,-9.876883405944730798e-02,-1.100000000000000006e-01,-6.690495874468900261e-01,9.876883405944730798e-02,1.100000000000000006e-01,-6.909504125531100716e-01,-3.840709972896108604e-03,-9.778385653471528827e-02,-3.479335292428371029e-01,1.038407099728960170e-01,1.222161434652847128e-01,-3.920664707571630547e-01
+-5.253190287849258677e-01,-2.922878092637552078e-02,-4.877165008266665103e-02,1.225311428526495126e-02,3.395273341123627442e-01,2.497974192157772361e-03,3.682489008897311122e-01,-2.643954788354201391e-01,1.064761765359733756e-02,2.788295816942134575e-01,1.198181587149901341e-02,1.193481551196214942e-02,-9.510565162938335038e-02,-1.100000000000000006e-01,-6.583688103934692837e-01,9.510565162938335038e-02,1.100000000000000006e-01,-7.016311896065308140e-01,9.645063682741372713e-04,-9.545702583675994002e-02,-3.411864185634022051e-01,9.903549363172575726e-02,1.245429741632400611e-01,-3.988135814365979526e-01
+-4.828051591272765619e-01,3.191699582648013789e-02,-3.609134981989250285e-02,1.631742097942533165e-02,3.107876914945940650e-01,-4.768801171594127392e-02,3.298837045289326753e-01,-3.319682847532683945e-01,1.374068819079706481e-02,3.039753575654844941e-01,1.395079121644957065e-02,1.498012027521126652e-02,-8.910065241864184582e-02,-1.100000000000000006e-01,-6.482206650179639373e-01,8.910065241864184582e-02,1.100000000000000006e-01,-7.117793349820361604e-01,6.977139302130931642e-03,-9.348829142806776293e-02,-3.351487938857308224e-01,9.302286069786894207e-02,1.265117085719322243e-01,-4.048512061142692797e-01
+-4.378336598923266432e-01,1.095522403433604464e-01,-2.442778464450100565e-02,2.363195766994407448e-02,2.808774127899126283e-01,-1.102372783073544138e-01,2.956860640207395474e-01,-4.144794111121178903e-01,1.181813277395767081e-02,3.318676187603945560e-01,1.581207081675380446e-02,1.744878856009091789e-02,-8.090169943724020984e-02,-1.100000000000000006e-01,-6.388550323392816477e-01,8.090169943724020984e-02,1.100000000000000006e-01,-7.211449676607184500e-01,1.404913785105869894e-02,-9.192613008363550997e-02,-3.299693215671143376e-01,8.595086214894114007e-02,1.280738699163644911e-01,-4.100306784328857646e-01
+-3.907770986517725142e-01,1.980260120110646782e-01,-1.395745259010051746e-02,3.546144753816722617e-02,2.498681818951445643e-01,-1.798060562186757916e-01,2.652653009979221710e-01,-5.040411986106948516e-01,5.665123502391240795e-03,3.478089728116817159e-01,1.743836329122215936e-02,1.886183327924631503e-02,-7.071067811834697014e-02,-1.100000000000000006e-01,-6.305025253167262367e-01,7.071067811834697014e-02,1.100000000000000006e-01,-7.294974746832738610e-01,2.200636594016397093e-02,-9.080900740027968154e-02,-3.257755374057211273e-01,7.799363405983585074e-02,1.291909925997203057e-01,-4.142244625942789193e-01
+-3.420655581753290764e-01,2.895443046030275469e-01,-4.841596824383060174e-03,5.160187264074291708e-02,2.178979182507633505e-01,-2.492728734072638674e-01,2.382376078098480121e-01,-5.905773675911466514e-01,-3.968751818116842897e-03,3.489874358007301058e-01,1.872202140061460934e-02,1.860051970966519058e-02,-5.877852522889337461e-02,-1.100000000000000006e-01,-6.233688103935737246e-01,5.877852522889337461e-02,1.100000000000000006e-01,-7.366311896064263731e-01,3.065289020536754103e-02,-9.016443064598196611e-02,-3.226707062859759390e-01,6.934710979463226677e-02,1.298355693540180211e-01,-4.173292937140241077e-01
+-2.922088815115807536e-01,3.793666227274185565e-01,2.782043068311053531e-03,7.120691346054260074e-02,1.851921758796676032e-01,-3.145830796564997867e-01,2.142641032473166229e-01,-6.714023036889230633e-01,-1.639386155555354677e-02,3.490610897375455712e-01,1.958198324590141454e-02,1.703940665424671583e-02,-4.539904997356289384e-02,-1.100000000000000006e-01,-6.176295433066745222e-01,4.539904997356289384e-02,1.100000000000000006e-01,-7.423704566933255755e-01,3.977580452309122105e-02,-9.000827143966076693e-02,-3.207312794543905055e-01,6.022419547690857633e-02,1.299917285603392203e-01,-4.192687205456094857e-01
+-2.418044428683667757e-01,4.622966703113781106e-01,8.810760645637074132e-03,9.227356492685327705e-02,1.520718893928159343e-01,-3.717175438110350005e-01,1.930679167295882848e-01,-7.407176961237942336e-01,-3.098756273299035219e-02,3.490656931085965864e-01,1.996643096951059362e-02,1.457753668240186970e-02,-3.090169943707444383e-02,-1.100000000000000006e-01,-6.134260438592437081e-01,3.090169943707444383e-02,1.100000000000000006e-01,-7.465739561407563896e-01,4.915047246561584510e-02,-9.034437493923842821e-02,-3.200050120361472850e-01,5.084952753438395229e-02,1.296556250607615590e-01,-4.199949879638527062e-01
+-1.915338529927605171e-01,5.348385334552451242e-01,1.318858593761964085e-02,1.124415214081661285e-01,1.189504629194360480e-01,-4.184620240923048184e-01,1.744406738130834522e-01,-7.942577162637346477e-01,-4.719277263902556946e-02,3.490659808192873026e-01,1.985221780111796550e-02,1.166413896003640899e-02,-1.564344650358440864e-02,-1.100000000000000006e-01,-6.108618161582917150e-01,1.564344650358440864e-02,1.100000000000000006e-01,-7.491381838417083827e-01,5.854605859545725099e-02,-9.116446516109176501e-02,-3.205097871454266056e-01,4.145394140454254639e-02,1.288355348389082222e-01,-4.194902128545733300e-01
+-1.421519329428165002e-01,5.953693400296072857e-01,1.591602986315878571e-02,1.297194457240309073e-01,8.632316183493961292e-02,-4.543397535397734610e-01,1.582451059994554599e-01,-8.301158477202610353e-01,-6.451373185777943553e-02,3.490659988012054238e-01,1.924197278442900047e-02,8.703821904284486308e-03,4.477890668389517879e-13,-1.100000000000000006e-01,-6.100000000000000977e-01,-4.477890668389517879e-13,1.100000000000000006e-01,-7.500000000000000000e-01,6.773121239993688814e-02,-9.244834876223548270e-02,-3.222331755437858325e-01,3.226878760006292313e-02,1.275516512377645184e-01,-4.177668244562141031e-01
+-9.447163462175187099e-02,6.433256773744462365e-01,1.705646484155106876e-02,1.426945809661372966e-01,5.475217720562787493e-02,-4.797609735122713159e-01,1.444180509876281382e-01,-8.476869101484446611e-01,-8.251230611444963781e-02,3.459210837701161001e-01,1.815963020592244875e-02,5.985677071169225906e-03,1.564344650446755636e-02,-1.100000000000000006e-01,-6.108618161583896367e-01,-1.564344650446755636e-02,1.100000000000000006e-01,-7.491381838416104610e-01,7.647976490860897147e-02,-9.416441226744379223e-02,-3.251327416892587641e-01,2.352023509139085367e-02,1.258355877325562089e-01,-4.148672583107411715e-01
+-4.934908311028658734e-02,6.773332858462125516e-01,1.673834903912478980e-02,1.498575406398075516e-01,2.485129274830267382e-02,-4.945905135247893880e-01,1.329767390239933456e-01,-8.412338040716048626e-01,-1.008067836228995207e-01,3.118859117671108350e-01,1.664499566588866983e-02,3.185372749424538168e-03,3.090169943792483997e-02,-1.100000000000000006e-01,-6.134260438594371090e-01,-3.090169943792483997e-02,1.100000000000000006e-01,-7.465739561405629887e-01,8.457629772392963319e-02,-9.627040049793031407e-02,-3.291370886402356644e-01,1.542370227607021277e-02,1.237295995020696870e-01,-4.108629113597642712e-01
+-7.673188383921685299e-03,6.991592328524126598e-01,1.515302578479397339e-02,1.516888329904660937e-01,-2.725583435912644695e-03,-5.007475828907406168e-01,1.240306783855855133e-01,-8.177541401311106961e-01,-1.190744289971414904e-01,2.714130818269102075e-01,1.474786567653401173e-02,7.917428048135373301e-04,4.539904997435959683e-02,-1.100000000000000006e-01,-6.176295433069587393e-01,-4.539904997435959683e-02,1.100000000000000006e-01,-7.423704566930413584e-01,9.182144733713376583e-02,-9.871445703408622541e-02,-3.341476160851178379e-01,8.178552662866087064e-03,1.212855429659137757e-01,-4.058523839148820422e-01
+2.963590179969222832e-02,7.098632864870761949e-01,1.254818146281871764e-02,1.487310921672114483e-01,-2.728787781541444288e-02,-4.994660274917188669e-01,1.178014005986665613e-01,-7.809684223224344635e-01,-1.370588412570480086e-01,2.278042664161910036e-01,1.252216408633824614e-02,-1.026656369191400464e-03,5.877852522961676818e-02,-1.100000000000000006e-01,-6.233688103939416525e-01,-5.877852522961676818e-02,1.100000000000000006e-01,-7.366311896060584452e-01,9.803681411947129387e-02,-1.014364010926327581e-01,-3.400409482092250357e-01,1.963185880528600658e-03,1.185635989073672431e-01,-3.999590517907748444e-01
+6.161585822287030806e-02,7.103901144864634976e-01,9.217067174979318156e-03,1.416878746223786678e-01,-4.810022722884768620e-02,-4.917885642700355886e-01,1.146525911130795855e-01,-7.340487569082886354e-01,-1.545832616041572238e-01,1.832300851369988715e-01,1.002054977256272052e-02,-2.367965080481065476e-03,7.071067811897922828e-02,-1.100000000000000006e-01,-6.305025253171688826e-01,-7.071067811897922828e-02,1.100000000000000006e-01,-7.294974746828312151e-01,1.030693551131412478e-01,-1.043692093772340540e-01,-3.466719716168137344e-01,-3.069355113141325475e-03,1.156307906227659471e-01,-3.933280283831860902e-01
+8.723604095498534161e-02,7.018536152207657253e-01,5.483080760971939527e-03,1.314589164204421068e-01,-6.436012173417264559e-02,-4.787833981380458792e-01,1.151334353456490572e-01,-6.803817301669231599e-01,-1.715712081084049545e-01,1.398613826568058383e-01,7.290000458989858746e-03,-3.411449538263736092e-03,8.090169943776660821e-02,-1.100000000000000006e-01,-6.388550323397889086e-01,-8.090169943776660821e-02,1.100000000000000006e-01,-7.211449676602111891e-01,1.067951524568337279e-01,-1.074406664144908485e-01,-3.538774085044847917e-01,-6.795152456833791765e-03,1.125593335855091526e-01,-3.861225914955150329e-01
+1.053548694617185005e-01,6.854951399738289375e-01,1.678016517485345646e-03,1.190053900475141202e-01,-7.516005639121323134e-02,-4.615221586751144245e-01,1.200377521515391538e-01,-6.233272708725031697e-01,-1.880758526941114506e-01,9.974724695606665414e-02,4.369022085596805868e-03,-4.366040839623414917e-03,8.910065241904778499e-02,-1.100000000000000006e-01,-6.482206650185216024e-01,-8.910065241904778499e-02,1.100000000000000006e-01,-7.117793349814784953e-01,1.091224646547339083e-01,-1.105751427385638086e-01,-3.614798371025883528e-01,-9.122464654733944411e-03,1.094248572614361925e-01,-3.785201628974114718e-01
+1.146620808152259141e-01,6.625800878594878540e-01,-1.890103041022435197e-03,1.052190971440928324e-01,-7.943570573498734411e-02,-4.410041489832258743e-01,1.304791654643753240e-01,-5.658964679598308400e-01,-2.043186049002000404e-01,6.461523056175534629e-02,1.287435098045046009e-03,-5.419406970919762000e-03,9.510565162965967101e-02,-1.100000000000000006e-01,-6.583688103940645853e-01,-9.510565162965967101e-02,1.100000000000000006e-01,-7.016311896059355124e-01,1.099939855566234997e-01,-1.136954571396240204e-01,-3.692920603880257002e-01,-9.993985556623494193e-03,1.063045428603759807e-01,-3.707079396119741244e-01
+1.136141537206933755e-01,6.342675291544086491e-01,-4.987495030920886287e-03,9.083235139003578706e-02,-7.590858215706042245e-02,-4.180607698334106725e-01,1.479745070387835926e-01,-5.104581687376673615e-01,-2.207334564722584769e-01,3.567820158515973283e-02,-1.929766589201090989e-03,-6.698175941205045981e-03,9.876883405958718221e-02,-1.100000000000000006e-01,-6.690495874475083093e-01,-9.876883405958718221e-02,1.100000000000000006e-01,-6.909504125524917884e-01,1.093882554254859141e-01,-1.167247771213875684e-01,-3.771217154962267504e-01,-9.388255425485880767e-03,1.032752228786124327e-01,-3.628782845037730742e-01
+1.003892154371643641e-01,6.015091030964688779e-01,-7.536003586247242043e-03,7.639017381953831787e-02,-6.304935679300695262e-02,-3.932898026084556964e-01,1.745055716390041811e-01,-4.585879697245673903e-01,-2.380022910162316041e-01,1.353823766666559930e-02,-5.252174634823747468e-03,-8.248665217485800713e-03,1.000000000000000056e-01,-1.100000000000000006e-01,-6.800000000003300071e-01,-1.000000000000000056e-01,1.100000000000000006e-01,-6.799999999996700906e-01,1.073201893474528268e-01,-1.195885107721667978e-01,-3.847760103332920067e-01,-7.320189347452758788e-03,1.004114892278332033e-01,-3.552239896667078178e-01
+7.293045398851950856e-02,5.650199172963132899e-01,-9.739606996882975085e-03,6.227748628577334938e-02,-3.912876259612620145e-02,-3.670525667955947258e-01,2.124776593404785474e-01,-4.111058022722258731e-01,-2.570391413971494510e-01,-1.772078937668280542e-03,-8.624325639798721341e-03,-1.003981562878780188e-02,9.876883405943968908e-02,-1.100000000000000006e-01,-6.909504125531437113e-01,-9.876883405943968908e-02,1.100000000000000006e-01,-6.690495874468563864e-01,1.038407099728832217e-01,-1.222161434652924289e-01,-3.920664707571847041e-01,-3.840709972883139811e-03,9.778385653470757222e-02,-3.479335292428151205e-01
+2.922878092620965693e-02,5.253190287847949724e-01,-1.225311428527455296e-02,4.877165008262479562e-02,-2.497974192020458589e-03,-3.395273341122730382e-01,2.643954788356085994e-01,-3.682489008896018268e-01,-2.788295816942876204e-01,-1.064761765361595981e-02,-1.193481551197221255e-02,-1.198181587150538331e-02,9.510565162936787664e-02,-1.100000000000000006e-01,-7.016311896065641207e-01,-9.510565162936787664e-02,1.100000000000000006e-01,-6.583688103934359770e-01,9.903549363170854880e-02,-1.245429741632469306e-01,-3.988135814366182696e-01,9.645063682915747116e-04,9.545702583675307051e-02,-3.411864185633816104e-01
+-3.191699582670230045e-02,4.828051591271372844e-01,-1.631742097944251929e-02,3.609134981985358953e-02,4.768801171612223333e-02,-3.107876914945005842e-01,3.319682847535081471e-01,-3.298837045288173786e-01,-3.039753575655700923e-01,-1.374068819079832422e-02,-1.498012027522019687e-02,-1.395079121645582433e-02,8.910065241861910013e-02,-1.100000000000000006e-01,-7.117793349820673576e-01,-8.910065241861910013e-02,1.100000000000000006e-01,-6.482206650179327401e-01,9.302286069784812539e-02,-1.265117085719378864e-01,-4.048512061142870988e-01,6.977139302152018940e-03,9.348829142806210080e-02,-3.351487938857127258e-01
+-1.095522403436254566e-01,4.378336598921844791e-01,-2.363195766997375907e-02,2.442778464446679343e-02,1.102372783075658141e-01,-2.808774127898184814e-01,4.144794111123959457e-01,-2.956860640206404045e-01,-3.318676187604852057e-01,-1.181813277394458406e-02,-1.744878856009742657e-02,-1.581207081675919252e-02,8.090169943721160772e-02,-1.100000000000000006e-01,-7.211449676607459836e-01,-8.090169943721160772e-02,1.100000000000000006e-01,-6.388550323392541141e-01,8.595086214891792253e-02,-1.280738699163686545e-01,-4.100306784329002530e-01,1.404913785108224261e-02,9.192613008363134663e-02,-3.299693215670996826e-01
+-1.980260120113489786e-01,3.907770986516259093e-01,-3.546144753821128814e-02,1.395745259007049634e-02,1.798060562188956990e-01,-2.498681818950483913e-01,5.040411986109720743e-01,-2.652653009978359622e-01,-3.478089728116929846e-01,-5.665123502366234756e-03,-1.886183327924795608e-02,-1.743836329122663842e-02,7.071067811831256711e-02,-1.100000000000000006e-01,-7.294974746832979529e-01,-7.071067811831256711e-02,1.100000000000000006e-01,-6.305025253167021448e-01,7.799363405981021846e-02,-1.291909925997230535e-01,-4.142244625942901881e-01,2.200636594018997791e-02,9.080900740027693374e-02,-3.257755374057096920e-01
+-2.895443046033148726e-01,3.420655581751778085e-01,-5.160187264079985070e-02,4.841596824357418359e-03,2.492728734074776686e-01,-2.178979182506642631e-01,5.905773675914136600e-01,-2.382376078097713790e-01,-3.489874358007307720e-01,3.968751818151167871e-03,-1.860051970966203339e-02,-1.872202140061777348e-02,5.877852522885401026e-02,-1.100000000000000006e-01,-7.366311896064463571e-01,-5.877852522885401026e-02,1.100000000000000006e-01,-6.233688103935537406e-01,6.934710979460483038e-02,-1.298355693540192701e-01,-4.173292937140319347e-01,3.065289020539537293e-02,9.016443064598071711e-02,-3.226707062859680009e-01
+-3.793666227276900060e-01,2.922088815114262106e-01,-7.120691346060720184e-02,-2.782043068332098329e-03,3.145830796566920773e-01,-1.851921758795660733e-01,6.714023036891602070e-01,-2.142641032472479279e-01,-3.490610897375456267e-01,1.639386155559560340e-02,-1.703940665424013429e-02,-1.958198324590320477e-02,4.539904997351953964e-02,-1.100000000000000006e-01,-7.423704566933410076e-01,-4.539904997351953964e-02,1.100000000000000006e-01,-6.176295433066590901e-01,6.022419547688001584e-02,-1.299917285603389427e-01,-4.192687205456135935e-01,3.977580452312019788e-02,9.000827143966105837e-02,-3.207312794543863421e-01
+-4.622966703116258014e-01,2.418044428682060709e-01,-9.227356492691962675e-02,-8.810760645653680639e-03,3.717175438112000907e-01,-1.520718893927100746e-01,7.407176961239887447e-01,-1.930679167295249188e-01,-3.490656931085965864e-01,3.098756273304061754e-02,-1.457753668239319261e-02,-1.996643096951093710e-02,3.090169943702681526e-02,-1.100000000000000006e-01,-7.465739561407672698e-01,-3.090169943702681526e-02,1.100000000000000006e-01,-6.134260438592328279e-01,5.084952753435411504e-02,-1.296556250607596994e-01,-4.199949879638530947e-01,4.915047246564609867e-02,9.034437493924028784e-02,-3.200050120361468964e-01
+-5.348385334554572879e-01,1.915338529926013666e-01,-1.124415214082265246e-01,-1.318858593763097033e-02,4.184620240924362689e-01,-1.189504629193311736e-01,7.942577162638763122e-01,-1.744406738130284962e-01,-3.490659808192873026e-01,4.719277263908137204e-02,-1.166413896002700679e-02,-1.985221780111679976e-02,1.564344650353494126e-02,-1.100000000000000006e-01,-7.491381838417138228e-01,-1.564344650353494126e-02,1.100000000000000006e-01,-6.108618161582862749e-01,4.145394140451300752e-02,-1.288355348389048638e-01,-4.194902128545697773e-01,5.854605859548719926e-02,9.116446516109513731e-02,-3.205097871454302139e-01
+-5.953693400297767058e-01,1.421519329426661482e-01,-1.297194457240789245e-01,-1.591602986316467683e-02,4.543397535398691067e-01,-8.632316183484016470e-02,8.301158477203458563e-01,-1.582451059994096076e-01,-3.490659988012054238e-01,6.451373185783500219e-02,-8.703821904275585442e-03,-1.924197278442633247e-02,-4.964489977705272150e-13,-1.100000000000000006e-01,-7.500000000000000000e-01,4.964489977705272150e-13,1.100000000000000006e-01,-6.100000000000000977e-01,3.226878760003522306e-02,-1.275516512377598555e-01,-4.177668244562069977e-01,6.773121239996497678e-02,9.244834876224014564e-02,-3.222331755437930489e-01
+-6.433256773745728019e-01,9.447163462160887426e-02,-1.426945809661687437e-01,-1.705646484155216511e-02,4.797609735123329333e-01,-5.475217720553325618e-02,8.476869101484615365e-01,-1.444180509875898355e-01,-3.459210837700303354e-01,8.251230611450409425e-02,-5.985677071161325108e-03,-1.815963020591847624e-02,-1.564344650451561514e-02,-1.100000000000000006e-01,-7.491381838416051320e-01,1.564344650451561514e-02,1.100000000000000006e-01,-6.108618161583949657e-01,2.352023509136483975e-02,-1.258355877325502414e-01,-4.148672583107305134e-01,7.647976490863535315e-02,9.416441226744974580e-02,-3.251327416892695887e-01
+-6.773332858462984829e-01,4.934908311015273608e-02,-1.498575406398212906e-01,-1.673834903912172628e-02,4.945905135248213624e-01,-2.485129274821403986e-02,8.412338040715557907e-01,-1.329767390239623981e-01,-3.118859117669905423e-01,1.008067836229545045e-01,-3.185372749416066213e-03,-1.664499566588349341e-02,-3.090169943797111546e-02,-1.100000000000000006e-01,-7.465739561405524416e-01,3.090169943797111546e-02,1.100000000000000006e-01,-6.134260438594476561e-01,1.542370227604651645e-02,-1.237295995020626094e-01,-4.108629113597503379e-01,8.457629772395365564e-02,9.627040049793739174e-02,-3.291370886402497642e-01
+-6.991592328524631750e-01,7.673188383799524337e-03,-1.516888329904642618e-01,-1.515302578478732072e-02,5.007475828907479443e-01,2.725583435993875724e-03,8.177541401310166602e-01,-1.240306783855624900e-01,-2.714130818267793677e-01,1.190744289971978342e-01,-7.917428048070385138e-04,-1.474786567652749958e-02,-4.539904997440295104e-02,-1.100000000000000006e-01,-7.423704566930259263e-01,4.539904997440295104e-02,1.100000000000000006e-01,-6.176295433069741714e-01,8.178552662845298138e-03,-1.212855429659057405e-01,-4.058523839148652224e-01,9.182144733715486007e-02,9.871445703409426065e-02,-3.341476160851348798e-01
+-7.098632864870938475e-01,-2.963590179980275102e-02,-1.487310921671951836e-01,-1.254818146280909340e-02,4.994660274917043230e-01,2.728787781548692309e-02,7.809684223223000155e-01,-1.178014005986521145e-01,-2.278042664160513653e-01,1.370588412571062398e-01,1.026656369196213671e-03,-1.252216408633054050e-02,-5.877852522965729132e-02,-1.100000000000000006e-01,-7.366311896060379061e-01,5.877852522965729132e-02,1.100000000000000006e-01,-6.233688103939621916e-01,1.963185880510726067e-03,-1.185635989073581947e-01,-3.999590517907549159e-01,9.803681411948941826e-02,1.014364010926418064e-01,-3.400409482092452418e-01
+-7.103901144864506190e-01,-6.161585822296224840e-02,-1.416878746223508567e-01,-9.217067174967879389e-03,4.917885642700023929e-01,4.810022722890625047e-02,7.340487569081276531e-01,-1.146525911130756858e-01,-1.832300851368593719e-01,1.545832616042132068e-01,2.367965080484616455e-03,-1.002054977255569662e-02,-7.071067811901464439e-02,-1.100000000000000006e-01,-7.294974746828064571e-01,7.071067811901464439e-02,1.100000000000000006e-01,-6.305025253171936406e-01,-3.069355113155244896e-03,-1.156307906227563437e-01,-3.933280283831641078e-01,1.030693551131553476e-01,1.043692093772436574e-01,-3.466719716168360499e-01
+-7.018536152207263124e-01,-8.723604095505337053e-02,-1.314589164204064964e-01,-5.483080760960085294e-03,4.787833981379983617e-01,6.436012173421482019e-02,6.803817301667498540e-01,-1.151334353456573978e-01,-1.398613826566753593e-01,1.715712081084570517e-01,3.411449538266759715e-03,-7.290000458981055025e-03,-8.090169943779522421e-02,-1.100000000000000006e-01,-7.211449676601836556e-01,8.090169943779522421e-02,1.100000000000000006e-01,-6.388550323398164421e-01,-6.795152456843145394e-03,-1.125593335854995075e-01,-3.861225914954921623e-01,1.067951524568432203e-01,1.074406664145004936e-01,-3.538774085045079953e-01
+-6.854951399737672091e-01,-1.053548694617613968e-01,-1.190053900474730836e-01,-1.678016517473838575e-03,4.615221586750553051e-01,7.516005639123696236e-02,6.233272708723239797e-01,-1.200377521515627044e-01,-9.974724695595088564e-02,1.880758526941621045e-01,4.366040839626706554e-03,-4.369022085587547649e-03,-8.910065241906987843e-02,-1.100000000000000006e-01,-7.117793349814480752e-01,8.910065241906987843e-02,1.100000000000000006e-01,-6.482206650185520225e-01,-9.122464654738884904e-03,-1.094248572614264642e-01,-3.785201628973876575e-01,1.091224646547389321e-01,1.105751427385735369e-01,-3.614798371026125001e-01
+-6.625800878594074739e-01,-1.146620808152394866e-01,-1.052190971440486594e-01,1.890103041032798002e-03,4.410041489831577621e-01,7.943570573498917597e-02,5.658964679596539815e-01,-1.304791654644176790e-01,-6.461523056165470458e-02,2.043186049002501115e-01,5.419406970923302570e-03,-1.287435098035318980e-03,-9.510565162967470065e-02,-1.100000000000000006e-01,-7.016311896059030939e-01,9.510565162967470065e-02,1.100000000000000006e-01,-6.583688103940970038e-01,-9.993985556623910527e-03,-1.063045428603664189e-01,-3.707079396119499215e-01,1.099939855566239161e-01,1.136954571396335822e-01,-3.692920603880502362e-01
+-6.342675291543129479e-01,-1.136141537206723229e-01,-9.083235138999060099e-02,4.987495030929616283e-03,4.180607698333361766e-01,7.590858215703588652e-02,5.104581687374994958e-01,-1.479745070388507333e-01,-3.567820158507988004e-02,2.207334564723102965e-01,6.698175941209445240e-03,1.929766589211245626e-03,-9.876883405959478723e-02,-1.100000000000000006e-01,-6.909504125524581486e-01,9.876883405959478723e-02,1.100000000000000006e-01,-6.690495874475419491e-01,-9.388255425481745187e-03,-1.032752228786032733e-01,-3.628782845037491489e-01,1.093882554254817230e-01,1.167247771213967278e-01,-3.771217154962510087e-01
+-6.015091030963577445e-01,-1.003892154371015533e-01,-7.639017381949245178e-02,7.536003586254588597e-03,3.932898026083738174e-01,6.304935679295022022e-02,4.585879697244079622e-01,-1.745055716391044620e-01,-1.353823766660568195e-02,2.380022910162893635e-01,8.248665217491126314e-03,5.252174634834496682e-03,-1.000000000000000056e-01,-1.100000000000000006e-01,-6.799999999996350075e-01,1.000000000000000056e-01,1.100000000000000006e-01,-6.800000000003650902e-01,-7.320189347443939454e-03,-1.004114892278244048e-01,-3.552239896666840591e-01,1.073201893474438895e-01,1.195885107721755963e-01,-3.847760103333160986e-01
+-5.650199172961909433e-01,-7.293045398840845850e-02,-6.227748628572895434e-02,9.739606996890014592e-03,3.670525667955084614e-01,3.912876259603174228e-02,4.111058022720807115e-01,-2.124776593406184633e-01,1.772078937707036866e-03,2.570391413972124006e-01,1.003981562879383872e-02,8.624325639809023863e-03,-9.876883405943184813e-02,-1.100000000000000006e-01,-6.690495874468218584e-01,9.876883405943184813e-02,1.100000000000000006e-01,-6.909504125531782392e-01,-3.840709972869962852e-03,-9.778385653469964800e-02,-3.479335292427928050e-01,1.038407099728698713e-01,1.222161434653003531e-01,-3.920664707572073526e-01
+-5.253190287846668527e-01,-2.922878092604770661e-02,-4.877165008258396023e-02,1.225311428528396557e-02,3.395273341121855526e-01,2.497974191886223952e-03,3.682489008894756499e-01,-2.643954788357930075e-01,1.064761765363436870e-02,2.788295816943602290e-01,1.198181587151156066e-02,1.193481551198224445e-02,-9.510565162935284700e-02,-1.100000000000000006e-01,-6.583688103934035585e-01,9.510565162935284700e-02,1.100000000000000006e-01,-7.016311896065965392e-01,9.645063683082835682e-04,-9.545702583674638142e-02,-3.411864185633618485e-01,9.903549363169161790e-02,1.245429741632536197e-01,-3.988135814366382537e-01
+-4.828051591270007270e-01,3.191699582691742698e-02,-3.609134981981554358e-02,1.631742097945916570e-02,3.107876914944091573e-01,-4.768801171629712121e-02,3.298837045287040803e-01,-3.319682847537407944e-01,1.374068819080018038e-02,3.039753575656514717e-01,1.395079121646188372e-02,1.498012027522859987e-02,-8.910065241859702057e-02,-1.100000000000000006e-01,-6.482206650179023200e-01,8.910065241859702057e-02,1.100000000000000006e-01,-7.117793349820977777e-01,6.977139302172224999e-03,-9.348829142805660519e-02,-3.351487938856954063e-01,9.302286069782764177e-02,1.265117085719433820e-01,-4.048512061143046958e-01
+-4.378336598920418155e-01,1.095522403438884129e-01,-2.442778464443251876e-02,2.363195767000327019e-02,2.808774127897243900e-01,-1.102372783077755214e-01,2.956860640205409285e-01,-4.144794111126721137e-01,1.181813277393189282e-02,3.318676187605722472e-01,1.581207081676453546e-02,1.744878856010368892e-02,-8.090169943718300560e-02,-1.100000000000000006e-01,-6.388550323392265806e-01,8.090169943718300560e-02,1.100000000000000006e-01,-7.211449676607735171e-01,1.404913785110545321e-02,-9.192613008362716942e-02,-3.299693215670851942e-01,8.595086214889438581e-02,1.280738699163728178e-01,-4.100306784329149079e-01
+-3.907770986514763067e-01,1.980260120116295319e-01,-1.395745259003986632e-02,3.546144753825467705e-02,2.498681818949498312e-01,-1.798060562191126088e-01,2.652653009977459231e-01,-5.040411986112444120e-01,5.665123502341874034e-03,3.478089728117041979e-01,1.743836329123111747e-02,1.886183327924961795e-02,-7.071067811827816407e-02,-1.100000000000000006e-01,-6.305025253166780530e-01,7.071067811827816407e-02,1.100000000000000006e-01,-7.294974746833220447e-01,2.200636594021561712e-02,-9.080900740027419982e-02,-3.257755374056984232e-01,7.799363405978421149e-02,1.291909925997258013e-01,-4.142244625943016234e-01
+-3.420655581750189356e-01,2.895443046036024759e-01,-4.841596824330439072e-03,5.160187264085661085e-02,2.178979182505602352e-01,-2.492728734076912200e-01,2.382376078096884175e-01,-5.905773675916773380e-01,-3.968751818186103467e-03,3.489874358007314936e-01,1.872202140062131578e-02,1.860051970965902191e-02,-5.877852522881349406e-02,-1.100000000000000006e-01,-6.233688103935330904e-01,5.877852522881349406e-02,1.100000000000000006e-01,-7.366311896064670073e-01,3.065289020542361770e-02,-9.016443064597944035e-02,-3.226707062859600073e-01,6.934710979457618663e-02,1.298355693540205469e-01,-4.173292937140400394e-01
+-2.922088815112641180e-01,3.793666227279646197e-01,2.782043068354166614e-03,7.120691346067237193e-02,1.851921758794596307e-01,-3.145830796568866439e-01,2.142641032471737650e-01,-6.714023036893977947e-01,-1.639386155563950925e-02,3.490610897375456823e-01,1.958198324590527603e-02,1.703940665423366030e-02,-4.539904997347492255e-02,-1.100000000000000006e-01,-6.176295433066432139e-01,4.539904997347492255e-02,1.100000000000000006e-01,-7.423704566933568838e-01,3.977580452314959797e-02,-9.000827143966134980e-02,-3.207312794543821233e-01,6.022419547685020635e-02,1.299917285603386374e-01,-4.192687205456179234e-01
+-2.418044428680487246e-01,4.622966703118678855e-01,8.810760645670021735e-03,9.227356492698469970e-02,1.520718893926066573e-01,-3.717175438113616281e-01,1.930679167294621912e-01,-7.407176961241809243e-01,-3.098756273308820794e-02,3.490656931085965864e-01,1.996643096951158242e-02,1.457753668238471502e-02,-3.090169943698053631e-02,-1.100000000000000006e-01,-6.134260438592222808e-01,3.090169943698053631e-02,1.100000000000000006e-01,-7.465739561407778169e-01,4.915047246567508243e-02,-9.034437493924207807e-02,-3.200050120361465633e-01,5.084952753432471495e-02,1.296556250607579230e-01,-4.199949879638534278e-01
+-1.915338529924455191e-01,5.348385334556627901e-01,1.318858593764204480e-02,1.124415214082849918e-01,1.189504629192284779e-01,-4.184620240925633894e-01,1.744406738129732903e-01,-7.942577162640137578e-01,-4.719277263913298354e-02,3.490659808192873026e-01,1.985221780111572770e-02,1.166413896001775377e-02,-1.564344650348688248e-02,-1.100000000000000006e-01,-6.108618161582809458e-01,1.564344650348688248e-02,1.100000000000000006e-01,-7.491381838417191519e-01,5.854605859551589853e-02,-9.116446516109839859e-02,-3.205097871454336556e-01,4.145394140448390580e-02,1.288355348389015886e-01,-4.194902128545663356e-01
+-1.421519329425151579e-01,5.953693400299451266e-01,1.591602986317063040e-02,1.297194457241263865e-01,8.632316183474048055e-02,-4.543397535399635867e-01,1.582451059993625619e-01,-8.301158477204299002e-01,-6.451373185788758513e-02,3.490659988012054238e-01,1.924197278442377201e-02,8.703821904266486817e-03,5.451089287021025411e-13,-1.100000000000000006e-01,-6.100000000000000977e-01,-5.451089287021025411e-13,1.100000000000000006e-01,-7.500000000000000000e-01,6.773121239999267684e-02,-9.244834876224482245e-02,-3.222331755438002099e-01,3.226878760000713442e-02,1.275516512377551648e-01,-4.177668244561997257e-01
+-9.447163462146387913e-02,6.433256773746979240e-01,1.705646484155339676e-02,1.426945809661996079e-01,5.475217720543715944e-02,-4.797609735123936625e-01,1.444180509875497842e-01,-8.476869101484764135e-01,-8.251230611456013275e-02,3.459210837699460694e-01,1.815963020591444821e-02,5.985677071153701866e-03,1.564344650456367739e-02,-1.100000000000000006e-01,-6.108618161584002948e-01,-1.564344650456367739e-02,1.100000000000000006e-01,-7.491381838415998029e-01,7.647976490866136012e-02,-9.416441226745568549e-02,-3.251327416892802469e-01,2.352023509133845461e-02,1.258355877325443017e-01,-4.148672583107196887e-01
+-4.934908311001280634e-02,6.773332858463861905e-01,1.673834903911860725e-02,1.498575406398351684e-01,2.485129274812163114e-02,-4.945905135248536144e-01,1.329767390239290636e-01,-8.412338040715050536e-01,-1.008067836230169545e-01,3.118859117668710823e-01,1.664499566587937518e-02,3.185372749407735637e-03,3.090169943801875097e-02,-1.100000000000000006e-01,-6.134260438594584253e-01,-3.090169943801875097e-02,1.100000000000000006e-01,-7.465739561405416724e-01,8.457629772397803891e-02,-9.627040049794467758e-02,-3.291370886402640861e-01,1.542370227602179317e-02,1.237295995020553235e-01,-4.108629113597357940e-01
+-7.673188383672308391e-03,6.991592328525143563e-01,1.515302578478057265e-02,1.516888329904621524e-01,-2.725583436077817258e-03,-5.007475828907551607e-01,1.240306783855378847e-01,-8.177541401309185165e-01,-1.190744289972584385e-01,2.714130818266456413e-01,1.474786567652162060e-02,7.917428048005000158e-04,4.539904997444757506e-02,-1.100000000000000006e-01,-6.176295433069900476e-01,-4.539904997444757506e-02,1.100000000000000006e-01,-7.423704566930100501e-01,9.182144733717625962e-02,-9.871445703410253181e-02,-3.341476160851522548e-01,8.178552662823600217e-03,1.212855429658974693e-01,-4.058523839148476253e-01
+2.963590179991104634e-02,7.098632864871107229e-01,1.254818146279969987e-02,1.487310921671792796e-01,-2.728787781555787675e-02,-4.994660274916898346e-01,1.178014005986370155e-01,-7.809684223221687871e-01,-1.370588412571614456e-01,2.278042664159131703e-01,1.252216408632315578e-02,-1.026656369200978740e-03,5.877852522969664872e-02,-1.100000000000000006e-01,-6.233688103939822867e-01,-5.877852522969664872e-02,1.100000000000000006e-01,-7.366311896060178110e-01,9.803681411950677937e-02,-1.014364010926506049e-01,-3.400409482092645597e-01,1.963185880493101276e-03,1.185635989073493962e-01,-3.999590517907353204e-01
+6.161585822305260668e-02,7.103901144864371853e-01,9.217067174956771955e-03,1.416878746223234620e-01,-4.810022722896518249e-02,-4.917885642699695858e-01,1.146525911130705372e-01,-7.340487569079692243e-01,-1.545832616042666918e-01,1.832300851367215377e-01,1.002054977254613830e-02,-2.367965080488171770e-03,7.071067811904906131e-02,-1.100000000000000006e-01,-6.305025253172177324e-01,-7.071067811904906131e-02,1.100000000000000006e-01,-7.294974746827823653e-01,1.030693551131688784e-01,-1.043692093772529972e-01,-3.466719716168574217e-01,-3.069355113168970028e-03,1.156307906227470039e-01,-3.933280283831424029e-01
+8.723604095512225987e-02,7.018536152206868994e-01,5.483080760948240602e-03,1.314589164203706639e-01,-6.436012173425811889e-02,-4.787833981379505666e-01,1.151334353456645032e-01,-6.803817301665758821e-01,-1.715712081085089546e-01,1.398613826565418272e-01,7.290000458970993628e-03,-3.411449538269728261e-03,8.090169943782382633e-02,-1.100000000000000006e-01,-6.388550323398439756e-01,-8.090169943782382633e-02,1.100000000000000006e-01,-7.211449676601561221e-01,1.067951524568525601e-01,-1.074406664145101525e-01,-3.538774085045308659e-01,-6.795152456852623923e-03,1.125593335854898486e-01,-3.861225914954689586e-01
+1.053548694618049730e-01,6.854951399737055917e-01,1.678016517462189473e-03,1.190053900474318943e-01,-7.516005639126115134e-02,-4.615221586749961857e-01,1.200377521515852419e-01,-6.233272708721446786e-01,-1.880758526942121756e-01,9.974724695583259138e-02,4.369022085578207898e-03,-4.366040839629803036e-03,8.910065241909197187e-02,-1.100000000000000006e-01,-6.482206650185823316e-01,-8.910065241909197187e-02,1.100000000000000006e-01,-7.117793349814177661e-01,1.091224646547438726e-01,-1.105751427385832653e-01,-3.614798371026363144e-01,-9.122464654743894785e-03,1.094248572614167359e-01,-3.785201628973635102e-01
+1.146620808152536974e-01,6.625800878593258725e-01,-1.890103041043517725e-03,1.052190971440036815e-01,-7.943570573499121601e-02,-4.410041489830885397e-01,1.304791654644611443e-01,-5.658964679594742364e-01,-2.043186049003019034e-01,6.461523056155293876e-02,1.287435098025276232e-03,-5.419406970926896917e-03,9.510565162969017439e-02,-1.100000000000000006e-01,-6.583688103941303105e-01,-9.510565162969017439e-02,1.100000000000000006e-01,-7.016311896058697872e-01,1.099939855566243463e-01,-1.136954571396434355e-01,-3.692920603880751051e-01,-9.993985556624333799e-03,1.063045428603565656e-01,-3.707079396119247194e-01
+1.136141537206507568e-01,6.342675291542158034e-01,-4.987495030938596079e-03,9.083235138994467939e-02,-7.590858215701080935e-02,-4.180607698332601263e-01,1.479745070389194839e-01,-5.104581687373289656e-01,-2.207334564723633374e-01,3.567820158499906275e-02,-1.929766589221623176e-03,-6.698175941213912153e-03,9.876883405960262818e-02,-1.100000000000000006e-01,-6.690495874475765881e-01,-9.876883405960262818e-02,1.100000000000000006e-01,-6.909504125524235096e-01,1.093882554254774764e-01,-1.167247771214061647e-01,-3.771217154962756557e-01,-9.388255425477436134e-03,1.032752228785938364e-01,-3.628782845037241689e-01
+1.003892154370390893e-01,6.015091030962507190e-01,-7.536003586261728719e-03,7.639017381944826490e-02,-6.304935679289358497e-02,-3.932898026082950471e-01,1.745055716392038547e-01,-4.585879697242544739e-01,-2.380022910163444028e-01,1.353823766654805444e-02,-5.252174634844715938e-03,-8.248665217496309668e-03,1.000000000000000056e-01,-1.100000000000000006e-01,-6.800000000003991740e-01,-1.000000000000000056e-01,1.100000000000000006e-01,-6.799999999996009237e-01,1.073201893474353130e-01,-1.195885107721841312e-01,-3.847760103333391912e-01,-7.320189347435245020e-03,1.004114892278158699e-01,-3.552239896666606334e-01
+7.293045398829854642e-02,5.650199172960733707e-01,-9.739606996896781749e-03,6.227748628568626627e-02,-3.912876259593820599e-02,-3.670525667954255833e-01,2.124776593407573522e-01,-4.111058022719416560e-01,-2.570391413972755168e-01,-1.772078937743793488e-03,-8.624325639819439143e-03,-1.003981562879967433e-02,9.876883405942424310e-02,-1.100000000000000006e-01,-6.909504125532119900e-01,-9.876883405942424310e-02,1.100000000000000006e-01,-6.690495874467881077e-01,1.038407099728570759e-01,-1.222161434653080553e-01,-3.920664707572290575e-01,-3.840709972856987120e-03,9.778385653469194583e-02,-3.479335292427708226e-01
+2.922878092588350810e-02,5.253190287845403983e-01,-1.225311428529335042e-02,4.877165008254362444e-02,-2.497974191750119283e-03,-3.395273341120991772e-01,2.643954788359803576e-01,-3.682489008893514160e-01,-2.788295816944337258e-01,-1.064761765365207502e-02,-1.193481551199236830e-02,-1.198181587151759403e-02,9.510565162933780348e-02,-1.100000000000000006e-01,-7.016311896066288467e-01,-9.510565162933780348e-02,1.100000000000000006e-01,-6.583688103933712510e-01,9.903549363167490904e-02,-1.245429741632602949e-01,-3.988135814366580156e-01,9.645063683252214082e-04,9.545702583673970620e-02,-3.411864185633418645e-01
+-3.191699582713636990e-02,4.828051591268663345e-01,-1.631742097947597517e-02,3.609134981977814988e-02,4.768801171647517323e-02,-3.107876914943192848e-01,3.319682847539781045e-01,-3.298837045285938352e-01,-3.039753575657359597e-01,-1.374068819080095059e-02,-1.498012027523756666e-02,-1.395079121646773321e-02,8.910065241857492713e-02,-1.100000000000000006e-01,-7.117793349821280868e-01,-8.910065241857492713e-02,1.100000000000000006e-01,-6.482206650178720109e-01,9.302286069780743571e-02,-1.265117085719488776e-01,-4.048512061143220153e-01,6.977139302192722492e-03,9.348829142805112347e-02,-3.351487938856778648e-01
+-1.095522403441525627e-01,4.378336598918996514e-01,-2.363195767003290274e-02,2.442778464439819552e-02,1.102372783079862001e-01,-2.808774127896303541e-01,4.144794111129490588e-01,-2.956860640204417301e-01,-3.318676187606620087e-01,-1.181813277391871413e-02,-1.744878856011013515e-02,-1.581207081677009699e-02,8.090169943715440348e-02,-1.100000000000000006e-01,-7.211449676608010506e-01,-8.090169943715440348e-02,1.100000000000000006e-01,-6.388550323391990471e-01,8.595086214887118214e-02,-1.280738699163769811e-01,-4.100306784329293963e-01,1.404913785112898994e-02,9.192613008362300608e-02,-3.299693215670704838e-01
+-1.980260120119173017e-01,3.907770986513233735e-01,-3.546144753829916924e-02,1.395745259000853375e-02,1.798060562193350420e-01,-2.498681818948495781e-01,5.040411986115225229e-01,-2.652653009976543852e-01,-3.478089728117152446e-01,-5.665123502315337969e-03,-1.886183327925129022e-02,-1.743836329123607184e-02,7.071067811824274796e-02,-1.100000000000000006e-01,-7.294974746833468027e-01,-7.071067811824274796e-02,1.100000000000000006e-01,-6.305025253166532950e-01,7.799363405975781594e-02,-1.291909925997286046e-01,-4.142244625943132252e-01,2.200636594024237697e-02,9.080900740027138263e-02,-3.257755374056866549e-01
+-2.895443046038885804e-01,3.420655581748665020e-01,-5.160187264091320447e-02,4.841596824304442506e-03,2.492728734079042163e-01,-2.178979182504596768e-01,5.905773675919423482e-01,-2.382376078096100636e-01,-3.489874358007321598e-01,3.968751818220735486e-03,-1.860051970965603818e-02,-1.872202140062464298e-02,5.877852522877412972e-02,-1.100000000000000006e-01,-7.366311896064869913e-01,-5.877852522877412972e-02,1.100000000000000006e-01,-6.233688103935131064e-01,6.934710979454875024e-02,-1.298355693540217959e-01,-4.173292937140478109e-01,3.065289020545144960e-02,9.016443064597819135e-02,-3.226707062859520692e-01
+-3.793666227282359027e-01,2.922088815111092419e-01,-7.120691346073688976e-02,-2.782043068375300750e-03,3.145830796570787680e-01,-1.851921758793579065e-01,6.714023036896348273e-01,-2.142641032471048756e-01,-3.490610897375457933e-01,1.639386155568206896e-02,-1.703940665422730080e-02,-1.958198324590727790e-02,4.539904997343156140e-02,-1.100000000000000006e-01,-7.423704566933724269e-01,-4.539904997343156140e-02,1.100000000000000006e-01,-6.176295433066276708e-01,6.022419547682163893e-02,-1.299917285603383599e-01,-4.192687205456220312e-01,3.977580452317856785e-02,9.000827143966162736e-02,-3.207312794543779599e-01
+-4.622966703121121346e-01,2.418044428678942648e-01,-9.227356492705048041e-02,-8.810760645685889250e-03,3.717175438115246089e-01,-1.520718893925052384e-01,7.407176961243761015e-01,-1.930679167294028220e-01,-3.490656931085965864e-01,3.098756273313700571e-02,-1.457753668237595293e-02,-1.996643096951221386e-02,3.090169943693425736e-02,-1.100000000000000006e-01,-7.465739561407882530e-01,-3.090169943693425736e-02,1.100000000000000006e-01,-6.134260438592118447e-01,5.084952753429573119e-02,-1.296556250607561189e-01,-4.199949879638537609e-01,4.915047246570448253e-02,9.034437493924388218e-02,-3.200050120361462302e-01
+-5.348385334558715121e-01,1.915338529922926969e-01,-1.124415214083447218e-01,-1.318858593765286254e-02,4.184620240926928969e-01,-1.189504629191273782e-01,7.942577162641559774e-01,-1.744406738129215262e-01,-3.490659808192873026e-01,4.719277263918413706e-02,-1.166413896000837412e-02,-1.985221780111452380e-02,1.564344650343882023e-02,-1.100000000000000006e-01,-7.491381838417244809e-01,-1.564344650343882023e-02,1.100000000000000006e-01,-6.108618161582756168e-01,4.145394140445521347e-02,-1.288355348388983135e-01,-4.194902128545628939e-01,5.854605859554500025e-02,9.116446516110167375e-02,-3.205097871454371528e-01
+-5.953693400301141025e-01,1.421519329423653055e-01,-1.297194457241742094e-01,-1.591602986317646254e-02,4.543397535400588438e-01,-8.632316183464129600e-02,8.301158477205140551e-01,-1.582451059993168763e-01,-3.490659988012054238e-01,6.451373185794243015e-02,-8.703821904257528705e-03,-1.924197278442102074e-02,-5.937688596336779682e-13,-1.100000000000000006e-01,-7.500000000000000000e-01,5.937688596336779682e-13,1.100000000000000006e-01,-6.100000000000000977e-01,3.226878759997944129e-02,-1.275516512377505018e-01,-4.177668244561926203e-01,6.773121240002075161e-02,9.244834876224948539e-02,-3.222331755438074263e-01
+-6.433256773748279311e-01,9.447163462131580314e-02,-1.426945809662317488e-01,-1.705646484155465617e-02,4.797609735124567787e-01,-5.475217720533897409e-02,8.476869101484927338e-01,-1.444180509875102048e-01,-3.459210837698616370e-01,8.251230611462061215e-02,-5.985677071145920763e-03,-1.815963020591023630e-02,-1.564344650461314476e-02,-1.100000000000000006e-01,-7.491381838415942518e-01,1.564344650461314476e-02,1.100000000000000006e-01,-6.108618161584058459e-01,2.352023509131167742e-02,-1.258355877325381955e-01,-4.148672583107086975e-01,7.647976490868851895e-02,9.416441226746180559e-02,-3.251327416892913491e-01
+-6.773332858464722328e-01,4.934908310987871916e-02,-1.498575406398488241e-01,-1.673834903911554720e-02,4.945905135248855888e-01,-2.485129274803293473e-02,8.412338040714562037e-01,-1.329767390238984492e-01,-3.118859117667526770e-01,1.008067836230734232e-01,-3.185372749399391183e-03,-1.664499566587362284e-02,-3.090169943806502298e-02,-1.100000000000000006e-01,-7.465739561405311253e-01,3.090169943806502298e-02,1.100000000000000006e-01,-6.134260438594689724e-01,1.542370227599810378e-02,-1.237295995020482459e-01,-4.108629113597218607e-01,8.457629772400207524e-02,9.627040049795175525e-02,-3.291370886402782414e-01
+-6.991592328525644273e-01,7.673188383550142225e-03,-1.516888329904602095e-01,-1.515302578477391304e-02,5.007475828907621551e-01,2.725583436158523533e-03,8.177541401308239255e-01,-1.240306783855149586e-01,-2.714130818265144129e-01,1.190744289973148934e-01,-7.917428047939386411e-04,-1.474786567651512233e-02,-4.539904997449092927e-02,-1.100000000000000006e-01,-7.423704566929945070e-01,4.539904997449092927e-02,1.100000000000000006e-01,-6.176295433070055907e-01,8.178552662802818229e-03,-1.212855429658894341e-01,-4.058523839148308054e-01,9.182144733719732610e-02,9.871445703411056705e-02,-3.341476160851692967e-01
+-7.098632864871274872e-01,-2.963590180001839103e-02,-1.487310921671633479e-01,-1.254818146279040175e-02,4.994660274916754017e-01,2.728787781562822326e-02,7.809684223220371146e-01,-1.178014005986223606e-01,-2.278042664157740316e-01,1.370588412572148751e-01,1.026656369205992091e-03,-1.252216408631601219e-02,-5.877852522973601307e-02,-1.100000000000000006e-01,-7.366311896059978270e-01,5.877852522973601307e-02,1.100000000000000006e-01,-6.233688103940022707e-01,1.963185880475733225e-03,-1.185635989073406116e-01,-3.999590517907159470e-01,9.803681411952439029e-02,1.014364010926593895e-01,-3.400409482092841551e-01
+-7.103901144864239736e-01,-6.161585822314188943e-02,-1.416878746222960950e-01,-9.217067174945582989e-03,4.917885642699368898e-01,4.810022722902269898e-02,7.340487569078114616e-01,-1.146525911130663322e-01,-1.832300851365830097e-01,1.545832616043190944e-01,2.367965080491920074e-03,-1.002054977253801112e-02,-7.071067811908346434e-02,-1.100000000000000006e-01,-7.294974746827582734e-01,7.071067811908346434e-02,1.100000000000000006e-01,-6.305025253172418243e-01,-3.069355113182493933e-03,-1.156307906227376642e-01,-3.933280283831210866e-01,1.030693551131826036e-01,1.043692093772623369e-01,-3.466719716168790710e-01
+-7.018536152206475975e-01,-8.723604095519021939e-02,-1.314589164203350813e-01,-5.483080760936409788e-03,4.787833981379030490e-01,6.436012173429971062e-02,6.803817301664030204e-01,-1.151334353456728438e-01,-1.398613826564115148e-01,1.715712081085598306e-01,3.411449538272713720e-03,-7.290000458963625390e-03,-8.090169943785241458e-02,-1.100000000000000006e-01,-7.211449676601285885e-01,8.090169943785241458e-02,1.100000000000000006e-01,-6.388550323398715092e-01,-6.795152456861970613e-03,-1.125593335854802035e-01,-3.861225914954460881e-01,1.067951524568620386e-01,1.074406664145197976e-01,-3.538774085045540696e-01
+-6.854951399736428641e-01,-1.053548694618491044e-01,-1.190053900473898446e-01,-1.678016517450323314e-03,4.615221586749357896e-01,7.516005639128557625e-02,6.233272708719619359e-01,-1.200377521516093893e-01,-9.974724695571313138e-02,1.880758526942645503e-01,4.366040839632850945e-03,-4.369022085568599265e-03,-8.910065241911470368e-02,-1.100000000000000006e-01,-7.117793349813865689e-01,8.910065241911470368e-02,1.100000000000000006e-01,-6.482206650186135288e-01,-9.122464654748974056e-03,-1.094248572614067161e-01,-3.785201628973390298e-01,1.091224646547490212e-01,1.105751427385932850e-01,-3.614798371026611279e-01
+-6.625800878592457144e-01,-1.146620808152672005e-01,-1.052190971439596751e-01,1.890103041053948184e-03,4.410041489830207606e-01,7.943570573499303400e-02,5.658964679592980440e-01,-1.304791654645039434e-01,-6.461523056145299093e-02,2.043186049003531402e-01,5.419406970930415804e-03,-1.287435098015625532e-03,-9.510565162970521791e-02,-1.100000000000000006e-01,-7.016311896058373687e-01,9.510565162970521791e-02,1.100000000000000006e-01,-6.583688103941627290e-01,-9.993985556624743194e-03,-1.063045428603470038e-01,-3.707079396119005721e-01,1.099939855566247487e-01,1.136954571396529973e-01,-3.692920603880995856e-01
+-6.342675291541203242e-01,-1.136141537206297458e-01,-9.083235138989961821e-02,4.987495030947319136e-03,4.180607698331856859e-01,7.590858215698628730e-02,5.104581687371615439e-01,-1.479745070389864858e-01,-3.567820158491948057e-02,2.207334564724150183e-01,6.698175941218274115e-03,1.929766589231795160e-03,-9.876883405961023321e-02,-1.100000000000000006e-01,-6.909504125523898699e-01,9.876883405961023321e-02,1.100000000000000006e-01,-6.690495874476102278e-01,-9.388255425473314431e-03,-1.032752228785846632e-01,-3.628782845037002991e-01,1.093882554254732853e-01,1.167247771214153379e-01,-3.771217154962998586e-01
+-6.015091030961425833e-01,-1.003892154369770695e-01,-7.639017381940366169e-02,7.536003586268866239e-03,3.932898026082156662e-01,6.304935679283729666e-02,4.585879697240995423e-01,-1.745055716393025813e-01,-1.353823766648989610e-02,2.380022910164006356e-01,8.248665217501588431e-03,5.252174634855436529e-03,-1.000000000000000056e-01,-1.100000000000000006e-01,-6.799999999995668398e-01,1.000000000000000056e-01,1.100000000000000006e-01,-6.800000000004332579e-01,-7.320189347426682425e-03,-1.004114892278073351e-01,-3.552239896666375407e-01,1.073201893474266255e-01,1.195885107721926660e-01,-3.847760103333626169e-01
+-5.650199172959545768e-01,-7.293045398818900904e-02,-6.227748628564322431e-02,9.739606996903607886e-03,3.670525667953420945e-01,3.912876259584487787e-02,4.111058022718012683e-01,-2.124776593408957137e-01,1.772078937781107824e-03,2.570391413973384664e-01,1.003981562880553249e-02,8.624325639830027895e-03,-9.876883405941662419e-02,-1.100000000000000006e-01,-6.690495874467544679e-01,9.876883405941662419e-02,1.100000000000000006e-01,-6.909504125532456298e-01,-3.840709972844198739e-03,-9.778385653468422978e-02,-3.479335292427491177e-01,1.038407099728441141e-01,1.222161434653157713e-01,-3.920664707572510399e-01
+-5.253190287844121675e-01,-2.922878092572214759e-02,-4.877165008250278905e-02,1.225311428530284630e-02,3.395273341120115251e-01,2.497974191616288836e-03,3.682489008892247395e-01,-2.643954788361642105e-01,1.064761765367062962e-02,2.788295816945061123e-01,1.198181587152373495e-02,1.193481551200233255e-02,-9.510565162932277383e-02,-1.100000000000000006e-01,-6.583688103933388325e-01,9.510565162932277383e-02,1.100000000000000006e-01,-7.016311896066612652e-01,9.645063683419233258e-04,-9.545702583673303099e-02,-3.411864185633221025e-01,9.903549363165795039e-02,1.245429741632669701e-01,-3.988135814366780552e-01
+-4.828051591267253917e-01,3.191699582735582630e-02,-3.609134981973881329e-02,1.631742097949304138e-02,3.107876914942246938e-01,-4.768801171665389138e-02,3.298837045284763736e-01,-3.319682847542142490e-01,1.374068819080319012e-02,3.039753575658197815e-01,1.395079121647408577e-02,1.498012027524637212e-02,-8.910065241855219531e-02,-1.100000000000000006e-01,-6.482206650178408136e-01,8.910065241855219531e-02,1.100000000000000006e-01,-7.117793349821592841e-01,6.977139302213518357e-03,-9.348829142804547521e-02,-3.351487938856600457e-01,9.302286069778634148e-02,1.265117085719545120e-01,-4.048512061143401120e-01
+-4.378336598917509370e-01,1.095522403444191134e-01,-2.442778464436237695e-02,2.363195767006283018e-02,2.808774127895317663e-01,-1.102372783081988911e-01,2.956860640203363699e-01,-4.144794111132272807e-01,1.181813277390597432e-02,3.318676187607527139e-01,1.581207081677584933e-02,1.744878856011669241e-02,-8.090169943712496869e-02,-1.100000000000000006e-01,-6.388550323391706254e-01,8.090169943712496869e-02,1.100000000000000006e-01,-7.211449676608294723e-01,1.404913785115288749e-02,-9.192613008361871785e-02,-3.299693215670556068e-01,8.595086214884695153e-02,1.280738699163812833e-01,-4.100306784329444953e-01
+-3.907770986511737155e-01,1.980260120121973000e-01,-1.395745258997792282e-02,3.546144753834255120e-02,2.498681818947512678e-01,-1.798060562195518408e-01,2.652653009975642906e-01,-5.040411986117940835e-01,5.665123502290968574e-03,3.478089728117264023e-01,1.743836329124065151e-02,1.886183327925303882e-02,-7.071067811820834492e-02,-1.100000000000000006e-01,-6.305025253166292032e-01,7.071067811820834492e-02,1.100000000000000006e-01,-7.294974746833708945e-01,2.200636594026801618e-02,-9.080900740026863482e-02,-3.257755374056753861e-01,7.799363405973180896e-02,1.291909925997313524e-01,-4.142244625943246605e-01
+-3.420655581747136798e-01,2.895443046041730195e-01,-4.841596824278499717e-03,5.160187264096970094e-02,2.178979182503595069e-01,-2.492728734081162412e-01,2.382376078095314320e-01,-5.905773675922061372e-01,-3.968751818254649330e-03,3.489874358007328814e-01,1.872202140062789039e-02,1.860051970965296078e-02,-5.877852522873475843e-02,-1.100000000000000006e-01,-6.233688103934930114e-01,5.877852522873475843e-02,1.100000000000000006e-01,-7.366311896065070863e-01,3.065289020547888946e-02,-9.016443064597694235e-02,-3.226707062859442976e-01,6.934710979452091140e-02,1.298355693540230449e-01,-4.173292937140557490e-01
+-2.922088815109539217e-01,3.793666227285064640e-01,2.782043068396382410e-03,7.120691346080149087e-02,1.851921758792559602e-01,-3.145830796572709476e-01,2.142641032470354312e-01,-6.714023036898716379e-01,-1.639386155572295986e-02,3.490610897375457933e-01,1.958198324590906467e-02,1.703940665422076436e-02,-4.539904997338820719e-02,-1.100000000000000006e-01,-6.176295433066122387e-01,4.539904997338820719e-02,1.100000000000000006e-01,-7.423704566933878590e-01,3.977580452320713528e-02,-9.000827143966190491e-02,-3.207312794543738521e-01,6.022419547679266905e-02,1.299917285603380823e-01,-4.192687205456261945e-01
+-2.418044428677372515e-01,4.622966703123533860e-01,8.810760645702082894e-03,9.227356492711534519e-02,1.520718893924017101e-01,-3.717175438116857578e-01,1.930679167293402054e-01,-7.407176961245672819e-01,-3.098756273318304180e-02,3.490656931085966419e-01,1.996643096951223467e-02,1.457753668236735911e-02,-3.090169943688798188e-02,-1.100000000000000006e-01,-6.134260438592012976e-01,3.090169943688798188e-02,1.100000000000000006e-01,-7.465739561407988001e-01,4.915047246573346629e-02,-9.034437493924567242e-02,-3.200050120361458417e-01,5.084952753426633110e-02,1.296556250607543148e-01,-4.199949879638541494e-01
+-1.915338529921318811e-01,5.348385334560818993e-01,1.318858593766433947e-02,1.124415214084043824e-01,1.189504629190210744e-01,-4.184620240928227930e-01,1.744406738128644885e-01,-7.942577162642957544e-01,-4.719277263923830207e-02,3.490659808192873026e-01,1.985221780111317419e-02,1.166413895999889386e-02,-1.564344650338935980e-02,-1.100000000000000006e-01,-6.108618161582701767e-01,1.564344650338935980e-02,1.100000000000000006e-01,-7.491381838417299210e-01,5.854605859557453218e-02,-9.116446516110504605e-02,-3.205097871454406500e-01,4.145394140442526520e-02,1.288355348388949551e-01,-4.194902128545592856e-01
+-1.421519329422087363e-01,5.953693400302859651e-01,1.591602986318272836e-02,1.297194457242226151e-01,8.632316183453754566e-02,-4.543397535401555998e-01,1.582451059992678877e-01,-8.301158477205975439e-01,-6.451373185800103605e-02,3.490659988012054793e-01,1.924197278441832498e-02,8.703821904248551511e-03,6.438498760367735148e-13,-1.100000000000000006e-01,-6.100000000000000977e-01,-6.438498760367735148e-13,1.100000000000000006e-01,-7.500000000000000000e-01,6.773121240004927046e-02,-9.244834876225428710e-02,-3.222331755438148093e-01,3.226878759995054080e-02,1.275516512377457001e-01,-4.177668244561851818e-01
+-9.447163462117083577e-02,6.433256773749529422e-01,1.705646484155580109e-02,1.426945809662626130e-01,5.475217720524291898e-02,-4.797609735125174524e-01,1.444180509874702090e-01,-8.476869101485073887e-01,-8.251230611467678944e-02,3.459210837697769270e-01,1.815963020590604174e-02,5.985677071138354767e-03,1.564344650466120354e-02,-1.100000000000000006e-01,-6.108618161584111750e-01,-1.564344650466120354e-02,1.100000000000000006e-01,-7.491381838415889227e-01,7.647976490871452593e-02,-9.416441226746774529e-02,-3.251327416893020072e-01,2.352023509128529574e-02,1.258355877325322558e-01,-4.148672583106979284e-01
+-4.934908310974325113e-02,6.773332858465577200e-01,1.673834903911248714e-02,1.498575406398623966e-01,2.485129274794312809e-02,-4.945905135249170081e-01,1.329767390238657254e-01,-8.412338040714071319e-01,-1.008067836231286429e-01,3.118859117666323844e-01,1.664499566586888704e-02,3.185372749390855476e-03,3.090169943811130193e-02,-1.100000000000000006e-01,-6.134260438594795195e-01,-3.090169943811130193e-02,1.100000000000000006e-01,-7.465739561405205782e-01,8.457629772402576462e-02,-9.627040049795883292e-02,-3.291370886402921192e-01,1.542370227597406745e-02,1.237295995020411682e-01,-4.108629113597077609e-01
+-7.673188383426716649e-03,6.991592328526140543e-01,1.515302578476721701e-02,1.516888329904580723e-01,-2.725583436240009566e-03,-5.007475828907689275e-01,1.240306783854899508e-01,-8.177541401307284463e-01,-1.190744289973686282e-01,2.714130818263810196e-01,1.474786567650874722e-02,7.917428047873928789e-04,4.539904997453429042e-02,-1.100000000000000006e-01,-6.176295433070210228e-01,-4.539904997453429042e-02,1.100000000000000006e-01,-7.423704566929790749e-01,9.182144733721812890e-02,-9.871445703411860229e-02,-3.341476160851861721e-01,8.178552662781730931e-03,1.212855429658813988e-01,-4.058523839148137080e-01
+2.963590180012676961e-02,7.098632864871443626e-01,1.254818146278100476e-02,1.487310921671474717e-01,-2.728787781569924631e-02,-4.994660274916609688e-01,1.178014005986069562e-01,-7.809684223219055532e-01,-1.370588412572697479e-01,2.278042664156362529e-01,1.252216408630863094e-02,-1.026656369210696444e-03,5.877852522977538435e-02,-1.100000000000000006e-01,-6.233688103940222547e-01,-5.877852522977538435e-02,1.100000000000000006e-01,-7.366311896059778430e-01,9.803681411954176528e-02,-1.014364010926681881e-01,-3.400409482093035285e-01,1.963185880458115373e-03,1.185635989073318131e-01,-3.999590517906963516e-01
+6.161585822323466244e-02,7.103901144864107620e-01,9.217067174934184121e-03,1.416878746222681174e-01,-4.810022722908183224e-02,-4.917885642699034721e-01,1.146525911130615860e-01,-7.340487569076495911e-01,-1.545832616043747720e-01,1.832300851364430105e-01,1.002054977253109477e-02,-2.367965080495453706e-03,7.071067811911888046e-02,-1.100000000000000006e-01,-6.305025253172665822e-01,-7.071067811911888046e-02,1.100000000000000006e-01,-7.294974746827335155e-01,1.030693551131965230e-01,-1.043692093772719542e-01,-3.466719716169011090e-01,-3.069355113196607643e-03,1.156307906227280469e-01,-3.933280283830987711e-01
+8.723604095526087121e-02,7.018536152206072964e-01,5.483080760924230294e-03,1.314589164202984717e-01,-6.436012173434355055e-02,-4.787833981378543102e-01,1.151334353456807680e-01,-6.803817301662247186e-01,-1.715712081086137875e-01,1.398613826562782603e-01,7.290000458954543246e-03,-3.411449538275650173e-03,8.090169943788184936e-02,-1.100000000000000006e-01,-6.388550323398999309e-01,-8.090169943788184936e-02,1.100000000000000006e-01,-7.211449676601001668e-01,1.067951524568716698e-01,-1.074406664145297341e-01,-3.538774085045776063e-01,-6.795152456871726698e-03,1.125593335854702670e-01,-3.861225914954222183e-01
+1.053548694618926390e-01,6.854951399735809137e-01,1.678016517438717797e-03,1.190053900473487941e-01,-7.516005639130980687e-02,-4.615221586748773364e-01,1.200377521516321072e-01,-6.233272708717825239e-01,-1.880758526943140940e-01,9.974724695559374077e-02,4.369022085559251707e-03,-4.366040839635674208e-03,8.910065241913678324e-02,-1.100000000000000006e-01,-6.482206650186439489e-01,-8.910065241913678324e-02,1.100000000000000006e-01,-7.117793349813561488e-01,1.091224646547539479e-01,-1.105751427386030133e-01,-3.614798371026849422e-01,-9.122464654753983937e-03,1.094248572613969878e-01,-3.785201628973148824e-01
+1.146620808152809812e-01,6.625800878591655563e-01,-1.890103041064369101e-03,1.052190971439156408e-01,-7.943570573499500465e-02,-4.410041489829529260e-01,1.304791654645458820e-01,-5.658964679591215186e-01,-2.043186049004029337e-01,6.461523056135284881e-02,1.287435098005714840e-03,-5.419406970934133316e-03,9.510565162972024755e-02,-1.100000000000000006e-01,-6.583688103941951475e-01,-9.510565162972024755e-02,1.100000000000000006e-01,-7.016311896058049502e-01,1.099939855566251651e-01,-1.136954571396625591e-01,-3.692920603881237329e-01,-9.993985556625159528e-03,1.063045428603374420e-01,-3.707079396118760917e-01
+1.136141537206082630e-01,6.342675291540257332e-01,-4.987495030956094234e-03,9.083235138985495949e-02,-7.590858215696148770e-02,-4.180607698331118560e-01,1.479745070390539874e-01,-5.104581687369953436e-01,-2.207334564724670878e-01,3.567820158484039800e-02,-1.929766589242024608e-03,-6.698175941222667303e-03,9.876883405961783824e-02,-1.100000000000000006e-01,-6.690495874476438676e-01,-9.876883405961783824e-02,1.100000000000000006e-01,-6.909504125523562301e-01,1.093882554254691497e-01,-1.167247771214244972e-01,-3.771217154963237839e-01,-9.388255425469123339e-03,1.032752228785755039e-01,-3.628782845036760407e-01
+1.003892154369148970e-01,6.015091030960355578e-01,-7.536003586276040188e-03,7.639017381935948869e-02,-6.304935679278103611e-02,-3.932898026081368958e-01,1.745055716394014189e-01,-4.585879697239464425e-01,-2.380022910164563688e-01,1.353823766643236920e-02,-5.252174634865863952e-03,-8.248665217506775255e-03,1.000000000000000056e-01,-1.100000000000000006e-01,-6.800000000004672307e-01,-1.000000000000000056e-01,1.100000000000000006e-01,-6.799999999995328670e-01,1.073201893474180629e-01,-1.195885107722012147e-01,-3.847760103333856541e-01,-7.320189347417994929e-03,1.004114892277987864e-01,-3.552239896666141705e-01
+7.293045398807701529e-02,5.650199172958332294e-01,-9.739606996910591882e-03,6.227748628559910682e-02,-3.912876259575007176e-02,-3.670525667952563853e-01,2.124776593410369618e-01,-4.111058022716574945e-01,-2.570391413974033590e-01,-1.772078937819379293e-03,-8.624325639840562871e-03,-1.003981562881155372e-02,9.876883405940878324e-02,-1.100000000000000006e-01,-6.909504125532801577e-01,-9.876883405940878324e-02,1.100000000000000006e-01,-6.690495874467199400e-01,1.038407099728309302e-01,-1.222161434653236955e-01,-3.920664707572733554e-01,-3.840709972830841368e-03,9.778385653467630556e-02,-3.479335292427265247e-01
+2.922878092555576332e-02,5.253190287842810502e-01,-1.225311428531242024e-02,4.877165008246095446e-02,-2.497974191478680162e-03,-3.395273341119216526e-01,2.643954788363530595e-01,-3.682489008890955096e-01,-2.788295816945798311e-01,-1.064761765368927270e-02,-1.193481551201223435e-02,-1.198181587153004241e-02,9.510565162930728622e-02,-1.100000000000000006e-01,-7.016311896066946829e-01,-9.510565162930728622e-02,1.100000000000000006e-01,-6.583688103933054148e-01,9.903549363164076969e-02,-1.245429741632738535e-01,-3.988135814366983722e-01,9.645063683593607662e-04,9.545702583672614761e-02,-3.411864185633015079e-01
+-3.191699582757343695e-02,4.828051591265904996e-01,-1.631742097950982656e-02,3.609134981970124612e-02,4.768801171683087481e-02,-3.107876914941344326e-01,3.319682847544499493e-01,-3.298837045283652403e-01,-3.039753575659031593e-01,-1.374068819080414942e-02,-1.498012027525506308e-02,-1.395079121648007403e-02,8.910065241853010187e-02,-1.100000000000000006e-01,-7.117793349821897042e-01,-8.910065241853010187e-02,1.100000000000000006e-01,-6.482206650178103935e-01,9.302286069776613542e-02,-1.265117085719600076e-01,-4.048512061143574314e-01,6.977139302234015850e-03,9.348829142803997960e-02,-3.351487938856424487e-01
+-1.095522403446842208e-01,4.378336598916100497e-01,-2.363195767009255294e-02,2.442778464432848046e-02,1.102372783084102220e-01,-2.808774127894387296e-01,4.144794111135057246e-01,-2.956860640202389479e-01,-3.318676187608418093e-01,-1.181813277389261695e-02,-1.744878856012323579e-02,-1.581207081678115758e-02,8.090169943709636657e-02,-1.100000000000000006e-01,-7.211449676608570059e-01,-8.090169943709636657e-02,1.100000000000000006e-01,-6.388550323391430918e-01,8.595086214882374787e-02,-1.280738699163854466e-01,-4.100306784329589838e-01,1.404913785117641728e-02,9.192613008361455451e-02,-3.299693215670408963e-01
+-1.980260120124818779e-01,3.907770986510270550e-01,-3.546144753838668950e-02,1.395745258994792078e-02,1.798060562197720258e-01,-2.498681818946548450e-01,5.040411986120719723e-01,-2.652653009974779708e-01,-3.478089728117376711e-01,-5.665123502266281724e-03,-1.886183327925454456e-02,-1.743836329124496404e-02,7.071067811817392801e-02,-1.100000000000000006e-01,-7.294974746833949864e-01,-7.071067811817392801e-02,1.100000000000000006e-01,-6.305025253166051113e-01,7.799363405970616281e-02,-1.291909925997341002e-01,-4.142244625943359293e-01,2.200636594029402315e-02,9.080900740026590090e-02,-3.257755374056639508e-01
+-2.895443046044582913e-01,3.420655581745615237e-01,-5.160187264102619742e-02,4.841596824252617642e-03,2.492728734083284325e-01,-2.178979182502596146e-01,5.905773675924703703e-01,-2.382376078094534944e-01,-3.489874358007336030e-01,3.968751818289579722e-03,-1.860051970964992155e-02,-1.872202140063123840e-02,5.877852522869539409e-02,-1.100000000000000006e-01,-7.366311896065270703e-01,-5.877852522869539409e-02,1.100000000000000006e-01,-6.233688103934730274e-01,6.934710979449347501e-02,-1.298355693540242939e-01,-4.173292937140635206e-01,3.065289020550672136e-02,9.016443064597569335e-02,-3.226707062859364150e-01
+-3.793666227287835202e-01,2.922088815107937165e-01,-7.120691346086732709e-02,-2.782043068418311484e-03,3.145830796574672350e-01,-1.851921758791505168e-01,6.714023036901121122e-01,-2.142641032469634055e-01,-3.490610897375458488e-01,1.639386155576772960e-02,-1.703940665421415507e-02,-1.958198324591124348e-02,4.539904997334358316e-02,-1.100000000000000006e-01,-7.423704566934037352e-01,-4.539904997334358316e-02,1.100000000000000006e-01,-6.176295433065963625e-01,6.022419547676326201e-02,-1.299917285603378048e-01,-4.192687205456304134e-01,3.977580452323695170e-02,9.000827143966218247e-02,-3.207312794543695222e-01
+-4.622966703126022425e-01,2.418044428675759916e-01,-9.227356492718208347e-02,-8.810760645718729300e-03,3.717175438118515141e-01,-1.520718893922958503e-01,7.407176961247634583e-01,-1.930679167292766729e-01,-3.490656931085965864e-01,3.098756273323505575e-02,-1.457753668235871672e-02,-1.996643096951296326e-02,3.090169943684034637e-02,-1.100000000000000006e-01,-7.465739561408096803e-01,-3.090169943684034637e-02,1.100000000000000006e-01,-6.134260438591904174e-01,5.084952753423649385e-02,-1.296556250607524552e-01,-4.199949879638544825e-01,4.915047246576371986e-02,9.034437493924753204e-02,-3.200050120361455086e-01
+-5.348385334562896221e-01,1.915338529919779209e-01,-1.124415214084637238e-01,-1.318858593767526823e-02,4.184620240929513568e-01,-1.189504629189194751e-01,7.942577162644358646e-01,-1.744406738128116696e-01,-3.490659808192873026e-01,4.719277263929201605e-02,-1.166413895998959921e-02,-1.985221780111231724e-02,1.564344650334129755e-02,-1.100000000000000006e-01,-7.491381838417352501e-01,-1.564344650334129755e-02,1.100000000000000006e-01,-6.108618161582648476e-01,4.145394140439657288e-02,-1.288355348388916799e-01,-4.194902128545558440e-01,5.854605859560363390e-02,9.116446516110832121e-02,-3.205097871454441472e-01
+-5.953693400304553851e-01,1.421519329420592725e-01,-1.297194457242704380e-01,-1.591602986318859519e-02,4.543397535402509679e-01,-8.632316183443863866e-02,8.301158477206822539e-01,-1.582451059992226738e-01,-3.490659988012054238e-01,6.451373185805531207e-02,-8.703821904239537888e-03,-1.924197278441603515e-02,-6.925098069683489419e-13,-1.100000000000000006e-01,-7.500000000000000000e-01,6.925098069683489419e-13,1.100000000000000006e-01,-6.100000000000000977e-01,3.226878759992284074e-02,-1.275516512377410372e-01,-4.177668244561780209e-01,6.773121240007735910e-02,9.244834876225895004e-02,-3.222331755438220258e-01
+-6.433256773750795077e-01,9.447163462102797782e-02,-1.426945809662940323e-01,-1.705646484155693213e-02,4.797609735125790142e-01,-5.475217720514835573e-02,8.476869101485242641e-01,-1.444180509874321561e-01,-3.459210837696912733e-01,8.251230611473137078e-02,-5.985677071130575400e-03,-1.815963020590211432e-02,-1.564344650470926232e-02,-1.100000000000000006e-01,-7.491381838415835936e-01,1.564344650470926232e-02,1.100000000000000006e-01,-6.108618161584165041e-01,2.352023509125927836e-02,-1.258355877325262884e-01,-4.148672583106872147e-01,7.647976490874090760e-02,9.416441226747369886e-02,-3.251327416893128319e-01
+-6.773332858466437623e-01,4.934908310960910149e-02,-1.498575406398761356e-01,-1.673834903910938893e-02,4.945905135249489826e-01,-2.485129274785423392e-02,8.412338040713583931e-01,-1.329767390238349167e-01,-3.118859117665141456e-01,1.008067836231857084e-01,-3.185372749382586050e-03,-1.664499566586356838e-02,-3.090169943815758435e-02,-1.100000000000000006e-01,-7.465739561405100311e-01,3.090169943815758435e-02,1.100000000000000006e-01,-6.134260438594900666e-01,1.542370227595037807e-02,-1.237295995020341044e-01,-4.108629113596938276e-01,8.457629772404978707e-02,9.627040049796589671e-02,-3.291370886403062745e-01
+-6.991592328526656797e-01,7.673188383301009913e-03,-1.516888329904559074e-01,-1.515302578476043424e-02,5.007475828907763660e-01,2.725583436323192159e-03,8.177541401306311908e-01,-1.240306783854668721e-01,-2.714130818262479594e-01,1.190744289974281223e-01,-7.917428047807631994e-04,-1.474786567650131740e-02,-4.539904997457891445e-02,-1.100000000000000006e-01,-7.423704566929631987e-01,4.539904997457891445e-02,1.100000000000000006e-01,-6.176295433070368990e-01,8.178552662760338321e-03,-1.212855429658731415e-01,-4.058523839147963885e-01,9.182144733723981989e-02,9.871445703412685957e-02,-3.341476160852037136e-01
+-7.098632864871617931e-01,-2.963590180023716741e-02,-1.487310921671310682e-01,-1.254818146277143082e-02,4.994660274916462583e-01,2.728787781577162591e-02,7.809684223217708832e-01,-1.178014005985928703e-01,-2.278042664154960040e-01,1.370588412573285342e-01,1.026656369215646911e-03,-1.252216408630094091e-02,-5.877852522981590749e-02,-1.100000000000000006e-01,-7.366311896059571929e-01,5.877852522981590749e-02,1.100000000000000006e-01,-6.233688103940429048e-01,1.963185880440233844e-03,-1.185635989073227647e-01,-3.999590517906764231e-01,9.803681411955988967e-02,1.014364010926772364e-01,-3.400409482093236790e-01
+-7.103901144863978834e-01,-6.161585822332402151e-02,-1.416878746222408614e-01,-9.217067174923066278e-03,4.917885642698709980e-01,4.810022722913940424e-02,7.340487569074921614e-01,-1.146525911130576031e-01,-1.832300851363057870e-01,1.545832616044285068e-01,2.367965080499089686e-03,-1.002054977252287565e-02,-7.071067811915328349e-02,-1.100000000000000006e-01,-7.294974746827094236e-01,7.071067811915328349e-02,1.100000000000000006e-01,-6.305025253172906741e-01,-3.069355113210138486e-03,-1.156307906227187071e-01,-3.933280283830773993e-01,1.030693551132102342e-01,1.043692093772812940e-01,-3.466719716169227583e-01
+-7.018536152205677725e-01,-8.723604095532888625e-02,-1.314589164202626947e-01,-5.483080760912391674e-03,4.787833981378069592e-01,6.436012173438573902e-02,6.803817301660510797e-01,-1.151334353456889420e-01,-1.398613826561478368e-01,1.715712081086651075e-01,3.411449538278886300e-03,-7.290000458945858353e-03,-8.090169943791046536e-02,-1.100000000000000006e-01,-7.211449676600726333e-01,8.090169943791046536e-02,1.100000000000000006e-01,-6.388550323399274644e-01,-6.795152456881073388e-03,-1.125593335854606081e-01,-3.861225914953993477e-01,1.067951524568811483e-01,1.074406664145393930e-01,-3.538774085046007545e-01
+-6.854951399735190742e-01,-1.053548694619355353e-01,-1.190053900473076326e-01,-1.678016517427230458e-03,4.615221586748181060e-01,7.516005639133352401e-02,6.233272708716032229e-01,-1.200377521516554635e-01,-9.974724695547562692e-02,1.880758526943644149e-01,4.366040839638722984e-03,-4.369022085550061142e-03,-8.910065241915887668e-02,-1.100000000000000006e-01,-7.117793349813258397e-01,8.910065241915887668e-02,1.100000000000000006e-01,-6.482206650186742580e-01,-9.122464654758924429e-03,-1.094248572613872594e-01,-3.785201628972910681e-01,1.091224646547589716e-01,1.105751427386127417e-01,-3.614798371027090895e-01
+-6.625800878590853982e-01,-1.146620808152945536e-01,-1.052190971438714678e-01,1.890103041074747735e-03,4.410041489828850358e-01,7.943570573499682264e-02,5.658964679589453262e-01,-1.304791654645884036e-01,-6.461523056125290099e-02,2.043186049004536153e-01,5.419406970937726796e-03,-1.287435097996113579e-03,-9.510565162973527720e-02,-1.100000000000000006e-01,-7.016311896057725317e-01,9.510565162973527720e-02,1.100000000000000006e-01,-6.583688103942275660e-01,-9.993985556625575861e-03,-1.063045428603278802e-01,-3.707079396118519443e-01,1.099939855566255814e-01,1.136954571396721209e-01,-3.692920603881482133e-01
+-6.342675291539275895e-01,-1.136141537205869190e-01,-9.083235138980851053e-02,4.987495030965002039e-03,4.180607698330352506e-01,7.590858215693653543e-02,5.104581687368231480e-01,-1.479745070391224882e-01,-3.567820158475861619e-02,2.207334564725201287e-01,6.698175941227129011e-03,1.929766589252331467e-03,-9.876883405962567919e-02,-1.100000000000000006e-01,-6.909504125523215912e-01,9.876883405962567919e-02,1.100000000000000006e-01,-6.690495874476785065e-01,-9.388255425464876736e-03,-1.032752228785660670e-01,-3.628782845036513938e-01,1.093882554254648476e-01,1.167247771214339341e-01,-3.771217154963487639e-01
+-6.015091030959240914e-01,-1.003892154368520029e-01,-7.639017381931348383e-02,7.536003586283492560e-03,3.932898026080547949e-01,6.304935679272402616e-02,4.585879697237866814e-01,-1.745055716395016721e-01,-1.353823766637240675e-02,2.380022910165130456e-01,8.248665217512144224e-03,5.252174634876500409e-03,-1.000000000000000056e-01,-1.100000000000000006e-01,-6.799999999994977840e-01,1.000000000000000056e-01,1.100000000000000006e-01,-6.800000000005023137e-01,-7.320189347409175595e-03,-1.004114892277900017e-01,-3.552239896665904118e-01,1.073201893474091118e-01,1.195885107722099994e-01,-3.847760103334097459e-01
+-5.650199172957144356e-01,-7.293045398796811629e-02,-6.227748628555609262e-02,9.739606996917405876e-03,3.670525667951727300e-01,3.912876259565730569e-02,4.111058022715167737e-01,-2.124776593411746850e-01,1.772078937856843683e-03,2.570391413974659756e-01,1.003981562881739974e-02,8.624325639850979885e-03,-9.876883405940117822e-02,-1.100000000000000006e-01,-6.690495874466863002e-01,9.876883405940117822e-02,1.100000000000000006e-01,-6.909504125533137975e-01,-3.840709972818052986e-03,-9.778385653466860339e-02,-3.479335292427048199e-01,1.038407099728179683e-01,1.222161434653313977e-01,-3.920664707572953378e-01
+-5.253190287841533745e-01,-2.922878092539320932e-02,-4.877165008242022315e-02,1.225311428532179815e-02,3.395273341118346666e-01,2.497974191343867861e-03,3.682489008889697213e-01,-2.643954788365384667e-01,1.064761765370743005e-02,2.788295816946525507e-01,1.198181587153619720e-02,1.193481551202234953e-02,-9.510565162929225658e-02,-1.100000000000000006e-01,-6.583688103932731073e-01,9.510565162929225658e-02,1.100000000000000006e-01,-7.016311896067269904e-01,9.645063683760626838e-04,-9.545702583671947239e-02,-3.411864185632817459e-01,9.903549363162381103e-02,1.245429741632805287e-01,-3.988135814367184118e-01
+-4.828051591264544418e-01,3.191699582779033983e-02,-3.609134981966345690e-02,1.631742097952657705e-02,3.107876914940435054e-01,-4.768801171700770558e-02,3.298837045282529412e-01,-3.319682847546846505e-01,1.374068819080575404e-02,3.039753575659870366e-01,1.395079121648591658e-02,1.498012027526417038e-02,-8.910065241850800843e-02,-1.100000000000000006e-01,-6.482206650177800844e-01,8.910065241850800843e-02,1.100000000000000006e-01,-7.117793349822200133e-01,6.977139302254214970e-03,-9.348829142803448400e-02,-3.351487938856251292e-01,9.302286069774563793e-02,1.265117085719655032e-01,-4.048512061143749730e-01
+-4.378336598914666644e-01,1.095522403449461224e-01,-2.442778464429401497e-02,2.363195767012194609e-02,2.808774127893438610e-01,-1.102372783086190966e-01,2.956860640201384172e-01,-4.144794111137801718e-01,1.181813277387997255e-02,3.318676187609296835e-01,1.581207081678653176e-02,1.744878856012951895e-02,-8.090169943706776445e-02,-1.100000000000000006e-01,-6.388550323391155583e-01,8.090169943706776445e-02,1.100000000000000006e-01,-7.211449676608845394e-01,1.404913785119963482e-02,-9.192613008361039117e-02,-3.299693215670264079e-01,8.595086214880021114e-02,1.280738699163896099e-01,-4.100306784329736387e-01
+-3.907770986508725120e-01,1.980260120127675383e-01,-1.395745258991624299e-02,3.546144753843081393e-02,2.498681818945534261e-01,-1.798060562199927936e-01,2.652653009973844900e-01,-5.040411986123478627e-01,5.665123502240822922e-03,3.478089728117486623e-01,1.743836329124993922e-02,1.886183327925621336e-02,-7.071067811813851189e-02,-1.100000000000000006e-01,-6.305025253165803534e-01,7.071067811813851189e-02,1.100000000000000006e-01,-7.294974746834197443e-01,2.200636594032041871e-02,-9.080900740026308371e-02,-3.257755374056523490e-01,7.799363405967940643e-02,1.291909925997369035e-01,-4.142244625943476977e-01
+-3.420655581744023177e-01,2.895443046047467828e-01,-4.841596824225523864e-03,5.160187264108320737e-02,2.178979182501553091e-01,-2.492728734085432329e-01,2.382376078093703387e-01,-5.905773675927352695e-01,-3.968751818325467681e-03,3.489874358007342692e-01,1.872202140063496112e-02,1.860051970964692394e-02,-5.877852522865487789e-02,-1.100000000000000006e-01,-6.233688103934523772e-01,5.877852522865487789e-02,1.100000000000000006e-01,-7.366311896065477205e-01,3.065289020553497307e-02,-9.016443064597441659e-02,-3.226707062859284214e-01,6.934710979446484513e-02,1.298355693540255706e-01,-4.173292937140716807e-01
+-2.922088815106370085e-01,3.793666227290525272e-01,2.782043068439586132e-03,7.120691346093120655e-02,1.851921758790478212e-01,-3.145830796576579713e-01,2.142641032468924900e-01,-6.714023036903464803e-01,-1.639386155580959542e-02,3.490610897375458488e-01,1.958198324591316902e-02,1.703940665420781292e-02,-4.539904997330022896e-02,-1.100000000000000006e-01,-6.176295433065808194e-01,4.539904997330022896e-02,1.100000000000000006e-01,-7.423704566934192783e-01,3.977580452326551219e-02,-9.000827143966247390e-02,-3.207312794543654144e-01,6.022419547673428519e-02,1.299917285603375272e-01,-4.192687205456345767e-01
+-2.418044428674198110e-01,4.622966703128442711e-01,8.810760645734862229e-03,9.227356492724719805e-02,1.520718893921927939e-01,-3.717175438120134401e-01,1.930679167292150278e-01,-7.407176961249557490e-01,-3.098756273328099470e-02,3.490656931085965864e-01,1.996643096951321306e-02,1.457753668235011596e-02,-3.090169943679407435e-02,-1.100000000000000006e-01,-6.134260438591798703e-01,3.090169943679407435e-02,1.100000000000000006e-01,-7.465739561408202274e-01,4.915047246579271056e-02,-9.034437493924932228e-02,-3.200050120361451755e-01,5.084952753420709376e-02,1.296556250607506788e-01,-4.199949879638548156e-01
+-1.915338529918231281e-01,5.348385334564962346e-01,1.318858593768624035e-02,1.124415214085226766e-01,1.189504629188176954e-01,-4.184620240930795876e-01,1.744406738127572964e-01,-7.942577162645751976e-01,-4.719277263934185118e-02,3.490659808192873026e-01,1.985221780111119314e-02,1.166413895998029415e-02,-1.564344650329323530e-02,-1.100000000000000006e-01,-6.108618161582595185e-01,1.564344650329323530e-02,1.100000000000000006e-01,-7.491381838417405792e-01,5.854605859563233317e-02,-9.116446516111159637e-02,-3.205097871454475889e-01,4.145394140436747116e-02,1.288355348388884047e-01,-4.194902128545523468e-01
+-1.421519329419078381e-01,5.953693400306234729e-01,1.591602986319452448e-02,1.297194457243177890e-01,8.632316183433869083e-02,-4.543397535403455034e-01,1.582451059991751008e-01,-8.301158477207655206e-01,-6.451373185810750643e-02,3.490659988012054238e-01,1.924197278441280162e-02,8.703821904230598858e-03,7.411697378999244700e-13,-1.100000000000000006e-01,-6.100000000000000977e-01,-7.411697378999244700e-13,1.100000000000000006e-01,-7.500000000000000000e-01,6.773121240010505917e-02,-9.244834876226361298e-02,-3.222331755438291867e-01,3.226878759989475209e-02,1.275516512377363743e-01,-4.177668244561707489e-01
+-9.447163462087837527e-02,6.433256773752078495e-01,1.705646484155821929e-02,1.426945809663255627e-01,5.475217720504978181e-02,-4.797609735126411867e-01,1.444180509873906615e-01,-8.476869101485385860e-01,-8.251230611479043464e-02,3.459210837696060081e-01,1.815963020589797527e-02,5.985677071122786491e-03,1.564344650475872969e-02,-1.100000000000000006e-01,-6.108618161584219441e-01,-1.564344650475872969e-02,1.100000000000000006e-01,-7.491381838415781536e-01,7.647976490876769173e-02,-9.416441226747980509e-02,-3.251327416893238231e-01,2.352023509123212994e-02,1.258355877325201821e-01,-4.148672583106761125e-01
+-4.934908310946929666e-02,6.773332858467315809e-01,1.673834903910635663e-02,1.498575406398899301e-01,2.485129274776191541e-02,-4.945905135249813456e-01,1.329767390238018043e-01,-8.412338040713074339e-01,-1.008067836232467984e-01,3.118859117663944636e-01,1.664499566585864523e-02,3.185372749374212539e-03,3.090169943820521292e-02,-1.100000000000000006e-01,-6.134260438595008358e-01,-3.090169943820521292e-02,1.100000000000000006e-01,-7.465739561404992619e-01,8.457629772407418423e-02,-9.627040049797318255e-02,-3.291370886403205964e-01,1.542370227592565479e-02,1.237295995020268186e-01,-4.108629113596792837e-01
+-7.673188383177461172e-03,6.991592328527153066e-01,1.515302578475374862e-02,1.516888329904537980e-01,-2.725583436404786612e-03,-5.007475828907832494e-01,1.240306783854424194e-01,-8.177541401305357116e-01,-1.190744289974842579e-01,2.714130818261161759e-01,1.474786567649483300e-02,7.917428047742740326e-04,4.539904997462226866e-02,-1.100000000000000006e-01,-6.176295433070524421e-01,-4.539904997462226866e-02,1.100000000000000006e-01,-7.423704566929476556e-01,9.182144733726060881e-02,-9.871445703413489481e-02,-3.341476160852205890e-01,8.178552662739251022e-03,1.212855429658651063e-01,-4.058523839147792911e-01
+2.963590180034555988e-02,7.098632864871783354e-01,1.254818146276202168e-02,1.487310921671149977e-01,-2.728787781584265937e-02,-4.994660274916314924e-01,1.178014005985770357e-01,-7.809684223216387666e-01,-1.370588412573815473e-01,2.278042664153569208e-01,1.252216408629370885e-02,-1.026656369220543168e-03,5.877852522985526490e-02,-1.100000000000000006e-01,-6.233688103940628888e-01,-5.877852522985526490e-02,1.100000000000000006e-01,-7.366311896059372089e-01,9.803681411957726466e-02,-1.014364010926860349e-01,-3.400409482093430524e-01,1.963185880422622931e-03,1.185635989073139662e-01,-3.999590517906568277e-01
+6.161585822341424101e-02,7.103901144863845607e-01,9.217067174911974456e-03,1.416878746222135776e-01,-4.810022722919826688e-02,-4.917885642698382465e-01,1.146525911130523434e-01,-7.340487569073341767e-01,-1.545832616044810204e-01,1.832300851361670369e-01,1.002054977251350121e-02,-2.367965080502767300e-03,7.071067811918768653e-02,-1.100000000000000006e-01,-6.305025253173147659e-01,-7.071067811918768653e-02,1.100000000000000006e-01,-7.294974746826853318e-01,1.030693551132237651e-01,-1.043692093772906199e-01,-3.466719716169441301e-01,-3.069355113223849740e-03,1.156307906227093812e-01,-3.933280283830556945e-01
+8.723604095539770620e-02,7.018536152205285816e-01,5.483080760900464583e-03,1.314589164202272231e-01,-6.436012173442846873e-02,-4.787833981377597747e-01,1.151334353456961862e-01,-6.803817301658778849e-01,-1.715712081087165941e-01,1.398613826560173024e-01,7.290000458936998252e-03,-3.411449538281879131e-03,8.090169943793906748e-02,-1.100000000000000006e-01,-6.388550323399549979e-01,-8.090169943793906748e-02,1.100000000000000006e-01,-7.211449676600450998e-01,1.067951524568905020e-01,-1.074406664145490381e-01,-3.538774085046236251e-01,-6.795152456890551917e-03,1.125593335854509630e-01,-3.861225914953761995e-01
+1.053548694619803189e-01,6.854951399734565687e-01,1.678016517415268890e-03,1.190053900472656384e-01,-7.516005639135835137e-02,-4.615221586747578764e-01,1.200377521516790003e-01,-6.233272708714203691e-01,-1.880758526944176223e-01,9.974724695535593100e-02,4.369022085540390926e-03,-4.366040839641741403e-03,8.910065241918162238e-02,-1.100000000000000006e-01,-6.482206650187054553e-01,-8.910065241918162238e-02,1.100000000000000006e-01,-7.117793349812946424e-01,1.091224646547640509e-01,-1.105751427386227476e-01,-3.614798371027335699e-01,-9.122464654764086966e-03,1.094248572613772535e-01,-3.785201628972662546e-01
+1.146620808153086674e-01,6.625800878590037968e-01,-1.890103041085425175e-03,1.052190971438264622e-01,-7.943570573499883491e-02,-4.410041489828156469e-01,1.304791654646320631e-01,-5.658964679587653590e-01,-2.043186049005054628e-01,6.461523056115098251e-02,1.287435097986110513e-03,-5.419406970941250887e-03,9.510565162975076481e-02,-1.100000000000000006e-01,-6.583688103942608727e-01,-9.510565162975076481e-02,1.100000000000000006e-01,-7.016311896057392250e-01,1.099939855566260116e-01,-1.136954571396819602e-01,-3.692920603881730823e-01,-9.993985556625999134e-03,1.063045428603180409e-01,-3.707079396118267423e-01
+1.136141537205657692e-01,6.342675291538326654e-01,-4.987495030973764995e-03,9.083235138976367140e-02,-7.590858215691193012e-02,-4.180607698329611988e-01,1.479745070391896566e-01,-5.104581687366563925e-01,-2.207334564725717818e-01,3.567820158467942954e-02,-1.929766589262539881e-03,-6.698175941231535209e-03,9.876883405963329809e-02,-1.100000000000000006e-01,-6.690495874477121463e-01,-9.876883405963329809e-02,1.100000000000000006e-01,-6.909504125522879514e-01,1.093882554254607120e-01,-1.167247771214430935e-01,-3.771217154963726892e-01,-9.388255425460685644e-03,1.032752228785569076e-01,-3.628782845036271354e-01
+1.003892154367893308e-01,6.015091030958173990e-01,-7.536003586290591916e-03,7.639017381926943573e-02,-6.304935679266739090e-02,-3.932898026079763021e-01,1.745055716396012868e-01,-4.585879697236336927e-01,-2.380022910165693617e-01,1.353823766631498220e-02,-5.252174634886984210e-03,-8.248665217517303291e-03,1.000000000000000056e-01,-1.100000000000000006e-01,-6.800000000005363976e-01,-1.000000000000000056e-01,1.100000000000000006e-01,-6.799999999994637001e-01,1.073201893474005630e-01,-1.195885107722185481e-01,-3.847760103334328385e-01,-7.320189347400488100e-03,1.004114892277814530e-01,-3.552239896665669860e-01
+7.293045398785746869e-02,5.650199172955968629e-01,-9.739606996924330892e-03,6.227748628551343923e-02,-3.912876259556258285e-02,-3.670525667950899074e-01,2.124776593413145176e-01,-4.111058022713779958e-01,-2.570391413975295913e-01,-1.772078937893520507e-03,-8.624325639861889561e-03,-1.003981562882319024e-02,9.876883405939357319e-02,-1.100000000000000006e-01,-6.909504125533474372e-01,-9.876883405939357319e-02,1.100000000000000006e-01,-6.690495874466526605e-01,1.038407099728051730e-01,-1.222161434653391138e-01,-3.920664707573169872e-01,-3.840709972805077255e-03,9.778385653466088734e-02,-3.479335292426828374e-01
+2.922878092523002735e-02,5.253190287840266981e-01,-1.225311428533122117e-02,4.877165008237981103e-02,-2.497974191208545552e-03,-3.395273341117478472e-01,2.643954788367242625e-01,-3.682489008888450432e-01,-2.788295816947256589e-01,-1.064761765372520055e-02,-1.193481551203234327e-02,-1.198181587154224098e-02,9.510565162927721305e-02,-1.100000000000000006e-01,-7.016311896067594089e-01,-9.510565162927721305e-02,1.100000000000000006e-01,-6.583688103932406888e-01,9.903549363160711605e-02,-1.245429741632872178e-01,-3.988135814367381182e-01,9.645063683930144016e-04,9.545702583671278330e-02,-3.411864185632617064e-01
+-3.191699582801144075e-02,4.828051591263154418e-01,-1.631742097954359816e-02,3.609134981962461297e-02,4.768801171718727722e-02,-3.107876914939501911e-01,3.319682847549229043e-01,-3.298837045281379221e-01,-3.039753575660706364e-01,-1.374068819080660232e-02,-1.498012027527270869e-02,-1.395079121649222056e-02,8.910065241848527662e-02,-1.100000000000000006e-01,-7.117793349822512106e-01,-8.910065241848527662e-02,1.100000000000000006e-01,-6.482206650177488871e-01,9.302286069772483512e-02,-1.265117085719711654e-01,-4.048512061143927920e-01,6.977139302275309207e-03,9.348829142802883574e-02,-3.351487938856070325e-01
+-1.095522403452154070e-01,4.378336598913197819e-01,-2.363195767015207824e-02,2.442778464425856416e-02,1.102372783088337999e-01,-2.808774127892466610e-01,4.144794111140615023e-01,-2.956860640200353885e-01,-3.318676187610209993e-01,-1.181813277386628211e-02,-1.744878856013595825e-02,-1.581207081679235002e-02,8.090169943703832967e-02,-1.100000000000000006e-01,-7.211449676609129611e-01,-8.090169943703832967e-02,1.100000000000000006e-01,-6.388550323390871366e-01,8.595086214877631359e-02,-1.280738699163938843e-01,-4.100306784329885712e-01,1.404913785122385850e-02,9.192613008360610294e-02,-3.299693215670113089e-01
+-1.980260120130500068e-01,3.907770986507247968e-01,-3.546144753847459835e-02,1.395745258988598941e-02,1.798060562202113688e-01,-2.498681818944560595e-01,5.040411986126223098e-01,-2.652653009972966713e-01,-3.478089728117599311e-01,-5.665123502215671167e-03,-1.886183327925800360e-02,-1.743836329125434542e-02,7.071067811810410886e-02,-1.100000000000000006e-01,-7.294974746834438362e-01,-7.071067811810410886e-02,1.100000000000000006e-01,-6.305025253165562615e-01,7.799363405965376028e-02,-1.291909925997396513e-01,-4.142244625943589664e-01,2.200636594034642568e-02,9.080900740026033591e-02,-3.257755374056409137e-01
+-2.895443046050334979e-01,3.420655581742511053e-01,-5.160187264113987038e-02,4.841596824199920213e-03,2.492728734087559239e-01,-2.178979182500560829e-01,5.905773675930011679e-01,-2.382376078092935667e-01,-3.489874358007349908e-01,3.968751818360011230e-03,-1.860051970964376328e-02,-1.872202140063798301e-02,5.877852522861551354e-02,-1.100000000000000006e-01,-7.366311896065677045e-01,-5.877852522861551354e-02,1.100000000000000006e-01,-6.233688103934323932e-01,6.934710979443739487e-02,-1.298355693540268196e-01,-4.173292937140794523e-01,3.065289020556280497e-02,9.016443064597316759e-02,-3.226707062859204833e-01
+-3.793666227293256976e-01,2.922088815104834092e-01,-7.120691346099636276e-02,-2.782043068460477407e-03,3.145830796578515942e-01,-1.851921758789471240e-01,6.714023036905869546e-01,-2.142641032468249329e-01,-3.490610897375459598e-01,1.639386155585101715e-02,-1.703940665420108913e-02,-1.958198324591500089e-02,4.539904997325687475e-02,-1.100000000000000006e-01,-7.423704566934347104e-01,-4.539904997325687475e-02,1.100000000000000006e-01,-6.176295433065653873e-01,6.022419547670572471e-02,-1.299917285603372497e-01,-4.192687205456387400e-01,3.977580452329448901e-02,9.000827143966275146e-02,-3.207312794543612511e-01
+-4.622966703130879651e-01,2.418044428672644075e-01,-9.227356492731268733e-02,-8.810760645750854644e-03,3.717175438121756437e-01,-1.520718893920908199e-01,7.407176961251497049e-01,-1.930679167291543818e-01,-3.490656931085966419e-01,3.098756273332849143e-02,-1.457753668234146316e-02,-1.996643096951351143e-02,3.090169943674779540e-02,-1.100000000000000006e-01,-7.465739561408306635e-01,-3.090169943674779540e-02,1.100000000000000006e-01,-6.134260438591694342e-01,5.084952753417810306e-02,-1.296556250607488747e-01,-4.199949879638551486e-01,4.915047246582210372e-02,9.034437493925112639e-02,-3.200050120361448425e-01
+-5.348385334567081761e-01,1.915338529916640331e-01,-1.124415214085829479e-01,-1.318858593769750044e-02,4.184620240932105384e-01,-1.189504629187128487e-01,7.942577162647169731e-01,-1.744406738127022849e-01,-3.490659808192872471e-01,4.719277263939741784e-02,-1.166413895997074103e-02,-1.985221780110998230e-02,1.564344650324377139e-02,-1.100000000000000006e-01,-7.491381838417461303e-01,-1.564344650324377139e-02,1.100000000000000006e-01,-6.108618161582539674e-01,4.145394140433793229e-02,-1.288355348388850186e-01,-4.194902128545487940e-01,5.854605859566228143e-02,9.116446516111496867e-02,-3.205097871454511971e-01
+-5.953693400307962236e-01,1.421519329417527955e-01,-1.297194457243664723e-01,-1.591602986320067928e-02,4.543397535404425369e-01,-8.632316183423616174e-02,8.301158477208503417e-01,-1.582451059991278886e-01,-3.490659988012054238e-01,6.451373185816661193e-02,-8.703821904221592173e-03,-1.924197278441015097e-02,-7.912507543030199157e-13,-1.100000000000000006e-01,-7.500000000000000000e-01,7.912507543030199157e-13,1.100000000000000006e-01,-6.100000000000000977e-01,3.226878759986624712e-02,-1.275516512377315725e-01,-4.177668244561634214e-01,6.773121240013395272e-02,9.244834876226841469e-02,-3.222331755438366252e-01
+-6.433256773753347479e-01,9.447163462073485118e-02,-1.426945809663572040e-01,-1.705646484155937462e-02,4.797609735127030817e-01,-5.475217720495467039e-02,8.476869101485557945e-01,-1.444180509873524143e-01,-3.459210837695225749e-01,8.251230611484752786e-02,-5.985677071115042686e-03,-1.815963020589389521e-02,-1.564344650480678847e-02,-1.100000000000000006e-01,-7.491381838415728245e-01,1.564344650480678847e-02,1.100000000000000006e-01,-6.108618161584272732e-01,2.352023509120611949e-02,-1.258355877325142425e-01,-4.148672583106654543e-01,7.647976490879407341e-02,9.416441226748574478e-02,-3.251327416893345923e-01
+-6.773332858468177342e-01,4.934908310933533437e-02,-1.498575406399037524e-01,-1.673834903910318209e-02,4.945905135250133200e-01,-2.485129274767321553e-02,8.412338040712590281e-01,-1.329767390237708569e-01,-3.118859117662745040e-01,1.008067836233020459e-01,-3.185372749365719333e-03,-1.664499566585333004e-02,-3.090169943825149187e-02,-1.100000000000000006e-01,-7.465739561404887148e-01,3.090169943825149187e-02,1.100000000000000006e-01,-6.134260438595113829e-01,1.542370227590195847e-02,-1.237295995020197409e-01,-4.108629113596653504e-01,8.457629772409822055e-02,9.627040049798026022e-02,-3.291370886403346963e-01
+-6.991592328527653777e-01,7.673188383055412967e-03,-1.516888329904519106e-01,-1.515302578474718095e-02,5.007475828907902438e-01,2.725583436485367120e-03,8.177541401304412316e-01,-1.240306783854191741e-01,-2.714130818259833378e-01,1.190744289975386588e-01,-7.917428047676267891e-04,-1.474786567648866259e-02,-4.539904997466562286e-02,-1.100000000000000006e-01,-7.423704566929322235e-01,4.539904997466562286e-02,1.100000000000000006e-01,-6.176295433070678742e-01,8.178552662718462096e-03,-1.212855429658570711e-01,-4.058523839147624712e-01,9.182144733728168917e-02,9.871445703414293005e-02,-3.341476160852376309e-01
+-7.098632864871954329e-01,-2.963590180045278660e-02,-1.487310921670992325e-01,-1.254818146275268366e-02,4.994660274916172815e-01,2.728787781591292608e-02,7.809684223215079824e-01,-1.178014005985630053e-01,-2.278042664152193919e-01,1.370588412574368919e-01,1.026656369225354640e-03,-1.252216408628637270e-02,-5.877852522989462924e-02,-1.100000000000000006e-01,-7.366311896059171138e-01,5.877852522989462924e-02,1.100000000000000006e-01,-6.233688103940829839e-01,1.963185880405247941e-03,-1.185635989073051677e-01,-3.999590517906374543e-01,9.803681411959488945e-02,1.014364010926948334e-01,-3.400409482093626479e-01
+-7.103901144863716821e-01,-6.161585822350616054e-02,-1.416878746221858498e-01,-9.217067174900500995e-03,4.917885642698050508e-01,4.810022722925746952e-02,7.340487569071730833e-01,-1.146525911130485409e-01,-1.832300851360279814e-01,1.545832616045372809e-01,2.367965080506308738e-03,-1.002054977250494902e-02,-7.071067811922310264e-02,-1.100000000000000006e-01,-7.294974746826605738e-01,7.071067811922310264e-02,1.100000000000000006e-01,-6.305025253173395239e-01,-3.069355113237776100e-03,-1.156307906226997639e-01,-3.933280283830337121e-01,1.030693551132378788e-01,1.043692093773002372e-01,-3.466719716169663901e-01
+-7.018536152204886136e-01,-8.723604095546753923e-02,-1.314589164201905580e-01,-5.483080760888312845e-03,4.787833981377110359e-01,6.436012173447175355e-02,6.803817301657005823e-01,-1.151334353457050264e-01,-1.398613826558847972e-01,1.715712081087708840e-01,3.411449538284815584e-03,-7.290000458927914373e-03,-8.090169943796848839e-02,-1.100000000000000006e-01,-7.211449676600167891e-01,8.090169943796848839e-02,1.100000000000000006e-01,-6.388550323399833086e-01,-6.795152456900176163e-03,-1.125593335854410265e-01,-3.861225914953526628e-01,1.067951524569002442e-01,1.074406664145589746e-01,-3.538774085046474949e-01
+-6.854951399733946182e-01,-1.053548694620231735e-01,-1.190053900472243104e-01,-1.678016517403704789e-03,4.615221586746981464e-01,7.516005639138209626e-02,6.233272708712409571e-01,-1.200377521517026203e-01,-9.974724695524081475e-02,1.880758526944677489e-01,4.366040839645188298e-03,-4.369022085531054644e-03,-8.910065241920371581e-02,-1.100000000000000006e-01,-7.117793349812642223e-01,8.910065241920371581e-02,1.100000000000000006e-01,-6.482206650187358754e-01,-9.122464654769027459e-03,-1.094248572613675252e-01,-3.785201628972424404e-01,1.091224646547690746e-01,1.105751427386324759e-01,-3.614798371027577173e-01
+-6.625800878589233056e-01,-1.146620808153222260e-01,-1.052190971437822753e-01,1.890103041095897701e-03,4.410041489827477013e-01,7.943570573500058352e-02,5.658964679585885005e-01,-1.304791654646745291e-01,-6.461523056105056284e-02,2.043186049005554783e-01,5.419406970944954521e-03,-1.287435097976138022e-03,-9.510565162976580833e-02,-1.100000000000000006e-01,-7.016311896057068065e-01,9.510565162976580833e-02,1.100000000000000006e-01,-6.583688103942932912e-01,-9.993985556626408528e-03,-1.063045428603084652e-01,-3.707079396118025394e-01,1.099939855566264141e-01,1.136954571396915359e-01,-3.692920603881976183e-01
+-6.342675291537375193e-01,-1.136141537205445085e-01,-9.083235138971873512e-02,4.987495030982526216e-03,4.180607698328870359e-01,7.590858215688728317e-02,5.104581687364893039e-01,-1.479745070392569362e-01,-3.567820158459994451e-02,2.207334564726238513e-01,6.698175941235978703e-03,1.929766589272759788e-03,-9.876883405964090312e-02,-1.100000000000000006e-01,-6.909504125522543116e-01,9.876883405964090312e-02,1.100000000000000006e-01,-6.690495874477457861e-01,-9.388255425456557002e-03,-1.032752228785477344e-01,-3.628782845036032656e-01,1.093882554254565348e-01,1.167247771214522667e-01,-3.771217154963968921e-01
+-6.015091030957091522e-01,-1.003892154367277689e-01,-7.639017381922483252e-02,7.536003586297731170e-03,3.932898026078968101e-01,6.304935679261147730e-02,4.585879697234787056e-01,-1.745055716396994583e-01,-1.353823766625666253e-02,2.380022910166251782e-01,8.248665217522542156e-03,5.252174634897600718e-03,-1.000000000000000056e-01,-1.100000000000000006e-01,-6.799999999994296163e-01,1.000000000000000056e-01,1.100000000000000006e-01,-6.800000000005704814e-01,-7.320189347391925505e-03,-1.004114892277729182e-01,-3.552239896665438934e-01,1.073201893473918617e-01,1.195885107722270829e-01,-3.847760103334562642e-01
+-5.650199172954746274e-01,-7.293045398774664068e-02,-6.227748628546911358e-02,9.739606996931255908e-03,3.670525667950038096e-01,3.912876259546874125e-02,4.111058022712331117e-01,-2.124776593414542114e-01,1.772078937932171881e-03,2.570391413975930406e-01,1.003981562882923229e-02,8.624325639872141777e-03,-9.876883405938573224e-02,-1.100000000000000006e-01,-6.690495874466180215e-01,9.876883405938573224e-02,1.100000000000000006e-01,-6.909504125533820762e-01,-3.840709972791907234e-03,-9.778385653465296312e-02,-3.479335292426605220e-01,1.038407099727918226e-01,1.222161434653470380e-01,-3.920664707573396357e-01
+-5.253190287838941375e-01,-2.922878092506520087e-02,-4.877165008233766419e-02,1.225311428534082807e-02,3.395273341116573085e-01,2.497974191072237921e-03,3.682489008887141479e-01,-2.643954788369115017e-01,1.064761765374439006e-02,2.788295816947997108e-01,1.198181587154858833e-02,1.193481551204243069e-02,-9.510565162926173932e-02,-1.100000000000000006e-01,-6.583688103932073821e-01,9.510565162926173932e-02,1.100000000000000006e-01,-7.016311896067927156e-01,9.645063684102089807e-04,-9.545702583670591379e-02,-3.411864185632413893e-01,9.903549363158967167e-02,1.245429741632940873e-01,-3.988135814367587129e-01
+-4.828051591261786069e-01,3.191699582822740688e-02,-3.609134981958649763e-02,1.631742097956034171e-02,3.107876914938584312e-01,-4.768801171736315736e-02,3.298837045280241798e-01,-3.319682847551565508e-01,1.374068819080888869e-02,3.039753575661537921e-01,1.395079121649823312e-02,1.498012027528144129e-02,-8.910065241846318318e-02,-1.100000000000000006e-01,-6.482206650177184670e-01,8.910065241846318318e-02,1.100000000000000006e-01,-7.117793349822816307e-01,6.977139302295515266e-03,-9.348829142802334013e-02,-3.351487938855897131e-01,9.302286069770435151e-02,1.265117085719766610e-01,-4.048512061144103891e-01
+-4.378336598911761746e-01,1.095522403454763927e-01,-2.442778464422397031e-02,2.363195767018146445e-02,2.808774127891516259e-01,-1.102372783090420638e-01,2.956860640199344692e-01,-4.144794111143346171e-01,1.181813277385376434e-02,3.318676187611080408e-01,1.581207081679786991e-02,1.744878856014225182e-02,-8.090169943700972754e-02,-1.100000000000000006e-01,-6.388550323390596031e-01,8.090169943700972754e-02,1.100000000000000006e-01,-7.211449676609404946e-01,1.404913785124706216e-02,-9.192613008360192572e-02,-3.299693215669968760e-01,8.595086214875277686e-02,1.280738699163980754e-01,-4.100306784330032261e-01
+-3.907770986505761934e-01,1.980260120133316704e-01,-1.395745258985569420e-02,3.546144753851818848e-02,2.498681818943586097e-01,-1.798060562204292778e-01,2.652653009972079645e-01,-5.040411986128962019e-01,5.665123502191580195e-03,3.478089728117710333e-01,1.743836329125872386e-02,1.886183327925962036e-02,-7.071067811806970582e-02,-1.100000000000000006e-01,-6.305025253165321697e-01,7.071067811806970582e-02,1.100000000000000006e-01,-7.294974746834679280e-01,2.200636594037206836e-02,-9.080900740025760198e-02,-3.257755374056296449e-01,7.799363405962775331e-02,1.291909925997423991e-01,-4.142244625943704017e-01
+-3.420655581740975060e-01,2.895443046053166603e-01,-4.841596824173774460e-03,5.160187264119601297e-02,2.178979182499554412e-01,-2.492728734089670606e-01,2.382376078092140192e-01,-5.905773675932628475e-01,-3.968751818394277223e-03,3.489874358007356570e-01,1.872202140064149409e-02,1.860051970964082119e-02,-5.877852522857614226e-02,-1.100000000000000006e-01,-6.233688103934124092e-01,5.877852522857614226e-02,1.100000000000000006e-01,-7.366311896065876885e-01,3.065289020559024483e-02,-9.016443064597193247e-02,-3.226707062859127118e-01,6.934710979440956991e-02,1.298355693540280686e-01,-4.173292937140873349e-01
+-2.922088815103215942e-01,3.793666227295991455e-01,2.782043068482498854e-03,7.120691346106126918e-02,1.851921758788407091e-01,-3.145830796580453281e-01,2.142641032467511031e-01,-6.714023036908227660e-01,-1.639386155589509647e-02,3.490610897375459598e-01,1.958198324591700623e-02,1.703940665419460820e-02,-4.539904997321225072e-02,-1.100000000000000006e-01,-6.176295433065495111e-01,4.539904997321225072e-02,1.100000000000000006e-01,-7.423704566934505866e-01,3.977580452332389604e-02,-9.000827143966304289e-02,-3.207312794543569767e-01,6.022419547667590828e-02,1.299917285603369443e-01,-4.192687205456430144e-01
+-2.418044428671017321e-01,4.622966703133342126e-01,8.810760645767648502e-03,9.227356492737877336e-02,1.520718893919838222e-01,-3.717175438123400677e-01,1.930679167290889897e-01,-7.407176961253431058e-01,-3.098756273337876371e-02,3.490656931085966419e-01,1.996643096951400756e-02,1.457753668233282771e-02,-3.090169943670016683e-02,-1.100000000000000006e-01,-6.134260438591585540e-01,3.090169943670016683e-02,1.100000000000000006e-01,-7.465739561408415437e-01,4.915047246585194790e-02,-9.034437493925297213e-02,-3.200050120361444539e-01,5.084952753414785642e-02,1.296556250607470151e-01,-4.199949879638555372e-01
+-1.915338529915080745e-01,5.348385334569145666e-01,1.318858593770854022e-02,1.124415214086418591e-01,1.189504629186096812e-01,-4.184620240933385471e-01,1.744406738126471901e-01,-7.942577162648559730e-01,-4.719277263944954282e-02,3.490659808192872471e-01,1.985221780110875064e-02,1.166413895996157475e-02,-1.564344650319570915e-02,-1.100000000000000006e-01,-6.108618161582486383e-01,1.564344650319570915e-02,1.100000000000000006e-01,-7.491381838417514594e-01,5.854605859569097376e-02,-9.116446516111822995e-02,-3.205097871454546388e-01,4.145394140430883057e-02,1.288355348388817712e-01,-4.194902128545453524e-01
+-1.421519329416012223e-01,5.953693400309639783e-01,1.591602986320661897e-02,1.297194457244138510e-01,8.632316183413549227e-02,-4.543397535405369614e-01,1.582451059990804820e-01,-8.301158477209329423e-01,-6.451373185822138756e-02,3.490659988012054793e-01,1.924197278440734071e-02,8.703821904212661817e-03,8.399106852345953428e-13,-1.100000000000000006e-01,-6.100000000000000977e-01,-8.399106852345953428e-13,1.100000000000000006e-01,-7.500000000000000000e-01,6.773121240016165279e-02,-9.244834876227307763e-02,-3.222331755438437861e-01,3.226878759983815848e-02,1.275516512377269096e-01,-4.177668244561562050e-01
+-9.447163462059030015e-02,6.433256773754600921e-01,1.705646484156057852e-02,1.426945809663881792e-01,5.475217720485898304e-02,-4.797609735127638109e-01,1.444180509873124185e-01,-8.476869101485710045e-01,-8.251230611490131817e-02,3.459210837694363661e-01,1.815963020588998861e-02,5.985677071107364799e-03,1.564344650485485072e-02,-1.100000000000000006e-01,-6.108618161584326023e-01,-1.564344650485485072e-02,1.100000000000000006e-01,-7.491381838415674954e-01,7.647976490882008038e-02,-9.416441226749169835e-02,-3.251327416893452504e-01,2.352023509117973088e-02,1.258355877325083028e-01,-4.148672583106546297e-01
+-4.934908310919972063e-02,6.773332858469029993e-01,1.673834903910017755e-02,1.498575406399170473e-01,2.485129274758305501e-02,-4.945905135250446838e-01,1.329767390237382441e-01,-8.412338040712089571e-01,-1.008067836233576264e-01,3.118859117661557656e-01,1.664499566584753260e-02,3.185372749357384421e-03,3.090169943829777083e-02,-1.100000000000000006e-01,-6.134260438595219300e-01,-3.090169943829777083e-02,1.100000000000000006e-01,-7.465739561404781677e-01,8.457629772412189606e-02,-9.627040049798733790e-02,-3.291370886403486296e-01,1.542370227587793602e-02,1.237295995020126632e-01,-4.108629113596512505e-01
+-7.673188382928150184e-03,6.991592328528166700e-01,1.515302578474035655e-02,1.516888329904497179e-01,-2.725583436569458708e-03,-5.007475828907973492e-01,1.240306783853941525e-01,-8.177541401303434210e-01,-1.190744289975979170e-01,2.714130818258500000e-01,1.474786567648193707e-02,7.917428047610723532e-04,4.539904997471024689e-02,-1.100000000000000006e-01,-6.176295433070837504e-01,-4.539904997471024689e-02,1.100000000000000006e-01,-7.423704566929163473e-01,9.182144733730307484e-02,-9.871445703415120121e-02,-3.341476160852550059e-01,8.178552662696764175e-03,1.212855429658487999e-01,-4.058523839147448742e-01
+2.963590180056412809e-02,7.098632864872128634e-01,1.254818146274303513e-02,1.487310921670829122e-01,-2.728787781598584344e-02,-4.994660274916025711e-01,1.178014005985478924e-01,-7.809684223213730903e-01,-1.370588412574952342e-01,2.278042664150792540e-01,1.252216408627863757e-02,-1.026656369230179774e-03,5.877852522993515239e-02,-1.100000000000000006e-01,-6.233688103941035230e-01,-5.877852522993515239e-02,1.100000000000000006e-01,-7.366311896058965747e-01,9.803681411961276404e-02,-1.014364010927038817e-01,-3.400409482093825764e-01,1.963185880387123550e-03,1.185635989072961194e-01,-3.999590517906173037e-01
+6.161585822359631759e-02,7.103901144863583594e-01,9.217067174889412642e-03,1.416878746221583718e-01,-4.810022722931553418e-02,-4.917885642697721882e-01,1.146525911130436837e-01,-7.340487569070147655e-01,-1.545832616045907382e-01,1.832300851358893978e-01,1.002054977249689470e-02,-2.367965080509989821e-03,7.071067811925750568e-02,-1.100000000000000006e-01,-6.305025253173636157e-01,-7.071067811925750568e-02,1.100000000000000006e-01,-7.294974746826364820e-01,1.030693551132514096e-01,-1.043692093773095769e-01,-3.466719716169878174e-01,-3.069355113251487355e-03,1.156307906226904242e-01,-3.933280283830120627e-01
+8.723604095553645632e-02,7.018536152204492007e-01,5.483080760876498511e-03,1.314589164201551419e-01,-6.436012173451503837e-02,-4.787833981376639625e-01,1.151334353457123955e-01,-6.803817301655273875e-01,-1.715712081088236751e-01,1.398613826557561779e-01,7.290000458917833027e-03,-3.411449538287902091e-03,8.090169943799710439e-02,-1.100000000000000006e-01,-6.388550323400109532e-01,-8.090169943799710439e-02,1.100000000000000006e-01,-7.211449676599891445e-01,1.067951524569095978e-01,-1.074406664145686197e-01,-3.538774085046703655e-01,-6.795152456909661631e-03,1.125593335854313815e-01,-3.861225914953294591e-01
+1.053548694620668608e-01,6.854951399733332229e-01,1.678016517392125510e-03,1.190053900471832182e-01,-7.516005639140638239e-02,-4.615221586746391935e-01,1.200377521517249912e-01,-6.233272708710618781e-01,-1.880758526945175146e-01,9.974724695511946737e-02,4.369022085521792956e-03,-4.366040839647730536e-03,8.910065241922580925e-02,-1.100000000000000006e-01,-6.482206650187661845e-01,-8.910065241922580925e-02,1.100000000000000006e-01,-7.117793349812339132e-01,1.091224646547740013e-01,-1.105751427386422042e-01,-3.614798371027815316e-01,-9.122464654774037340e-03,1.094248572613577969e-01,-3.785201628972182930e-01
+1.146620808153359233e-01,6.625800878588437026e-01,-1.890103041106342471e-03,1.052190971437383937e-01,-7.943570573500251253e-02,-4.410041489826801442e-01,1.304791654647168564e-01,-5.658964679584129742e-01,-2.043186049006057992e-01,6.461523056095098971e-02,1.287435097966343122e-03,-5.419406970948522848e-03,9.510565162978083797e-02,-1.100000000000000006e-01,-6.583688103943257097e-01,-9.510565162978083797e-02,1.100000000000000006e-01,-7.016311896056743880e-01,1.099939855566268304e-01,-1.136954571397010977e-01,-3.692920603882217656e-01,-9.993985556626824862e-03,1.063045428602989034e-01,-3.707079396117780590e-01
+1.136141537205227620e-01,6.342675291536401527e-01,-4.987495030991423613e-03,9.083235138967271638e-02,-7.590858215686201171e-02,-4.180607698328109301e-01,1.479745070393257700e-01,-5.104581687363183296e-01,-2.207334564726766979e-01,3.567820158451878026e-02,-1.929766589283116954e-03,-6.698175941240392707e-03,9.876883405964874407e-02,-1.100000000000000006e-01,-6.690495874477803140e-01,-9.876883405964874407e-02,1.100000000000000006e-01,-6.909504125522197837e-01,1.093882554254522743e-01,-1.167247771214616897e-01,-3.771217154964215390e-01,-9.388255425452123049e-03,1.032752228785383114e-01,-3.628782845035775639e-01
+1.003892154366632372e-01,6.015091030955989071e-01,-7.536003586305069918e-03,7.639017381917921623e-02,-6.304935679255334324e-02,-3.932898026078155418e-01,1.745055716398018486e-01,-4.585879697233206653e-01,-2.380022910166824102e-01,1.353823766619733499e-02,-5.252174634907998650e-03,-8.248665217527914595e-03,1.000000000000000056e-01,-1.100000000000000006e-01,-6.800000000006055645e-01,-1.000000000000000056e-01,1.100000000000000006e-01,-6.799999999993945332e-01,1.073201893473830493e-01,-1.195885107722358814e-01,-3.847760103334800230e-01,-7.320189347382731471e-03,1.004114892277641197e-01,-3.552239896665191354e-01
+7.293045398764549936e-02,5.650199172953709326e-01,-9.739606996937329175e-03,6.227748628543138681e-02,-3.912876259538245610e-02,-3.670525667949306459e-01,2.124776593415822201e-01,-4.111058022711105431e-01,-2.570391413976517159e-01,-1.772078937964583888e-03,-8.624325639881883984e-03,-1.003981562883438615e-02,9.876883405937901539e-02,-1.100000000000000006e-01,-6.909504125534118302e-01,-9.876883405937901539e-02,1.100000000000000006e-01,-6.690495874465882675e-01,1.038407099727805261e-01,-1.222161434653538520e-01,-3.920664707573587315e-01,-3.840709972780055603e-03,9.778385653464614913e-02,-3.479335292426404269e-01
+2.922878092493381985e-02,5.253190287837978811e-01,-1.225311428534813993e-02,4.877165008230693183e-02,-2.497974190963599128e-03,-3.395273341115916388e-01,2.643954788370624920e-01,-3.682489008886198900e-01,-2.788295816948601624e-01,-1.064761765375776305e-02,-1.193481551205073481e-02,-1.198181587155317321e-02,9.510565162925022076e-02,-1.100000000000000006e-01,-7.016311896068175846e-01,-9.510565162925022076e-02,1.100000000000000006e-01,-6.583688103931825131e-01,9.903549363157690411e-02,-1.245429741632992082e-01,-3.988135814367738119e-01,9.645063684237120682e-04,9.545702583670079289e-02,-3.411864185632254576e-01
+-3.191699582837871640e-02,4.828051591260924535e-01,-1.631742097957184987e-02,3.609134981956248905e-02,4.768801171748617701e-02,-3.107876914938008661e-01,3.319682847553231397e-01,-3.298837045279542357e-01,-3.039753575662129115e-01,-1.374068819080919920e-02,-1.498012027528751282e-02,-1.395079121650189685e-02,8.910065241844883355e-02,-1.100000000000000006e-01,-7.117793349823012816e-01,-8.910065241844883355e-02,1.100000000000000006e-01,-6.482206650176988161e-01,9.302286069769127863e-02,-1.265117085719802137e-01,-4.048512061144216023e-01,6.977139302309476321e-03,9.348829142801977354e-02,-3.351487938855777782e-01
+-1.095522403456330313e-01,4.378336598910975153e-01,-2.363195767019907884e-02,2.442778464420502366e-02,1.102372783091671860e-01,-2.808774127890996120e-01,4.144794111145022608e-01,-2.956860640198802903e-01,-3.318676187611625528e-01,-1.181813277384635708e-02,-1.744878856014606128e-02,-1.581207081680075649e-02,8.090169943699365707e-02,-1.100000000000000006e-01,-7.211449676609559267e-01,-8.090169943699365707e-02,1.100000000000000006e-01,-6.388550323390441710e-01,8.595086214873981501e-02,-1.280738699164004069e-01,-4.100306784330113308e-01,1.404913785126036402e-02,9.192613008359958038e-02,-3.299693215669885493e-01
+-1.980260120134645363e-01,3.907770986505106348e-01,-3.546144753853893578e-02,1.395745258984217550e-02,1.798060562205323620e-01,-2.498681818943152277e-01,5.040411986130283184e-01,-2.652653009971691067e-01,-3.478089728117775836e-01,-5.665123502180005252e-03,-1.886183327926058140e-02,-1.743836329126079165e-02,7.071067811805438474e-02,-1.100000000000000006e-01,-7.294974746834785861e-01,-7.071067811805438474e-02,1.100000000000000006e-01,-6.305025253165215116e-01,7.799363405961644291e-02,-1.291909925997436204e-01,-4.142244625943753977e-01,2.200636594038374305e-02,9.080900740025638074e-02,-3.257755374056245379e-01
+-2.895443046054196889e-01,3.420655581740487117e-01,-5.160187264121676026e-02,4.841596824165574423e-03,2.492728734090441933e-01,-2.178979182499236056e-01,5.905773675933626565e-01,-2.382376078091899552e-01,-3.489874358007360455e-01,3.968751818405243277e-03,-1.860051970963974913e-02,-1.872202140064241349e-02,5.877852522856322204e-02,-1.100000000000000006e-01,-7.366311896065942388e-01,-5.877852522856322204e-02,1.100000000000000006e-01,-6.233688103934058589e-01,6.934710979440068812e-02,-1.298355693540284850e-01,-4.173292937140898884e-01,3.065289020559951519e-02,9.016443064597151613e-02,-3.226707062859100472e-01
+-3.793666227296605964e-01,2.922088815102953374e-01,-7.120691346107653474e-02,-2.782043068486020343e-03,3.145830796580897926e-01,-1.851921758788236394e-01,6.714023036908834952e-01,-2.142641032467407780e-01,-3.490610897375459598e-01,1.639386155590089739e-02,-1.703940665419312675e-02,-1.958198324591720052e-02,4.539904997320434732e-02,-1.100000000000000006e-01,-7.423704566934534732e-01,-4.539904997320434732e-02,1.100000000000000006e-01,-6.176295433065466245e-01,6.022419547667086370e-02,-1.299917285603368888e-01,-4.192687205456437360e-01,3.977580452332934308e-02,9.000827143966309840e-02,-3.207312794543561996e-01
+-4.622966703133665201e-01,2.418044428670887980e-01,-9.227356492738787719e-02,-8.810760645769003321e-03,3.717175438123619946e-01,-1.520718893919749126e-01,7.407176961253740810e-01,-1.930679167290854370e-01,-3.490656931085966419e-01,3.098756273338343012e-02,-1.457753668233169667e-02,-1.996643096951403878e-02,3.090169943669578145e-02,-1.100000000000000006e-01,-7.465739561408425429e-01,-3.090169943669578145e-02,1.100000000000000006e-01,-6.134260438591575548e-01,5.084952753414529597e-02,-1.296556250607468486e-01,-4.199949879638555372e-01,4.915047246585577123e-02,9.034437493925313867e-02,-3.200050120361443984e-01
+-5.348385334569177862e-01,1.915338529915128762e-01,-1.124415214086432746e-01,-1.318858593770820542e-02,4.184620240933407675e-01,-1.189504629186127899e-01,7.942577162648637445e-01,-1.744406738126497436e-01,-3.490659808192872471e-01,4.719277263944708645e-02,-1.166413895996135097e-02,-1.985221780110883391e-02,1.564344650319677427e-02,-1.100000000000000006e-01,-7.491381838417513483e-01,-1.564344650319677427e-02,1.100000000000000006e-01,-6.108618161582487494e-01,4.145394140430967711e-02,-1.288355348388818267e-01,-4.194902128545454079e-01,5.854605859569138315e-02,9.116446516111816056e-02,-3.205097871454546943e-01
+-5.953693400309459927e-01,1.421519329416240374e-01,-1.297194457244093824e-01,-1.591602986320566140e-02,4.543397535405275245e-01,-8.632316183415066069e-02,8.301158477209291675e-01,-1.582451059990886699e-01,-3.490659988012054238e-01,6.451373185821052125e-02,-8.703821904213480606e-03,-1.924197278440780909e-02,-8.331482827768828746e-13,-1.100000000000000006e-01,-7.500000000000000000e-01,8.331482827768828746e-13,1.100000000000000006e-01,-6.100000000000000977e-01,3.226878759984222467e-02,-1.275516512377275480e-01,-4.177668244561572042e-01,6.773121240015878008e-02,9.244834876227243925e-02,-3.222331755438430090e-01
+-6.433256773754315594e-01,9.447163462062838080e-02,-1.426945809663817122e-01,-1.705646484156018300e-02,4.797609735127505437e-01,-5.475217720488427531e-02,8.476869101485723368e-01,-1.444180509873235763e-01,-3.459210837694575713e-01,8.251230611488559463e-02,-5.985677071109059624e-03,-1.815963020589101903e-02,-1.564344650484255847e-02,-1.100000000000000006e-01,-7.491381838415688277e-01,1.564344650484255847e-02,1.100000000000000006e-01,-6.108618161584312700e-01,2.352023509118662120e-02,-1.258355877325098293e-01,-4.148672583106574607e-01,7.647976490881433498e-02,9.416441226749017179e-02,-3.251327416893429190e-01
+-6.773332858468744666e-01,4.934908310924676633e-02,-1.498575406399128285e-01,-1.673834903910112470e-02,4.945905135250343587e-01,-2.485129274761414472e-02,8.412338040712271647e-01,-1.329767390237500124e-01,-3.118859117661963998e-01,1.008067836233384473e-01,-3.185372749360211586e-03,-1.664499566584920834e-02,-3.090169943828187729e-02,-1.100000000000000006e-01,-7.465739561404818314e-01,3.090169943828187729e-02,1.100000000000000006e-01,-6.134260438595182663e-01,1.542370227588629045e-02,-1.237295995020150918e-01,-4.108629113596561910e-01,8.457629772411387470e-02,9.627040049798490928e-02,-3.291370886403439111e-01
+-6.991592328527924671e-01,7.673188382985909536e-03,-1.516888329904508004e-01,-1.515302578474355538e-02,5.007475828907941295e-01,2.725583436531345098e-03,8.177541401303894952e-01,-1.240306783854028400e-01,-2.714130818259118394e-01,1.190744289975680936e-01,-7.917428047640683291e-04,-1.474786567648514110e-02,-4.539904997468902775e-02,-1.100000000000000006e-01,-7.423704566929238968e-01,4.539904997468902775e-02,1.100000000000000006e-01,-6.176295433070762009e-01,8.178552662706554954e-03,-1.212855429658527273e-01,-4.058523839147528123e-01,9.182144733729298569e-02,9.871445703414727380e-02,-3.341476160852467903e-01
+-7.098632864872022052e-01,-2.963590180050087314e-02,-1.487310921670922659e-01,-1.254818146274863482e-02,4.994660274916110088e-01,2.728787781594462641e-02,7.809684223214512500e-01,-1.178014005985540819e-01,-2.278042664151596897e-01,1.370588412574593740e-01,1.026656369227454957e-03,-1.252216408628205671e-02,-5.877852522991128259e-02,-1.100000000000000006e-01,-7.366311896059086761e-01,5.877852522991128259e-02,1.100000000000000006e-01,-6.233688103940914216e-01,1.963185880397330663e-03,-1.185635989073014485e-01,-3.999590517906286835e-01,9.803681411960227243e-02,1.014364010926985527e-01,-3.400409482093709190e-01
+-7.103901144863671302e-01,-6.161585822353330549e-02,-1.416878746221778562e-01,-9.217067174897453086e-03,4.917885642697952808e-01,4.810022722927509431e-02,7.340487569071268981e-01,-1.146525911130441278e-01,-1.832300851359860427e-01,1.545832616045489660e-01,2.367965080507700420e-03,-1.002054977250318307e-02,-7.071067811923263668e-02,-1.100000000000000006e-01,-7.294974746826539125e-01,7.071067811923263668e-02,1.100000000000000006e-01,-6.305025253173461852e-01,-3.069355113241946376e-03,-1.156307906226971827e-01,-3.933280283830271618e-01,1.030693551132416536e-01,1.043692093773028184e-01,-3.466719716169723853e-01
+-7.018536152204816192e-01,-8.723604095548030679e-02,-1.314589164201845628e-01,-5.483080760886389037e-03,4.787833981377027648e-01,6.436012173448031615e-02,6.803817301656713834e-01,-1.151334353457041104e-01,-1.398613826558609829e-01,1.715712081087789331e-01,3.411449538285334700e-03,-7.290000458925260246e-03,-8.090169943797308194e-02,-1.100000000000000006e-01,-7.211449676600123482e-01,8.090169943797308194e-02,1.100000000000000006e-01,-6.388550323399877495e-01,-6.795152456901959459e-03,-1.125593335854394861e-01,-3.861225914953482774e-01,1.067951524569017568e-01,1.074406664145605150e-01,-3.538774085046512141e-01
+-6.854951399733906214e-01,-1.053548694620263931e-01,-1.190053900472222148e-01,-1.678016517403129295e-03,4.615221586746952043e-01,7.516005639138408079e-02,6.233272708712306320e-01,-1.200377521517016211e-01,-9.974724695523021212e-02,1.880758526944679709e-01,4.366040839645156206e-03,-4.369022085530769282e-03,-8.910065241920467338e-02,-1.100000000000000006e-01,-7.117793349812628900e-01,8.910065241920467338e-02,1.100000000000000006e-01,-6.482206650187372077e-01,-9.122464654769388281e-03,-1.094248572613671089e-01,-3.785201628972406640e-01,1.091224646547692689e-01,1.105751427386328922e-01,-3.614798371027587720e-01
+-6.625800878589288567e-01,-1.146620808153216708e-01,-1.052190971437854394e-01,1.890103041095147216e-03,4.410041489827525307e-01,7.943570573500077781e-02,5.658964679586006019e-01,-1.304791654646706711e-01,-6.461523056105683560e-02,2.043186049005513150e-01,5.419406970944807070e-03,-1.287435097976856631e-03,-9.510565162976469811e-02,-1.100000000000000006e-01,-7.016311896057092490e-01,9.510565162976469811e-02,1.100000000000000006e-01,-6.583688103942908487e-01,-9.993985556626394651e-03,-1.063045428603091730e-01,-3.707079396118036496e-01,1.099939855566263863e-01,1.136954571396908281e-01,-3.692920603881957864e-01
+-6.342675291537496207e-01,-1.136141537205470481e-01,-9.083235138972453604e-02,4.987495030981368288e-03,4.180607698328965838e-01,7.590858215689032240e-02,5.104581687365108422e-01,-1.479745070392482764e-01,-3.567820158461018631e-02,2.207334564726170512e-01,6.698175941235383693e-03,1.929766589271446602e-03,-9.876883405963990392e-02,-1.100000000000000006e-01,-6.909504125522587525e-01,9.876883405963990392e-02,1.100000000000000006e-01,-6.690495874477413452e-01,-9.388255425456980274e-03,-1.032752228785489557e-01,-3.628782845036057081e-01,1.093882554254570760e-01,1.167247771214510454e-01,-3.771217154963937279e-01
+-6.015091030957360196e-01,-1.003892154367416467e-01,-7.639017381923590699e-02,7.536003586295941803e-03,3.932898026079165721e-01,6.304935679262420323e-02,4.585879697235172303e-01,-1.745055716396768652e-01,-1.353823766627111971e-02,2.380022910166121886e-01,8.248665217521261930e-03,5.252174634895081032e-03,-1.000000000000000056e-01,-1.100000000000000006e-01,-6.799999999994381650e-01,1.000000000000000056e-01,1.100000000000000006e-01,-6.800000000005619327e-01,-7.320189347393812884e-03,-1.004114892277750415e-01,-3.552239896665490004e-01,1.073201893473940127e-01,1.195885107722249596e-01,-3.847760103334504356e-01
+-5.650199172955213678e-01,-7.293045398778566502e-02,-6.227748628548604448e-02,9.739606996928563618e-03,3.670525667950366722e-01,3.912876259550156915e-02,4.111058022712885118e-01,-2.124776593414052506e-01,1.772078937917348669e-03,2.570391413975707806e-01,1.003981562882686786e-02,8.624325639868531818e-03,-9.876883405938874372e-02,-1.100000000000000006e-01,-6.690495874466312332e-01,9.876883405938874372e-02,1.100000000000000006e-01,-6.909504125533688645e-01,-3.840709972796611804e-03,-9.778385653465600236e-02,-3.479335292426685156e-01,1.038407099727969018e-01,1.222161434653439988e-01,-3.920664707573310315e-01
+-5.253190287839597516e-01,-2.922878092514183401e-02,-4.877165008235853638e-02,1.225311428533613391e-02,3.395273341117023280e-01,2.497974191135647268e-03,3.682489008887789850e-01,-2.643954788368254594e-01,1.064761765373501735e-02,2.788295816947658490e-01,1.198181587154546583e-02,1.193481551203763244e-02,-9.510565162926942762e-02,-1.100000000000000006e-01,-6.583688103932239244e-01,9.510565162926942762e-02,1.100000000000000006e-01,-7.016311896067761733e-01,9.645063684020904748e-04,-9.545702583670932773e-02,-3.411864185632509927e-01,9.903549363159828978e-02,1.245429741632906734e-01,-3.988135814367485543e-01
+-4.828051591262644826e-01,3.191699582810210434e-02,-3.609134981961047844e-02,1.631742097955054052e-02,3.107876914939162183e-01,-4.768801171726122501e-02,3.298837045280956226e-01,-3.319682847550239901e-01,1.374068819080789469e-02,3.039753575661072182e-01,1.395079121649438203e-02,1.498012027527626314e-02,-8.910065241847706097e-02,-1.100000000000000006e-01,-6.482206650177375629e-01,8.910065241847706097e-02,1.100000000000000006e-01,-7.117793349822625348e-01,6.977139302283323630e-03,-9.348829142802679570e-02,-3.351487938856002047e-01,9.302286069771714683e-02,1.265117085719731915e-01,-4.048512061143993979e-01
+-4.378336598912829225e-01,1.095522403452946492e-01,-2.442778464424975177e-02,2.363195767016100513e-02,2.808774127892224581e-01,-1.102372783088971797e-01,2.956860640200095203e-01,-4.144794111141487658e-01,1.181813277386372860e-02,3.318676187610499762e-01,1.581207081679368576e-02,1.744878856013791502e-02,-8.090169943703104383e-02,-1.100000000000000006e-01,-6.388550323390801422e-01,8.090169943703104383e-02,1.100000000000000006e-01,-7.211449676609199555e-01,1.404913785123033249e-02,-9.192613008360503435e-02,-3.299693215670073121e-01,8.595086214877019348e-02,1.280738699163949668e-01,-4.100306784329923460e-01
+-3.907770986507053124e-01,1.980260120131052681e-01,-1.395745258988218690e-02,3.546144753848342462e-02,2.498681818944435418e-01,-1.798060562202546675e-01,2.652653009972861242e-01,-5.040411986126824839e-01,5.665123502213952923e-03,3.478089728117634283e-01,1.743836329125455706e-02,1.886183327925843728e-02,-7.071067811809936265e-02,-1.100000000000000006e-01,-6.305025253165529309e-01,7.071067811809936265e-02,1.100000000000000006e-01,-7.294974746834471668e-01,2.200636594035056126e-02,-9.080900740025996121e-02,-3.257755374056391373e-01,7.799363405965001328e-02,1.291909925997400399e-01,-4.142244625943606318e-01
+-3.420655581742484408e-01,2.895443046050537039e-01,-4.841596824199583676e-03,5.160187264114429739e-02,2.178979182500545841e-01,-2.492728734087716058e-01,2.382376078092925953e-01,-5.905773675930263700e-01,-3.968751818358803862e-03,3.489874358007352129e-01,1.872202140063782341e-02,1.860051970964363838e-02,-5.877852522861468088e-02,-1.100000000000000006e-01,-6.233688103934319491e-01,5.877852522861468088e-02,1.100000000000000006e-01,-7.366311896065681486e-01,3.065289020556399846e-02,-9.016443064597313983e-02,-3.226707062859201502e-01,6.934710979443661771e-02,1.298355693540268474e-01,-4.173292937140796743e-01
+-2.922088815104880166e-01,3.793666227293221449e-01,2.782043068459848570e-03,7.120691346099575214e-02,1.851921758789499828e-01,-3.145830796578493738e-01,2.142641032468260986e-01,-6.714023036905865105e-01,-1.639386155584899793e-02,3.490610897375459043e-01,1.958198324591487946e-02,1.703940665420125913e-02,-4.539904997325849151e-02,-1.100000000000000006e-01,-6.176295433065659424e-01,4.539904997325849151e-02,1.100000000000000006e-01,-7.423704566934341553e-01,3.977580452329405186e-02,-9.000827143966273758e-02,-3.207312794543613066e-01,6.022419547670658513e-02,1.299917285603372497e-01,-4.192687205456385735e-01
+-2.418044428672874446e-01,4.622966703130563793e-01,8.810760645748538789e-03,9.227356492730445781e-02,1.520718893921056691e-01,-3.717175438121549935e-01,1.930679167291627640e-01,-7.407176961251279446e-01,-3.098756273332090375e-02,3.490656931085965864e-01,1.996643096951349061e-02,1.457753668234262716e-02,-3.090169943675492165e-02,-1.100000000000000006e-01,-6.134260438591709885e-01,3.090169943675492165e-02,1.100000000000000006e-01,-7.465739561408291092e-01,4.915047246581825263e-02,-9.034437493925084883e-02,-3.200050120361448425e-01,5.084952753418239824e-02,1.296556250607491523e-01,-4.199949879638551486e-01
+-1.915338529917099408e-01,5.348385334566525540e-01,1.318858593769420967e-02,1.124415214085675019e-01,1.189504629187430884e-01,-4.184620240931764545e-01,1.744406738127176337e-01,-7.942577162646845546e-01,-4.719277263937961958e-02,3.490659808192872471e-01,1.985221780111027373e-02,1.166413895997328587e-02,-1.564344650325819389e-02,-1.100000000000000006e-01,-6.108618161582556327e-01,1.564344650325819389e-02,1.100000000000000006e-01,-7.491381838417444650e-01,5.854605859565424619e-02,-9.116446516111398335e-02,-3.205097871454502534e-01,4.145394140434639774e-02,1.288355348388860178e-01,-4.194902128545498488e-01
+-1.421519329418154398e-01,5.953693400307304984e-01,1.591602986319812923e-02,1.297194457243485421e-01,8.632316183427758693e-02,-4.543397535404062881e-01,1.582451059991465958e-01,-8.301158477208221420e-01,-6.451373185814120170e-02,3.490659988012054238e-01,1.924197278441116057e-02,8.703821904225052947e-03,7.709635469298826121e-13,-1.100000000000000006e-01,-6.100000000000000977e-01,-7.709635469298826121e-13,1.100000000000000006e-01,-7.500000000000000000e-01,6.773121240012294764e-02,-9.244834876226647180e-02,-3.222331755438337941e-01,3.226878759987768241e-02,1.275516512377335154e-01,-4.177668244561663635e-01
+-9.447163462081137331e-02,6.433256773752703550e-01,1.705646484155876053e-02,1.426945809663417164e-01,5.475217720500548391e-02,-4.797609735126721064e-01,1.444180509873724538e-01,-8.476869101485516866e-01,-8.251230611481494281e-02,3.459210837695665397e-01,1.815963020589619892e-02,5.985677071118945813e-03,1.564344650478113538e-02,-1.100000000000000006e-01,-6.108618161584244977e-01,-1.564344650478113538e-02,1.100000000000000006e-01,-7.491381838415756000e-01,7.647976490878066747e-02,-9.416441226748258064e-02,-3.251327416893291522e-01,2.352023509121991748e-02,1.258355877325174066e-01,-4.148672583106711165e-01
+-4.934908310942229259e-02,6.773332858467637774e-01,1.673834903910523947e-02,1.498575406398956478e-01,2.485129274773045793e-02,-4.945905135249938356e-01,1.329767390237907854e-01,-8.412338040712928899e-01,-1.008067836232646175e-01,3.118859117663513314e-01,1.664499566585631377e-02,3.185372749370965137e-03,3.090169943822138054e-02,-1.100000000000000006e-01,-6.134260438595046105e-01,-3.090169943822138054e-02,1.100000000000000006e-01,-7.465739561404954872e-01,8.457629772408321867e-02,-9.627040049797565280e-02,-3.291370886403259255e-01,1.542370227591731424e-02,1.237295995020243483e-01,-4.108629113596743987e-01
+-7.673188383148987421e-03,6.991592328527280742e-01,1.515302578475222380e-02,1.516888329904537425e-01,-2.725583436423561524e-03,-5.007475828907853588e-01,1.240306783854368544e-01,-8.177541401305147284e-01,-1.190744289974959985e-01,2.714130818260837019e-01,1.474786567649351808e-02,7.917428047724508382e-04,4.539904997463235087e-02,-1.100000000000000006e-01,-6.176295433070559948e-01,-4.539904997463235087e-02,1.100000000000000006e-01,-7.423704566929441029e-01,9.182144733726609054e-02,-9.871445703413676831e-02,-3.341476160852250299e-01,8.178552662734386858e-03,1.212855429658632328e-01,-4.058523839147753498e-01
+2.963590180035804295e-02,7.098632864871801118e-01,1.254818146276090104e-02,1.487310921671130826e-01,-2.728787781585080563e-02,-4.994660274916296605e-01,1.178014005985748847e-01,-7.809684223216225574e-01,-1.370588412573852666e-01,2.278042664153364927e-01,1.252216408629304792e-02,-1.026656369221494447e-03,5.877852522985982375e-02,-1.100000000000000006e-01,-6.233688103940652203e-01,-5.877852522985982375e-02,1.100000000000000006e-01,-7.366311896059348774e-01,9.803681411957980429e-02,-1.014364010926870480e-01,-3.400409482093458835e-01,1.963185880420589835e-03,1.185635989073129531e-01,-3.999590517906545517e-01
+6.161585822341939661e-02,7.103901144863836725e-01,9.217067174911341282e-03,1.416878746222119956e-01,-4.810022722920155591e-02,-4.917885642698361925e-01,1.146525911130522046e-01,-7.340487569073245178e-01,-1.545832616044841568e-01,1.832300851361586824e-01,1.002054977251306406e-02,-2.367965080503002789e-03,7.071067811918967105e-02,-1.100000000000000006e-01,-6.305025253173162092e-01,-7.071067811918967105e-02,1.100000000000000006e-01,-7.294974746826838885e-01,1.030693551132249447e-01,-1.043692093772911611e-01,-3.466719716169459620e-01,-3.069355113224633835e-03,1.156307906227088400e-01,-3.933280283830544732e-01
+8.723604095539370940e-02,7.018536152205303580e-01,5.483080760901221790e-03,1.314589164202289717e-01,-6.436012173442598461e-02,-4.787833981377620507e-01,1.151334353456955617e-01,-6.803817301658873218e-01,-1.715712081087133745e-01,1.398613826560247686e-01,7.290000458937614947e-03,-3.411449538281670964e-03,8.090169943793736052e-02,-1.100000000000000006e-01,-6.388550323399533326e-01,-8.090169943793736052e-02,1.100000000000000006e-01,-7.211449676600467651e-01,1.067951524568902105e-01,-1.074406664145484691e-01,-3.538774085046229589e-01,-6.795152456889996806e-03,1.125593335854515320e-01,-3.861225914953775318e-01
+1.053548694619715204e-01,6.854951399734678930e-01,1.678016517417664760e-03,1.190053900472734655e-01,-7.516005639135346639e-02,-4.615221586747687565e-01,1.200377521516740320e-01,-6.233272708714548971e-01,-1.880758526944066034e-01,9.974724695537758035e-02,4.369022085542377185e-03,-4.366040839641077004e-03,8.910065241917708434e-02,-1.100000000000000006e-01,-6.482206650186992380e-01,-8.910065241917708434e-02,1.100000000000000006e-01,-7.117793349813008597e-01,1.091224646547631766e-01,-1.105751427386207492e-01,-3.614798371027293511e-01,-9.122464654763066949e-03,1.094248572613792519e-01,-3.785201628972711396e-01
+1.146620808153042959e-01,6.625800878590279996e-01,-1.890103041082177339e-03,1.052190971438401179e-01,-7.943570573499819654e-02,-4.410041489828365746e-01,1.304791654646182408e-01,-5.658964679588195379e-01,-2.043186049004888372e-01,6.461523056118199937e-02,1.287435097989010537e-03,-5.419406970940253421e-03,9.510565162974592146e-02,-1.100000000000000006e-01,-6.583688103942504366e-01,-9.510565162974592146e-02,1.100000000000000006e-01,-7.016311896057496611e-01,1.099939855566258728e-01,-1.136954571396788793e-01,-3.692920603881659769e-01,-9.993985556625867295e-03,1.063045428603211218e-01,-3.707079396118345693e-01
+1.136141537205747759e-01,6.342675291538726334e-01,-4.987495030969934726e-03,9.083235138978291989e-02,-7.590858215692247724e-02,-4.180607698329927846e-01,1.479745070391605688e-01,-5.104581687367273357e-01,-2.207334564725493553e-01,3.567820158471336767e-02,-1.929766589258155368e-03,-6.698175941229672116e-03,9.876883405962993967e-02,-1.100000000000000006e-01,-6.690495874476973803e-01,-9.876883405962993967e-02,1.100000000000000006e-01,-6.909504125523027174e-01,1.093882554254624190e-01,-1.167247771214390689e-01,-3.771217154963628082e-01,-9.388255425462510573e-03,1.032752228785609322e-01,-3.628782845036377380e-01
+1.003892154368232342e-01,6.015091030958751306e-01,-7.536003586286564755e-03,7.639017381929347206e-02,-6.304935679269799143e-02,-3.932898026080190457e-01,1.745055716395472745e-01,-4.585879697237166264e-01,-2.380022910165390526e-01,1.353823766634605456e-02,-5.252174634881417482e-03,-8.248665217514449671e-03,1.000000000000000056e-01,-1.100000000000000006e-01,-6.800000000005174128e-01,-1.000000000000000056e-01,1.100000000000000006e-01,-6.799999999994826849e-01,1.073201893474051011e-01,-1.195885107722138019e-01,-3.847760103334205706e-01,-7.320189347405282876e-03,1.004114892277861992e-01,-3.552239896665799201e-01
+7.293045398792959155e-02,5.650199172956738014e-01,-9.739606996919681833e-03,6.227748628554156257e-02,-3.912876259562413084e-02,-3.670525667951444193e-01,2.124776593412236181e-01,-4.111058022714686455e-01,-2.570391413974877914e-01,-1.772078937869878395e-03,-8.624325639854657499e-03,-1.003981562881929059e-02,9.876883405939868021e-02,-1.100000000000000006e-01,-6.909504125533248997e-01,-9.876883405939868021e-02,1.100000000000000006e-01,-6.690495874466751980e-01,1.038407099728134581e-01,-1.222161434653339235e-01,-3.920664707573029428e-01,-3.840709972813736994e-03,9.778385653466607763e-02,-3.479335292426975479e-01
+2.922878092535335925e-02,5.253190287841251749e-01,-1.225311428532397003e-02,4.877165008241147320e-02,-2.497974191311107608e-03,-3.395273341118156818e-01,2.643954788365854847e-01,-3.682489008889417437e-01,-2.788295816946701478e-01,-1.064761765371206870e-02,-1.193481551202449364e-02,-1.198181587153731263e-02,9.510565162928909244e-02,-1.100000000000000006e-01,-7.016311896067338738e-01,-9.510565162928909244e-02,1.100000000000000006e-01,-6.583688103932662239e-01,9.903549363161989749e-02,-1.245429741632819304e-01,-3.988135814367230192e-01,9.645063683797264198e-04,9.545702583671807073e-02,-3.411864185632774160e-01
+-3.191699582781877542e-02,4.828051591264407305e-01,-1.631742097952865872e-02,3.609134981965973071e-02,4.768801171703090924e-02,-3.107876914940346236e-01,3.319682847547182902e-01,-3.298837045282412839e-01,-3.039753575659992491e-01,-1.374068819080673590e-02,-1.498012027526542805e-02,-1.395079121648638842e-02,8.910065241850594064e-02,-1.100000000000000006e-01,-7.117793349822228999e-01,-8.910065241850594064e-02,1.100000000000000006e-01,-6.482206650177771978e-01,9.302286069774329258e-02,-1.265117085719660306e-01,-4.048512061143769714e-01,6.977139302256268882e-03,9.348829142803397052e-02,-3.351487938856233528e-01
+-1.095522403449594590e-01,4.378336598914591149e-01,-2.363195767012351081e-02,2.442778464429232188e-02,1.102372783086300045e-01,-2.808774127893391981e-01,4.144794111137956594e-01,-2.956860640201317558e-01,-3.318676187609357897e-01,-1.181813277388067858e-02,-1.744878856012990406e-02,-1.581207081678679890e-02,8.090169943706676525e-02,-1.100000000000000006e-01,-7.211449676608855386e-01,-8.090169943706676525e-02,1.100000000000000006e-01,-6.388550323391145591e-01,8.595086214879886499e-02,-1.280738699163897487e-01,-4.100306784329744714e-01,1.404913785120062014e-02,9.192613008361023852e-02,-3.299693215670258528e-01
+-1.980260120127436130e-01,3.907770986508871669e-01,-3.546144753842724734e-02,1.395745258991936376e-02,1.798060562199745305e-01,-2.498681818945633903e-01,5.040411986123276566e-01,-2.652653009973923171e-01,-3.478089728117487733e-01,-5.665123502245090342e-03,-1.886183327925623418e-02,-1.743836329124933554e-02,7.071067811814232829e-02,-1.100000000000000006e-01,-7.294974746834170798e-01,-7.071067811814232829e-02,1.100000000000000006e-01,-6.305025253165830179e-01,7.799363405968169627e-02,-1.291909925997365982e-01,-4.142244625943466985e-01,2.200636594031774029e-02,9.080900740026338902e-02,-3.257755374056535702e-01
+-2.895443046046892732e-01,3.420655581744353468e-01,-5.160187264107197330e-02,4.841596824231188603e-03,2.492728734085004616e-01,-2.178979182501772083e-01,5.905773675926850874e-01,-2.382376078093862148e-01,-3.489874358007343247e-01,3.968751818316256300e-03,-1.860051970964757620e-02,-1.872202140063417702e-02,5.877852522866383600e-02,-1.100000000000000006e-01,-7.366311896065431686e-01,-5.877852522866383600e-02,1.100000000000000006e-01,-6.233688103934569291e-01,6.934710979447050727e-02,-1.298355693540252931e-01,-4.173292937140700154e-01,3.065289020552887725e-02,9.016443064597470802e-02,-3.226707062859300867e-01
+-3.793666227289659854e-01,2.922088815106889115e-01,-7.120691346091106988e-02,-2.782043068432452949e-03,3.145830796575973531e-01,-1.851921758790822103e-01,6.714023036902747599e-01,-2.142641032469146389e-01,-3.490610897375458488e-01,1.639386155579307738e-02,-1.703940665420986336e-02,-1.958198324591241962e-02,4.539904997331516145e-02,-1.100000000000000006e-01,-7.423704566934139493e-01,-4.539904997331516145e-02,1.100000000000000006e-01,-6.176295433065861484e-01,6.022419547674355556e-02,-1.299917285603376105e-01,-4.192687205456332444e-01,3.977580452325581162e-02,9.000827143966237676e-02,-3.207312794543668022e-01
+-4.622966703127380783e-01,2.418044428674886448e-01,-9.227356492721899839e-02,-8.810760645727746393e-03,3.717175438119429964e-01,-1.520718893922381465e-01,7.407176961248750358e-01,-1.930679167292397858e-01,-3.490656931085965864e-01,3.098756273325784655e-02,-1.457753668235397745e-02,-1.996643096951304999e-02,3.090169943681541839e-02,-1.100000000000000006e-01,-7.465739561408153424e-01,-3.090169943681541839e-02,1.100000000000000006e-01,-6.134260438591847553e-01,5.084952753421990990e-02,-1.296556250607514837e-01,-4.199949879638547046e-01,4.915047246577945034e-02,9.034437493924850349e-02,-3.200050120361453421e-01
+-5.348385334563807714e-01,1.915338529919093924e-01,-1.124415214084902026e-01,-1.318858593768011504e-02,4.184620240930084778e-01,-1.189504629188747886e-01,7.942577162645009237e-01,-1.744406738127850243e-01,-3.490659808192872471e-01,4.719277263931068167e-02,-1.166413895998552434e-02,-1.985221780111186274e-02,1.564344650332101516e-02,-1.100000000000000006e-01,-7.491381838417374706e-01,-1.564344650332101516e-02,1.100000000000000006e-01,-6.108618161582626271e-01,4.145394140438353470e-02,-1.288355348388902921e-01,-4.194902128545542896e-01,5.854605859561583248e-02,9.116446516110969511e-02,-3.205097871454456460e-01
+-5.953693400305102301e-01,1.421519329420109501e-01,-1.297194457242865084e-01,-1.591602986319042359e-02,4.543397535402824983e-01,-8.632316183440727486e-02,8.301158477207140063e-01,-1.582451059992052156e-01,-3.490659988012054238e-01,6.451373185806490163e-02,-8.703821904236424059e-03,-1.924197278441473410e-02,-7.073577256113622300e-13,-1.100000000000000006e-01,-7.500000000000000000e-01,7.073577256113622300e-13,1.100000000000000006e-01,-6.100000000000000977e-01,3.226878759991351486e-02,-1.275516512377396217e-01,-4.177668244561756339e-01,6.773121240008586619e-02,9.244834876226036557e-02,-3.222331755438242462e-01
+-6.433256773751050428e-01,9.447163462099823772e-02,-1.426945809663007769e-01,-1.705646484155724091e-02,4.797609735125917818e-01,-5.475217720512883662e-02,8.476869101485300373e-01,-1.444180509874213314e-01,-3.459210837696723440e-01,8.251230611473700516e-02,-5.985677071128797308e-03,-1.815963020590156268e-02,-1.564344650471831411e-02,-1.100000000000000006e-01,-7.491381838415825944e-01,1.564344650471831411e-02,1.100000000000000006e-01,-6.108618161584175033e-01,2.352023509125358153e-02,-1.258355877325251782e-01,-4.148672583106848832e-01,7.647976490874584810e-02,9.416441226747480908e-02,-3.251327416893148303e-01
+-6.773332858466549755e-01,4.934908310958849298e-02,-1.498575406398778842e-01,-1.673834903910905239e-02,4.945905135249530904e-01,-2.485129274784065798e-02,8.412338040713519538e-01,-1.329767390238274227e-01,-3.118859117664984359e-01,1.008067836231921477e-01,-3.185372749381433326e-03,-1.664499566586285367e-02,-3.090169943816359344e-02,-1.100000000000000006e-01,-7.465739561405086988e-01,3.090169943816359344e-02,1.100000000000000006e-01,-6.134260438594913989e-01,1.542370227594658250e-02,-1.237295995020331746e-01,-4.108629113596916071e-01,8.457629772405289570e-02,9.627040049796682653e-02,-3.291370886403081064e-01
+-6.991592328526649025e-01,7.673188383300203266e-03,-1.516888329904560184e-01,-1.515302578476057302e-02,5.007475828907762549e-01,2.725583436323630177e-03,8.177541401306324120e-01,-1.240306783854639300e-01,-2.714130818262477929e-01,1.190744289974245834e-01,-7.917428047806544539e-04,-1.474786567650163485e-02,-4.539904997457821362e-02,-1.100000000000000006e-01,-7.423704566929634208e-01,4.539904997457821362e-02,1.100000000000000006e-01,-6.176295433070366769e-01,8.178552662760053826e-03,-1.212855429658732664e-01,-4.058523839147961665e-01,9.182144733723948682e-02,9.871445703412673467e-02,-3.341476160852034361e-01
+-7.098632864871590176e-01,-2.963590180022520129e-02,-1.487310921671329556e-01,-1.254818146277256706e-02,4.994660274916477016e-01,2.728787781576376414e-02,7.809684223217870924e-01,-1.178014005985918849e-01,-2.278042664155120467e-01,1.370588412573186532e-01,1.026656369215129747e-03,-1.252216408630196787e-02,-5.877852522981066863e-02,-1.100000000000000006e-01,-7.366311896059598574e-01,5.877852522981066863e-02,1.100000000000000006e-01,-6.233688103940402403e-01,1.963185880442051834e-03,-1.185635989073239305e-01,-3.999590517906784770e-01,9.803681411955755820e-02,1.014364010926760706e-01,-3.400409482093211255e-01
+-7.103901144864004369e-01,-6.161585822330365586e-02,-1.416878746222473839e-01,-9.217067174925779385e-03,4.917885642698786031e-01,4.810022722912633830e-02,7.340487569075299090e-01,-1.146525911130561320e-01,-1.832300851363381500e-01,1.545832616044131302e-01,2.367965080498261356e-03,-1.002054977252506140e-02,-7.071067811914469314e-02,-1.100000000000000006e-01,-7.294974746827154188e-01,7.071067811914469314e-02,1.100000000000000006e-01,-6.305025253172846789e-01,-3.069355113207133945e-03,-1.156307906227210386e-01,-3.933280283830821178e-01,1.030693551132068342e-01,1.043692093772789625e-01,-3.466719716169173737e-01
+-7.018536152205819834e-01,-8.723604095530551605e-02,-1.314589164202757954e-01,-5.483080760916714605e-03,4.787833981378244452e-01,6.436012173437134776e-02,6.803817301661142514e-01,-1.151334353456840570e-01,-1.398613826561949935e-01,1.715712081086453178e-01,3.411449538277771740e-03,-7.290000458949142184e-03,-8.090169943789997375e-02,-1.100000000000000006e-01,-7.211449676600827363e-01,8.090169943789997375e-02,1.100000000000000006e-01,-6.388550323399173614e-01,-6.795152456877895375e-03,-1.125593335854641469e-01,-3.861225914954071192e-01,1.067951524568776928e-01,1.074406664145358542e-01,-3.538774085045923168e-01
+-6.854951399735483841e-01,-1.053548694619158843e-01,-1.190053900473273946e-01,-1.678016517432687465e-03,4.615221586748464722e-01,7.516005639132282423e-02,6.233272708716889321e-01,-1.200377521516428764e-01,-9.974724695553184584e-02,1.880758526943395736e-01,4.366040839637306582e-03,-4.369022085554471677e-03,-8.910065241914820466e-02,-1.100000000000000006e-01,-7.117793349813404946e-01,8.910065241914820466e-02,1.100000000000000006e-01,-6.482206650186596031e-01,-9.122464654756669289e-03,-1.094248572613919640e-01,-3.785201628973019483e-01,1.091224646547565569e-01,1.105751427386080371e-01,-3.614798371026974877e-01
+-6.625800878591332488e-01,-1.146620808152868098e-01,-1.052190971438978634e-01,1.890103041068557158e-03,4.410041489829255590e-01,7.943570573499603160e-02,5.658964679590506863e-01,-1.304791654645624244e-01,-6.461523056131256160e-02,2.043186049004229177e-01,5.419406970935540177e-03,-1.287435098001809327e-03,-9.510565162972625664e-02,-1.100000000000000006e-01,-7.016311896057920716e-01,9.510565162972625664e-02,1.100000000000000006e-01,-6.583688103942080261e-01,-9.993985556625333000e-03,-1.063045428603336257e-01,-3.707079396118658221e-01,1.099939855566253316e-01,1.136954571396663755e-01,-3.692920603881336139e-01
+-6.342675291539978666e-01,-1.136141537206016711e-01,-9.083235138984192825e-02,4.987495030958478612e-03,4.180607698330904287e-01,7.590858215695403532e-02,5.104581687369466048e-01,-1.479745070390736661e-01,-3.567820158481709025e-02,2.207334564724822423e-01,6.698175941224017785e-03,1.929766589244967566e-03,-9.876883405962000317e-02,-1.100000000000000006e-01,-6.909504125523467932e-01,9.876883405962000317e-02,1.100000000000000006e-01,-6.690495874476533045e-01,-9.388255425467853521e-03,-1.032752228785729087e-01,-3.628782845036686577e-01,1.093882554254679562e-01,1.167247771214270924e-01,-3.771217154963307783e-01
+-6.015091030960170171e-01,-1.003892154369023654e-01,-7.639017381935199469e-02,7.536003586277186840e-03,3.932898026081234621e-01,6.304935679276992000e-02,4.585879697239199637e-01,-1.745055716394208478e-01,-1.353823766642251597e-02,2.380022910164673322e-01,8.248665217507642616e-03,5.252174634867860618e-03,-1.000000000000000056e-01,-1.100000000000000006e-01,-6.799999999995272049e-01,1.000000000000000056e-01,1.100000000000000006e-01,-6.800000000004728928e-01,-7.320189347416371228e-03,-1.004114892277973708e-01,-3.552239896666097851e-01,1.073201893474165780e-01,1.195885107722026303e-01,-3.847760103333897064e-01
+-5.650199172958235705e-01,-7.293045398806533020e-02,-6.227748628559569982e-02,9.739606996911129647e-03,3.670525667952497240e-01,3.912876259574021159e-02,4.111058022716461702e-01,-2.124776593410519498e-01,1.772078937822403784e-03,2.570391413974100758e-01,1.003981562881199434e-02,8.624325639841589827e-03,-9.876883405940820038e-02,-1.100000000000000006e-01,-6.690495874467172754e-01,9.876883405940820038e-02,1.100000000000000006e-01,-6.909504125532828223e-01,-3.840709972829550733e-03,-9.778385653467569494e-02,-3.479335292427243043e-01,1.038407099728298338e-01,1.222161434653243062e-01,-3.920664707572751873e-01
+-5.253190287842858242e-01,-2.922878092555675211e-02,-4.877165008246245326e-02,1.225311428531212013e-02,3.395273341119250943e-01,2.497974191479573544e-03,3.682489008891002280e-01,-2.643954788363531150e-01,1.064761765368860309e-02,2.788295816945809968e-01,1.198181587152982730e-02,1.193481551201227772e-02,-9.510565162930786909e-02,-1.100000000000000006e-01,-6.583688103933067470e-01,9.510565162930786909e-02,1.100000000000000006e-01,-7.016311896066933507e-01,9.645063683590901493e-04,-9.545702583672641128e-02,-3.411864185633017854e-01,9.903549363164128316e-02,1.245429741632735898e-01,-3.988135814366977616e-01
+-4.828051591266113163e-01,3.191699582754802672e-02,-3.609134981970711642e-02,1.631742097950772061e-02,3.107876914941485325e-01,-4.768801171681027323e-02,3.298837045283825598e-01,-3.319682847544247473e-01,1.374068819080418238e-02,3.039753575658954432e-01,1.395079121647903667e-02,1.498012027525415756e-02,-8.910065241853352969e-02,-1.100000000000000006e-01,-6.482206650178151675e-01,8.910065241853352969e-02,1.100000000000000006e-01,-7.117793349821849302e-01,6.977139302231309681e-03,-9.348829142804082615e-02,-3.351487938856447801e-01,9.302286069776914690e-02,1.265117085719591750e-01,-4.048512061143548224e-01
+-4.378336598916481304e-01,1.095522403446218956e-01,-2.442778464433769878e-02,2.363195767008557935e-02,2.808774127894640427e-01,-1.102372783083607338e-01,2.956860640202653712e-01,-4.144794111134432191e-01,1.181813277389636221e-02,3.318676187608236572e-01,1.581207081677964491e-02,1.744878856012175086e-02,-8.090169943710413814e-02,-1.100000000000000006e-01,-6.388550323391506414e-01,8.090169943710413814e-02,1.100000000000000006e-01,-7.211449676608494563e-01,1.404913785117058861e-02,-9.192613008361567861e-02,-3.299693215670445601e-01,8.595086214882993736e-02,1.280738699163843086e-01,-4.100306784329550980e-01
+-3.907770986510833988e-01,1.980260120123834566e-01,-1.395745258995946189e-02,3.546144753837154884e-02,2.498681818946918709e-01,-1.798060562196961143e-01,2.652653009975106113e-01,-5.040411986119801568e-01,5.665123502276842721e-03,3.478089728117350066e-01,1.743836329124327095e-02,1.886183327925416986e-02,-7.071067811818730620e-02,-1.100000000000000006e-01,-6.305025253166145482e-01,7.071067811818730620e-02,1.100000000000000006e-01,-7.294974746833855495e-01,2.200636594028455850e-02,-9.080900740026696949e-02,-3.257755374056681141e-01,7.799363405971601604e-02,1.291909925997330177e-01,-4.142244625943315994e-01
+-3.420655581746375740e-01,2.895443046043253976e-01,-4.841596824265553475e-03,5.160187264100010024e-02,2.178979182503094358e-01,-2.492728734082298447e-01,2.382376078094918248e-01,-5.905773675923516874e-01,-3.968751818271545537e-03,3.489874358007334365e-01,1.872202140062956266e-02,1.860051970965153484e-02,-5.877852522871529484e-02,-1.100000000000000006e-01,-6.233688103934831304e-01,5.877852522871529484e-02,1.100000000000000006e-01,-7.366311896065169673e-01,3.065289020549336399e-02,-9.016443064597633172e-02,-3.226707062859401898e-01,6.934710979450725565e-02,1.298355693540236555e-01,-4.173292937140596348e-01
+-2.922088815108963011e-01,3.793666227286219828e-01,2.782043068404165681e-03,7.120691346082957951e-02,1.851921758792182682e-01,-3.145830796573537147e-01,2.142641032470103679e-01,-6.714023036899798846e-01,-1.639386155573670234e-02,3.490610897375457933e-01,1.958198324590962672e-02,1.703940665421783268e-02,-4.539904997337183140e-02,-1.100000000000000006e-01,-6.176295433066063545e-01,4.539904997337183140e-02,1.100000000000000006e-01,-7.423704566933937432e-01,3.977580452321884119e-02,-9.000827143966201593e-02,-3.207312794543721313e-01,6.022419547678180274e-02,1.299917285603379713e-01,-4.192687205456277488e-01
+-2.418044428676974222e-01,4.622966703124277155e-01,8.810760645706086636e-03,9.227356492713595371e-02,1.520718893923756754e-01,-3.717175438117360509e-01,1.930679167293250509e-01,-7.407176961246331182e-01,-3.098756273319270768e-02,3.490656931085966419e-01,1.996643096951223467e-02,1.457753668236481254e-02,-3.090169943687590820e-02,-1.100000000000000006e-01,-6.134260438591985221e-01,3.090169943687590820e-02,1.100000000000000006e-01,-7.465739561408015756e-01,4.915047246574193868e-02,-9.034437493924614426e-02,-3.200050120361457862e-01,5.084952753425871913e-02,1.296556250607538430e-01,-4.199949879638542050e-01
+-1.915338529921057076e-01,5.348385334561241988e-01,1.318858593766613144e-02,1.124415214084170944e-01,1.189504629190040880e-01,-4.184620240928494939e-01,1.744406738128556900e-01,-7.942577162643290611e-01,-4.719277263924671201e-02,3.490659808192873026e-01,1.985221780111319154e-02,1.166413895999699434e-02,-1.564344650338103312e-02,-1.100000000000000006e-01,-6.108618161582691775e-01,1.564344650338103312e-02,1.100000000000000006e-01,-7.491381838417309202e-01,5.854605859558038861e-02,-9.116446516110561504e-02,-3.205097871454413716e-01,4.145394140442026226e-02,1.288355348388943722e-01,-4.194902128545586750e-01
+-1.421519329422006872e-01,5.953693400303003980e-01,1.591602986318299204e-02,1.297194457242272503e-01,8.632316183453239700e-02,-4.543397535401642040e-01,1.582451059992655562e-01,-8.301158477206096453e-01,-6.451373185800224341e-02,3.490659988012054238e-01,1.924197278441820008e-02,8.703821904247788233e-03,6.465940752358821880e-13,-1.100000000000000006e-01,-6.100000000000000977e-01,-6.465940752358821880e-13,1.100000000000000006e-01,-7.500000000000000000e-01,6.773121240005165744e-02,-9.244834876225453690e-02,-3.222331755438154199e-01,3.226878759994896567e-02,1.275516512377454503e-01,-4.177668244561847377e-01
+-9.447163462117996735e-02,6.433256773749487234e-01,1.705646484155574905e-02,1.426945809662620579e-01,5.475217720524899051e-02,-4.797609735125160646e-01,1.444180509874728180e-01,-8.476869101485113855e-01,-8.251230611467152976e-02,3.459210837697815899e-01,1.815963020590645807e-02,5.985677071138589822e-03,1.564344650465829961e-02,-1.100000000000000006e-01,-6.108618161584108419e-01,-1.564344650465829961e-02,1.100000000000000006e-01,-7.491381838415892558e-01,7.647976490871370714e-02,-9.416441226746738447e-02,-3.251327416893016742e-01,2.352023509128687781e-02,1.258355877325326166e-01,-4.148672583106985390e-01
+-4.934908310976719725e-02,6.773332858465443973e-01,1.673834903911302838e-02,1.498575406398606757e-01,2.485129274795898693e-02,-4.945905135249126228e-01,1.329767390238714708e-01,-8.412338040714181231e-01,-1.008067836231187897e-01,3.118859117666539227e-01,1.664499566586983073e-02,3.185372749392228510e-03,3.090169943810310016e-02,-1.100000000000000006e-01,-6.134260438594776321e-01,-3.090169943810310016e-02,1.100000000000000006e-01,-7.465739561405224656e-01,8.457629772402222579e-02,-9.627040049795757004e-02,-3.291370886402900653e-01,1.542370227597830018e-02,1.237295995020424311e-01,-4.108629113597102034e-01
+-7.673188383462864817e-03,6.991592328526003985e-01,1.515302578476923970e-02,1.516888329904590160e-01,-2.725583436216138904e-03,-5.007475828907675952e-01,1.240306783854972783e-01,-8.177541401307576452e-01,-1.190744289973525993e-01,2.714130818264198219e-01,1.474786567651078378e-02,7.917428047890899805e-04,4.539904997452154367e-02,-1.100000000000000006e-01,-6.176295433070164709e-01,-4.539904997452154367e-02,1.100000000000000006e-01,-7.423704566929836268e-01,9.182144733721259167e-02,-9.871445703411622918e-02,-3.341476160851816757e-01,8.178552662787885730e-03,1.212855429658837719e-01,-4.058523839148187040e-01
+2.963590180008246824e-02,7.098632864871377013e-01,1.254818146278482115e-02,1.487310921671541053e-01,-2.728787781567020704e-02,-4.994660274916671305e-01,1.178014005986133123e-01,-7.809684223219595101e-01,-1.370588412572478210e-01,2.278042664156923747e-01,1.252216408631159385e-02,-1.026656369208827930e-03,5.877852522975920979e-02,-1.100000000000000006e-01,-6.233688103940140390e-01,-5.877852522975920979e-02,1.100000000000000006e-01,-7.366311896059860587e-01,9.803681411953509006e-02,-1.014364010926645659e-01,-3.400409482092960900e-01,1.963185880465304067e-03,1.185635989073354352e-01,-3.999590517907043452e-01
+6.161585822318485506e-02,7.103901144864168682e-01,9.217067174940415247e-03,1.416878746222827723e-01,-4.810022722905037129e-02,-4.917885642699208470e-01,1.146525911130632652e-01,-7.340487569077346341e-01,-1.545832616043421592e-01,1.832300851365145922e-01,1.002054977253457463e-02,-2.367965080493918476e-03,7.071067811909971523e-02,-1.100000000000000006e-01,-6.305025253172531485e-01,-7.071067811909971523e-02,1.100000000000000006e-01,-7.294974746827469492e-01,1.030693551131893343e-01,-1.043692093772667501e-01,-3.466719716168897292e-01,-3.069355113189023432e-03,1.156307906227332510e-01,-3.933280283831107615e-01
+8.723604095521510227e-02,7.018536152206322765e-01,5.483080760932158848e-03,1.314589164203218974e-01,-6.436012173431519823e-02,-4.787833981378857851e-01,1.151334353456745785e-01,-6.803817301663384054e-01,-1.715712081085765395e-01,1.398613826563624707e-01,7.290000458960666820e-03,-3.411449538274136193e-03,8.090169943786258699e-02,-1.100000000000000006e-01,-6.388550323398812791e-01,-8.090169943786258699e-02,1.100000000000000006e-01,-7.211449676601188186e-01,1.067951524568656052e-01,-1.074406664145232393e-01,-3.538774085045627293e-01,-6.795152456865384549e-03,1.125593335854767618e-01,-3.861225914954377614e-01
+1.053548694618611226e-01,6.854951399736247675e-01,1.678016517447191488e-03,1.190053900473785065e-01,-7.516005639129229310e-02,-4.615221586749197469e-01,1.200377521516150375e-01,-6.233272708719114208e-01,-1.880758526942775677e-01,9.974724695567817323e-02,4.369022085566135957e-03,-4.366040839633498864e-03,8.910065241912062950e-02,-1.100000000000000006e-01,-6.482206650186217445e-01,-8.910065241912062950e-02,1.100000000000000006e-01,-7.117793349813783532e-01,1.091224646547504507e-01,-1.105751427385958802e-01,-3.614798371026680668e-01,-9.122464654750347957e-03,1.094248572614041209e-01,-3.785201628973324239e-01
+1.146620808152693100e-01,6.625800878592321697e-01,-1.890103041055528083e-03,1.052190971439525280e-01,-7.943570573499332543e-02,-4.410041489830097139e-01,1.304791654645101329e-01,-5.658964679592692892e-01,-2.043186049003604121e-01,6.461523056143665678e-02,1.287435098014001397e-03,-5.419406970931074131e-03,9.510565162970747999e-02,-1.100000000000000006e-01,-6.583688103941676140e-01,-9.510565162970747999e-02,1.100000000000000006e-01,-7.016311896058324837e-01,1.099939855566248181e-01,-1.136954571396544406e-01,-3.692920603881038044e-01,-9.993985556624805644e-03,1.063045428603455606e-01,-3.707079396118967418e-01
+1.136141537206286495e-01,6.342675291541154392e-01,-4.987495030947622712e-03,9.083235138989759205e-02,-7.590858215698519096e-02,-4.180607698331823552e-01,1.479745070389892059e-01,-5.104581687371535503e-01,-2.207334564724171000e-01,3.567820158491574745e-02,-1.929766589232184172e-03,-6.698175941218493558e-03,9.876883405961049689e-02,-1.100000000000000006e-01,-6.690495874476113380e-01,-9.876883405961049689e-02,1.100000000000000006e-01,-6.909504125523887597e-01,1.093882554254730632e-01,-1.167247771214156432e-01,-3.771217154963012463e-01,-9.388255425473140958e-03,1.032752228785843579e-01,-3.628782845036992999e-01
+1.003892154369815104e-01,6.015091030961500218e-01,-7.536003586268297250e-03,7.639017381940686746e-02,-6.304935679284137673e-02,-3.932898026082213838e-01,1.745055716392953371e-01,-4.585879697241103115e-01,-2.380022910163964445e-01,1.353823766649387902e-02,-5.252174634854611668e-03,-8.248665217501177302e-03,1.000000000000000056e-01,-1.100000000000000006e-01,-6.800000000004303713e-01,-1.000000000000000056e-01,1.100000000000000006e-01,-6.799999999995697264e-01,1.073201893474271529e-01,-1.195885107721919721e-01,-3.847760103333611736e-01,-7.320189347427334681e-03,1.004114892278080290e-01,-3.552239896666393171e-01
+7.293045398820949266e-02,5.650199172959762262e-01,-9.739606996902260005e-03,6.227748628565131506e-02,-3.912876259586241939e-02,-3.670525667953575266e-01,2.124776593408700676e-01,-4.111058022718265259e-01,-2.570391413973269756e-01,-1.772078937774807742e-03,-8.624325639827984391e-03,-1.003981562880432513e-02,9.876883405941815075e-02,-1.100000000000000006e-01,-6.909504125532388574e-01,-9.876883405941815075e-02,1.100000000000000006e-01,-6.690495874467612403e-01,1.038407099728463900e-01,-1.222161434653142309e-01,-3.920664707572471541e-01,-3.840709972846675924e-03,9.778385653468577021e-02,-3.479335292427533366e-01
+2.922878092577011616e-02,5.253190287844501372e-01,-1.225311428529984349e-02,4.877165008251500150e-02,-2.497974191656380030e-03,-3.395273341120376709e-01,2.643954788361104202e-01,-3.682489008892615434e-01,-2.788295816944858507e-01,-1.064761765366597709e-02,-1.193481551199930719e-02,-1.198181587152190482e-02,9.510565162932752004e-02,-1.100000000000000006e-01,-7.016311896066510512e-01,-9.510565162932752004e-02,1.100000000000000006e-01,-6.583688103933490465e-01,9.903549363166291863e-02,-1.245429741632648607e-01,-3.988135814366721710e-01,9.645063683367260943e-04,9.545702583673514041e-02,-3.411864185633282087e-01
+-3.191699582726326145e-02,4.828051591267863429e-01,-1.631742097948581105e-02,3.609134981975599399e-02,4.768801171657859050e-02,-3.107876914942658830e-01,3.319682847541167714e-01,-3.298837045285262781e-01,-3.039753575657857532e-01,-1.374068819080336533e-02,-1.498012027524268756e-02,-1.395079121647122347e-02,8.910065241856240936e-02,-1.100000000000000006e-01,-7.117793349821452953e-01,-8.910065241856240936e-02,1.100000000000000006e-01,-6.482206650178548024e-01,9.302286069779530653e-02,-1.265117085719519863e-01,-4.048512061143323959e-01,6.977139302204254934e-03,9.348829142804800096e-02,-3.351487938856679838e-01
+-1.095522403442796971e-01,4.378336598918333156e-01,-2.363195767004729053e-02,2.442778464438240607e-02,1.102372783080880492e-01,-2.808774127895866668e-01,4.144794111130860603e-01,-2.956860640203942125e-01,-3.318676187607054739e-01,-1.181813277391502957e-02,-1.744878856011335480e-02,-1.581207081677232784e-02,8.090169943714153877e-02,-1.100000000000000006e-01,-7.211449676608134851e-01,-8.090169943714153877e-02,1.100000000000000006e-01,-6.388550323391866126e-01,8.595086214885996889e-02,-1.280738699163788685e-01,-4.100306784329363907e-01,1.404913785113950930e-02,9.192613008362113258e-02,-3.299693215670639335e-01
+-1.980260120120157508e-01,3.907770986512769662e-01,-3.546144753831483032e-02,1.395745258999921828e-02,1.798060562194120360e-01,-2.498681818948195466e-01,5.040411986116243304e-01,-2.652653009976261300e-01,-3.478089728117206847e-01,-5.665123502311100907e-03,-1.886183327925208125e-02,-1.743836329123713003e-02,7.071067811823227023e-02,-1.100000000000000006e-01,-7.294974746833541301e-01,-7.071067811823227023e-02,1.100000000000000006e-01,-6.305025253166459676e-01,7.799363405974919783e-02,-1.291909925997294373e-01,-4.142244625943170000e-01,2.200636594025023179e-02,9.080900740027054996e-02,-3.257755374056832132e-01
+-2.895443046039634094e-01,3.420655581748262564e-01,-5.160187264092832432e-02,4.841596824297692697e-03,2.492728734079604491e-01,-2.178979182504336143e-01,5.905773675920145127e-01,-2.382376078095875815e-01,-3.489874358007325483e-01,3.968751818226971817e-03,-1.860051970965531654e-02,-1.872202140062542708e-02,5.877852522876445690e-02,-1.100000000000000006e-01,-7.366311896064919873e-01,-5.877852522876445690e-02,1.100000000000000006e-01,-6.233688103935081104e-01,6.934710979454114521e-02,-1.298355693540221012e-01,-4.173292937140499759e-01,3.065289020545823931e-02,9.016443064597788604e-02,-3.226707062859501818e-01
+-3.793666227282756487e-01,2.922088815110864823e-01,-7.120691346074675687e-02,-2.782043068378350827e-03,3.145830796571077448e-01,-1.851921758793429462e-01,6.714023036896725749e-01,-2.142641032470927742e-01,-3.490610897375457933e-01,1.639386155568499370e-02,-1.703940665422631201e-02,-1.958198324590743056e-02,4.539904997342597559e-02,-1.100000000000000006e-01,-7.423704566933744253e-01,-4.539904997342597559e-02,1.100000000000000006e-01,-6.176295433066256724e-01,6.022419547681708701e-02,-1.299917285603383321e-01,-4.192687205456226973e-01,3.977580452318228016e-02,9.000827143966165511e-02,-3.207312794543774048e-01
+-4.622966703121175192e-01,2.418044428678886304e-01,-9.227356492705227065e-02,-8.810760645686430484e-03,3.717175438115288277e-01,-1.520718893925017690e-01,7.407176961243823188e-01,-1.930679167293977705e-01,-3.490656931085965864e-01,3.098756273313546528e-02,-1.457753668237577599e-02,-1.996643096951212018e-02,3.090169943693370225e-02,-1.100000000000000006e-01,-7.465739561407883640e-01,-3.090169943693370225e-02,1.100000000000000006e-01,-6.134260438592117337e-01,5.084952753429452382e-02,-1.296556250607560912e-01,-4.199949879638538164e-01,4.915047246570483641e-02,9.034437493924389606e-02,-3.200050120361461747e-01
+-5.348385334558520832e-01,1.915338529923051591e-01,-1.124415214083394343e-01,-1.318858593765200905e-02,4.184620240926810730e-01,-1.189504629191358992e-01,7.942577162641449862e-01,-1.744406738129228585e-01,-3.490659808192873026e-01,4.719277263917720511e-02,-1.166413896000924495e-02,-1.985221780111470075e-02,1.564344650344385440e-02,-1.100000000000000006e-01,-7.491381838417239258e-01,-1.564344650344385440e-02,1.100000000000000006e-01,-6.108618161582761719e-01,4.145394140445739228e-02,-1.288355348388986465e-01,-4.194902128545631159e-01,5.854605859554196795e-02,9.116446516110134068e-02,-3.205097871454367642e-01
+-5.953693400300789085e-01,1.421519329423949485e-01,-1.297194457241645227e-01,-1.591602986317542170e-02,4.543397535400395260e-01,-8.632316183466097470e-02,8.301158477204988451e-01,-1.582451059993232323e-01,-3.490659988012054793e-01,6.451373185792955156e-02,-8.703821904259551392e-03,-1.924197278442171810e-02,-5.829882539173617050e-13,-1.100000000000000006e-01,-7.500000000000000000e-01,5.829882539173617050e-13,1.100000000000000006e-01,-6.100000000000000977e-01,3.226878759998480506e-02,-1.275516512377515566e-01,-4.177668244561940081e-01,6.773121240001457599e-02,9.244834876224844455e-02,-3.222331755438058165e-01
+-6.433256773747829671e-01,9.447163462136577705e-02,-1.426945809662209241e-01,-1.705646484155426065e-02,4.797609735124353514e-01,-5.475217720537265548e-02,8.476869101484892921e-01,-1.444180509875212237e-01,-3.459210837698913910e-01,8.251230611459829667e-02,-5.985677071148555808e-03,-1.815963020591230409e-02,-1.564344650459547834e-02,-1.100000000000000006e-01,-7.491381838415962502e-01,1.564344650459547834e-02,1.100000000000000006e-01,-6.108618161584038475e-01,2.352023509132054185e-02,-1.258355877325403882e-01,-4.148672583107123613e-01,7.647976490867888777e-02,9.416441226745961290e-02,-3.251327416892874078e-01
+-6.773332858464311546e-01,4.934908310994183533e-02,-1.498575406398425236e-01,-1.673834903911702171e-02,4.945905135248704343e-01,-2.485129274807498095e-02,8.412338040714802956e-01,-1.329767390239103286e-01,-3.118859117668034697e-01,1.008067836230391590e-01,-3.185372749402818997e-03,-1.664499566587654411e-02,-3.090169943804260688e-02,-1.100000000000000006e-01,-7.465739561405362323e-01,3.090169943804260688e-02,1.100000000000000006e-01,-6.134260438594638654e-01,1.542370227600896315e-02,-1.237295995020516876e-01,-4.108629113597282445e-01,8.457629772399051504e-02,9.627040049794831356e-02,-3.291370886402714135e-01
+-6.991592328525337852e-01,7.673188383621534769e-03,-1.516888329904610422e-01,-1.515302578477786821e-02,5.007475828907574922e-01,2.725583436111248849e-03,8.177541401308788815e-01,-1.240306783855254363e-01,-2.714130818265864109e-01,1.190744289972747866e-01,-7.917428047973367475e-04,-1.474786567651935679e-02,-4.539904997446486679e-02,-1.100000000000000006e-01,-7.423704566930038329e-01,4.539904997446486679e-02,1.100000000000000006e-01,-6.176295433069962648e-01,8.178552662814787821e-03,-1.212855429658942635e-01,-4.058523839148404644e-01,9.182144733718475282e-02,9.871445703410573758e-02,-3.341476160851591382e-01
+-7.098632864871161630e-01,-2.963590179994961618e-02,-1.487310921671736730e-01,-1.254818146279652706e-02,4.994660274916846721e-01,2.728787781558316555e-02,7.809684223221231569e-01,-1.178014005986295354e-01,-2.278042664158645425e-01,1.370588412571778769e-01,1.026656369202793044e-03,-1.252216408632086074e-02,-5.877852522971004773e-02,-1.100000000000000006e-01,-7.366311896060110387e-01,5.877852522971004773e-02,1.100000000000000006e-01,-6.233688103939890590e-01,1.963185880486759127e-03,-1.185635989073464125e-01,-3.999590517907282150e-01,9.803681411951285785e-02,1.014364010926535886e-01,-3.400409482092713320e-01
+-7.103901144864339656e-01,-6.161585822307427684e-02,-1.416878746223172447e-01,-9.217067174954247932e-03,4.917885642699621473e-01,4.810022722897919212e-02,7.340487569079333641e-01,-1.146525911130674563e-01,-1.832300851366891747e-01,1.545832616042769336e-01,2.367965080489126302e-03,-1.002054977254444347e-02,-7.071067811905674960e-02,-1.100000000000000006e-01,-7.294974746827769252e-01,7.071067811905674960e-02,1.100000000000000006e-01,-6.305025253172231725e-01,-3.069355113172314575e-03,-1.156307906227449084e-01,-3.933280283831371293e-01,1.030693551131720287e-01,1.043692093772550927e-01,-3.466719716168623622e-01
+-7.018536152206821255e-01,-8.723604095513075307e-02,-1.314589164203667226e-01,-5.483080760946900528e-03,4.787833981379453485e-01,6.436012173426292060e-02,6.803817301665568973e-01,-1.151334353456639897e-01,-1.398613826565295037e-01,1.715712081085129515e-01,3.411449538270163243e-03,-7.290000458971444657e-03,-8.090169943782687945e-02,-1.100000000000000006e-01,-7.211449676601531245e-01,8.090169943782687945e-02,1.100000000000000006e-01,-6.388550323398469732e-01,-6.795152456853838230e-03,-1.125593335854888216e-01,-3.861225914954660166e-01,1.067951524568536426e-01,1.074406664145111795e-01,-3.538774085045334750e-01
+-6.854951399737057027e-01,-1.053548694618053616e-01,-1.190053900474320886e-01,-1.678016517462276643e-03,4.615221586749965743e-01,7.516005639126149829e-02,6.233272708721456778e-01,-1.200377521515839513e-01,-9.974724695583318812e-02,1.880758526942112041e-01,4.366040839629803903e-03,-4.369022085578313716e-03,-8.910065241909174982e-02,-1.100000000000000006e-01,-7.117793349814180992e-01,8.910065241909174982e-02,1.100000000000000006e-01,-6.482206650185819985e-01,-9.122464654743950296e-03,-1.094248572614168330e-01,-3.785201628973632326e-01,1.091224646547438448e-01,1.105751427385831681e-01,-3.614798371026362034e-01
+-6.625800878593374188e-01,-1.146620808152518933e-01,-1.052190971440102180e-01,1.890103041041877327e-03,4.410041489830985872e-01,7.943570573499118825e-02,5.658964679595001046e-01,-1.304791654644540944e-01,-6.461523056156738554e-02,2.043186049002943261e-01,5.419406970926399052e-03,-1.287435098026834014e-03,-9.510565162968782904e-02,-1.100000000000000006e-01,-7.016311896058747832e-01,9.510565162968782904e-02,1.100000000000000006e-01,-6.583688103941253145e-01,-9.993985556624278288e-03,-1.063045428603580644e-01,-3.707079396119279946e-01,1.099939855566242630e-01,1.136954571396419367e-01,-3.692920603880714414e-01
+-6.342675291542408944e-01,-1.136141537206559055e-01,-9.083235138995657265e-02,4.987495030936162262e-03,4.180607698332799438e-01,7.590858215701704048e-02,5.104581687373732635e-01,-1.479745070389020811e-01,-3.567820158502005290e-02,2.207334564723497095e-01,6.698175941212810604e-03,1.929766589218859111e-03,-9.876883405960054652e-02,-1.100000000000000006e-01,-6.909504125524327245e-01,9.876883405960054652e-02,1.100000000000000006e-01,-6.690495874475673732e-01,-9.388255425478483907e-03,-1.032752228785963344e-01,-3.628782845037302196e-01,1.093882554254785866e-01,1.167247771214036667e-01,-3.771217154962692164e-01
+-6.015091030962922414e-01,-1.003892154370614465e-01,-7.639017381946544560e-02,7.536003586258916732e-03,3.932898026083256893e-01,6.304935679291390205e-02,4.585879697243140929e-01,-1.745055716391676059e-01,-1.353823766657051043e-02,2.380022910163240857e-01,8.248665217494300858e-03,5.252174634841026181e-03,-1.000000000000000056e-01,-1.100000000000000006e-01,-6.799999999996142463e-01,1.000000000000000056e-01,1.100000000000000006e-01,-6.800000000003858514e-01,-7.320189347438423033e-03,-1.004114892278192006e-01,-3.552239896666691821e-01,1.073201893474386159e-01,1.195885107721808005e-01,-3.847760103333303094e-01
+-5.650199172961328786e-01,-7.293045398834858972e-02,-6.227748628570803358e-02,9.739606996893340057e-03,3.670525667954680493e-01,3.912876259598101203e-02,4.111058022720126548e-01,-2.124776593406948189e-01,1.772078937724863752e-03,2.570391413972472616e-01,1.003981562879667500e-02,8.624325639814699879e-03,-9.876883405942810112e-02,-1.100000000000000006e-01,-6.690495874468052051e-01,9.876883405942810112e-02,1.100000000000000006e-01,-6.909504125531948926e-01,-3.840709972863225186e-03,-9.778385653469584549e-02,-3.479335292427813697e-01,1.038407099728635152e-01,1.222161434653041556e-01,-3.920664707572181218e-01
+-5.253190287846197792e-01,-2.922878092597726296e-02,-4.877165008256904855e-02,1.225311428528769175e-02,3.395273341121535782e-01,2.497974191827874793e-03,3.682489008894298532e-01,-2.643954788358754970e-01,1.064761765364080973e-02,2.788295816943928140e-01,1.198181587151361978e-02,1.193481551198660728e-02,-9.510565162934718486e-02,-1.100000000000000006e-01,-6.583688103933913460e-01,9.510565162934718486e-02,1.100000000000000006e-01,-7.016311896066087517e-01,9.645063683151114398e-04,-9.545702583674386954e-02,-3.411864185633537994e-01,9.903549363168526187e-02,1.245429741632561316e-01,-3.988135814366457477e-01
+-4.828051591269582055e-01,3.191699582699424054e-02,-3.609134981980374052e-02,1.631742097946493539e-02,3.107876914943806801e-01,-4.768801171635956432e-02,3.298837045286693304e-01,-3.319682847538257819e-01,1.374068819080048569e-02,3.039753575656826690e-01,1.395079121646363753e-02,1.498012027523180217e-02,-8.910065241858998453e-02,-1.100000000000000006e-01,-6.482206650178926610e-01,8.910065241858998453e-02,1.100000000000000006e-01,-7.117793349821074367e-01,6.977139302179288793e-03,-9.348829142805485659e-02,-3.351487938856893556e-01,9.302286069782116085e-02,1.265117085719451306e-01,-4.048512061143102470e-01
+-4.378336598920128386e-01,1.095522403439502523e-01,-2.442778464442548966e-02,2.363195767001018827e-02,2.808774127897052941e-01,-1.102372783078249263e-01,2.956860640205205004e-01,-4.144794111127395042e-01,1.181813277392943298e-02,3.318676187605959504e-01,1.581207081676575324e-02,1.744878856010527099e-02,-8.090169943717724632e-02,-1.100000000000000006e-01,-6.388550323392210295e-01,8.090169943717724632e-02,1.100000000000000006e-01,-7.211449676607790682e-01,1.404913785111083779e-02,-9.192613008362633675e-02,-3.299693215670818081e-01,8.595086214888968124e-02,1.280738699163736505e-01,-4.100306784329178500e-01
+-3.907770986514639278e-01,1.980260120116635048e-01,-1.395745259003738220e-02,3.546144753826004775e-02,2.498681818949418654e-01,-1.798060562191391154e-01,2.652653009977387066e-01,-5.040411986112809384e-01,5.665123502339633639e-03,3.478089728117068069e-01,1.743836329123151646e-02,1.886183327924986081e-02,-7.071067811827524974e-02,-1.100000000000000006e-01,-6.305025253166760546e-01,7.071067811827524974e-02,1.100000000000000006e-01,-7.294974746833240431e-01,2.200636594021855574e-02,-9.080900740027396389e-02,-3.257755374056971465e-01,7.799363405978201880e-02,1.291909925997260233e-01,-4.142244625943025671e-01
+-3.420655581750288166e-01,2.895443046035982015e-01,-4.841596824332061039e-03,5.160187264085616676e-02,2.178979182505664802e-01,-2.492728734076886665e-01,2.382376078096938576e-01,-5.905773675916788923e-01,-3.968751818184020931e-03,3.489874358007316602e-01,1.872202140062110762e-02,1.860051970965915721e-02,-5.877852522881591574e-02,-1.100000000000000006e-01,-6.233688103935343117e-01,5.877852522881591574e-02,1.100000000000000006e-01,-7.366311896064657860e-01,3.065289020542272952e-02,-9.016443064597950974e-02,-3.226707062859602848e-01,6.934710979457789359e-02,1.298355693540204914e-01,-4.173292937140395953e-01
+-2.922088815112922067e-01,3.793666227279293146e-01,2.782043068350384049e-03,7.120691346066448935e-02,1.851921758794780604e-01,-3.145830796568622745e-01,2.142641032471866713e-01,-6.714023036893733698e-01,-1.639386155563094319e-02,3.490610897375456823e-01,1.958198324590495684e-02,1.703940665423461440e-02,-4.539904997348265248e-02,-1.100000000000000006e-01,-6.176295433066458784e-01,4.539904997348265248e-02,1.100000000000000006e-01,-7.423704566933542193e-01,3.977580452314530973e-02,-9.000827143966129429e-02,-3.207312794543827339e-01,6.022419547685532726e-02,1.299917285603386929e-01,-4.192687205456171462e-01
+-2.418044428680952707e-01,4.622966703118067677e-01,8.810760645665188795e-03,9.227356492696890677e-02,1.520718893926371051e-01,-3.717175438113214936e-01,1.930679167294808429e-01,-7.407176961241389579e-01,-3.098756273307293890e-02,3.490656931085965864e-01,1.996643096951137772e-02,1.457753668238690598e-02,-3.090169943699419206e-02,-1.100000000000000006e-01,-6.134260438592253895e-01,3.090169943699419206e-02,1.100000000000000006e-01,-7.465739561407747082e-01,4.915047246566732475e-02,-9.034437493924155071e-02,-3.200050120361466188e-01,5.084952753433333306e-02,1.296556250607584504e-01,-4.199949879638533168e-01
+-1.915338529925114108e-01,5.348385334555875170e-01,1.318858593763726043e-02,1.124415214082644943e-01,1.189504629192720264e-01,-4.184620240925175927e-01,1.744406738129974932e-01,-7.942577162639713473e-01,-4.719277263910596348e-02,3.490659808192873026e-01,1.985221780111592893e-02,1.166413896002085719e-02,-1.564344650350667915e-02,-1.100000000000000006e-01,-6.108618161582831663e-01,1.564344650350667915e-02,1.100000000000000006e-01,-7.491381838417169314e-01,5.854605859550483793e-02,-9.116446516109706633e-02,-3.205097871454323233e-01,4.145394140449580600e-02,1.288355348389029209e-01,-4.194902128545677789e-01
+-1.421519329425959821e-01,5.953693400298625260e-01,1.591602986316737259e-02,1.297194457241039323e-01,8.632316183479388227e-02,-4.543397535399179565e-01,1.582451059993878473e-01,-8.301158477203954833e-01,-6.451373185785493070e-02,3.490659988012054238e-01,1.924197278442522918e-02,8.703821904270747298e-03,5.193824325988412219e-13,-1.100000000000000006e-01,-6.100000000000000977e-01,-5.193824325988412219e-13,1.100000000000000006e-01,-7.500000000000000000e-01,6.773121239997874354e-02,-9.244834876224235221e-02,-3.222331755437966017e-01,3.226878760002188651e-02,1.275516512377576350e-01,-4.177668244562035560e-01
+-9.447163462154851976e-02,6.433256773746270918e-01,1.705646484155272369e-02,1.426945809661825104e-01,5.475217720549330203e-02,-4.797609735123595787e-01,1.444180509875728213e-01,-8.476869101484711955e-01,-8.251230611452721464e-02,3.459210837699964181e-01,1.815963020591687335e-02,5.985677071158100257e-03,1.564344650453546037e-02,-1.100000000000000006e-01,-6.108618161583971862e-01,-1.564344650453546037e-02,1.100000000000000006e-01,-7.491381838416029115e-01,7.647976490864674681e-02,-9.416441226745218829e-02,-3.251327416892742517e-01,2.352023509135383814e-02,1.258355877325477989e-01,-4.148672583107260170e-01
+-4.934908311011198395e-02,6.773332858463252393e-01,1.673834903912079300e-02,1.498575406398258425e-01,2.485129274818707185e-02,-4.945905135248314655e-01,1.329767390239521840e-01,-8.412338040715433563e-01,-1.008067836229713243e-01,3.118859117669561254e-01,1.664499566588182808e-02,3.185372749413468464e-03,3.090169943798481977e-02,-1.100000000000000006e-01,-6.134260438594507647e-01,-3.090169943798481977e-02,1.100000000000000006e-01,-7.465739561405493330e-01,8.457629772396124679e-02,-9.627040049793948728e-02,-3.291370886402542606e-01,1.542370227603928612e-02,1.237295995020605138e-01,-4.108629113597460636e-01
+-7.673188383776764765e-03,6.991592328524728339e-01,1.515302578478618795e-02,1.516888329904643173e-01,-2.725583436008819499e-03,-5.007475828907497206e-01,1.240306783855576744e-01,-8.177541401310004510e-01,-1.190744289972088393e-01,2.714130818267557199e-01,1.474786567652717172e-02,7.917428048058018728e-04,4.539904997441072260e-02,-1.100000000000000006e-01,-6.176295433069769469e-01,-4.539904997441072260e-02,1.100000000000000006e-01,-7.423704566930231508e-01,9.182144733715907892e-02,-9.871445703409569006e-02,-3.341476160851383215e-01,8.178552662841398480e-03,1.212855429659043111e-01,-4.058523839148620582e-01
+2.963590179980688660e-02,7.098632864870944026e-01,1.254818146280881758e-02,1.487310921671946284e-01,-2.728787781548959457e-02,-4.994660274917038234e-01,1.178014005986508100e-01,-7.809684223222953525e-01,-1.370588412571066561e-01,2.278042664160445374e-01,1.252216408633051448e-02,-1.026656369196474530e-03,5.877852522965858889e-02,-1.100000000000000006e-01,-6.233688103939628578e-01,-5.877852522965858889e-02,1.100000000000000006e-01,-7.366311896060372399e-01,9.803681411949037583e-02,-1.014364010926420978e-01,-3.400409482092462965e-01,1.963185880510018300e-03,1.185635989073579033e-01,-3.999590517907541387e-01
+6.161585822295531645e-02,7.103901144864510631e-01,9.217067174968800528e-03,1.416878746223528551e-01,-4.810022722890178876e-02,-4.917885642700047799e-01,1.146525911130751724e-01,-7.340487569081394215e-01,-1.545832616042071561e-01,1.832300851368685313e-01,1.002054977255652235e-02,-2.367965080484437344e-03,7.071067811901177169e-02,-1.100000000000000006e-01,-6.305025253171916422e-01,-7.071067811901177169e-02,1.100000000000000006e-01,-7.294974746828084555e-01,1.030693551131545149e-01,-1.043692093772428803e-01,-3.466719716168347176e-01,-3.069355113154211001e-03,1.156307906227571208e-01,-3.933280283831657176e-01
+8.723604095504011724e-02,7.018536152207331957e-01,5.483080760962430640e-03,1.314589164204131577e-01,-6.436012173420663229e-02,-4.787833981380072434e-01,1.151334353456551218e-01,-6.803817301667823836e-01,-1.715712081084457830e-01,1.398613826566992846e-01,7.290000458982878219e-03,-3.411449538266263150e-03,8.090169943778947881e-02,-1.100000000000000006e-01,-6.388550323398108910e-01,-8.090169943778947881e-02,1.100000000000000006e-01,-7.211449676601892067e-01,1.067951524568415411e-01,-1.074406664144985646e-01,-3.538774085045038875e-01,-6.795152456841320465e-03,1.125593335855014365e-01,-3.861225914954966032e-01
+1.053548694617481990e-01,6.854951399737848616e-01,1.678016517477464147e-03,1.190053900474853238e-01,-7.516005639122970428e-02,-4.615221586750728466e-01,1.200377521515543083e-01,-6.233272708723771593e-01,-1.880758526941444519e-01,9.974724695598465030e-02,4.369022085590610303e-03,-4.366040839626022206e-03,8.910065241906287015e-02,-1.100000000000000006e-01,-6.482206650185423635e-01,-8.910065241906287015e-02,1.100000000000000006e-01,-7.117793349814577342e-01,1.091224646547374610e-01,-1.105751427385704561e-01,-3.614798371026053947e-01,-9.122464654737337530e-03,1.094248572614295451e-01,-3.785201628973950960e-01
+1.146620808152336163e-01,6.625800878594402255e-01,-1.890103041028301815e-03,1.052190971440672140e-01,-7.943570573498839882e-02,-4.410041489831862394e-01,1.304791654643991106e-01,-5.658964679597275893e-01,-2.043186049002282123e-01,6.461523056169589385e-02,1.287435098039528504e-03,-5.419406970921865352e-03,9.510565162966816422e-02,-1.100000000000000006e-01,-6.583688103940829039e-01,-9.510565162966816422e-02,1.100000000000000006e-01,-7.016311896059171938e-01,1.099939855566237495e-01,-1.136954571396294328e-01,-3.692920603880401886e-01,-9.993985556623730115e-03,1.063045428603705683e-01,-3.707079396119603576e-01
+1.136141537206826341e-01,6.342675291543584670e-01,-4.987495030925336720e-03,9.083235139001238911e-02,-7.590858215704793244e-02,-4.180607698333719258e-01,1.479745070388177042e-01,-5.104581687375804311e-01,-2.207334564722847892e-01,3.567820158511843948e-02,-1.929766589206262199e-03,-6.698175941207234335e-03,9.876883405959104023e-02,-1.100000000000000006e-01,-6.690495874475252958e-01,-9.876883405959104023e-02,1.100000000000000006e-01,-6.909504125524748019e-01,1.093882554254836936e-01,-1.167247771213922175e-01,-3.771217154962396845e-01,-9.388255425483764405e-03,1.032752228786077836e-01,-3.628782845037608062e-01
+1.003892154371399531e-01,6.015091030964245800e-01,-7.536003586250012397e-03,7.639017381952027674e-02,-6.304935679298503959e-02,-3.932898026084234999e-01,1.745055716390431499e-01,-4.585879697245040520e-01,-2.380022910162546967e-01,1.353823766664177287e-02,-5.252174634828027031e-03,-8.248665217487892790e-03,1.000000000000000056e-01,-1.100000000000000006e-01,-6.800000000003433298e-01,-1.000000000000000056e-01,1.100000000000000006e-01,-6.799999999996567679e-01,1.073201893474492047e-01,-1.195885107721701424e-01,-3.847760103333017767e-01,-7.320189347449393424e-03,1.004114892278298588e-01,-3.552239896666987140e-01
+7.293045398848903293e-02,5.650199172962783178e-01,-9.739606996884773993e-03,6.227748628576082468e-02,-3.912876259610026386e-02,-3.670525667955703564e-01,2.124776593405170444e-01,-4.111058022721840177e-01,-2.570391413971669925e-01,-1.772078937679803443e-03,-8.624325639801566287e-03,-1.003981562878949324e-02,9.876883405943759353e-02,-1.100000000000000006e-01,-6.909504125531529262e-01,-9.876883405943759353e-02,1.100000000000000006e-01,-6.690495874468471715e-01,1.038407099728793359e-01,-1.222161434652945383e-01,-3.920664707571913654e-01,-3.840709972879607914e-03,9.778385653470546279e-02,-3.479335292428091253e-01
+2.922878092618543672e-02,5.253190287847764317e-01,-1.225311428527585920e-02,4.877165008261908491e-02,-2.497974192000288959e-03,-3.395273341122607702e-01,2.643954788356372987e-01,-3.682489008895832305e-01,-2.788295816942992777e-01,-1.064761765361940497e-02,-1.193481551197380676e-02,-1.198181587150618302e-02,9.510565162936596151e-02,-1.100000000000000006e-01,-7.016311896065682285e-01,-9.510565162936596151e-02,1.100000000000000006e-01,-6.583688103934318692e-01,9.903549363170591202e-02,-1.245429741632477910e-01,-3.988135814366213783e-01,9.645063682937257687e-04,9.545702583675221009e-02,-3.411864185633790569e-01
+-3.191699582670913526e-02,4.828051591271332876e-01,-1.631742097944305359e-02,3.609134981985265972e-02,4.768801171612795792e-02,-3.107876914944982527e-01,3.319682847535173620e-01,-3.298837045288132153e-01,-3.039753575655736451e-01,-1.374068819079958710e-02,-1.498012027522051259e-02,-1.395079121645587811e-02,8.910065241861886420e-02,-1.100000000000000006e-01,-7.117793349820676907e-01,-8.910065241861886420e-02,1.100000000000000006e-01,-6.482206650179324070e-01,9.302286069784732048e-02,-1.265117085719379419e-01,-4.048512061142878204e-01,6.977139302152240985e-03,9.348829142806204529e-02,-3.351487938857125592e-01
+-1.095522403436056530e-01,4.378336598921966361e-01,-2.363195766997166353e-02,2.442778464446982226e-02,1.102372783075504098e-01,-2.808774127898268080e-01,4.144794111123786817e-01,-2.956860640206474544e-01,-3.318676187604807093e-01,-1.181813277394779330e-02,-1.744878856009713861e-02,-1.581207081675865822e-02,8.090169943721463308e-02,-1.100000000000000006e-01,-7.211449676607430970e-01,-8.090169943721463308e-02,1.100000000000000006e-01,-6.388550323392570007e-01,8.595086214891971277e-02,-1.280738699163682104e-01,-4.100306784328990872e-01,1.404913785107977237e-02,9.192613008363177685e-02,-3.299693215671011814e-01
+-1.980260120112937172e-01,3.907770986516549416e-01,-3.546144753820294065e-02,1.395745259007646032e-02,1.798060562188535105e-01,-2.498681818950675426e-01,5.040411986109216702e-01,-2.652653009978507836e-01,-3.478089728116923185e-01,-5.665123502373731364e-03,-1.886183327924785894e-02,-1.743836329122579881e-02,7.071067811832022765e-02,-1.100000000000000006e-01,-7.294974746832925128e-01,-7.071067811832022765e-02,1.100000000000000006e-01,-6.305025253167075849e-01,7.799363405981520059e-02,-1.291909925997224429e-01,-4.142244625942880232e-01,2.200636594018422904e-02,9.080900740027754436e-02,-3.257755374057122455e-01
+-2.895443046032281087e-01,3.420655581752276575e-01,-5.160187264078299613e-02,4.841596824365987026e-03,2.492728734074135255e-01,-2.178979182506973478e-01,5.905773675913384979e-01,-2.382376078097956373e-01,-3.489874358007307720e-01,3.968751818136080980e-03,-1.860051970966300830e-02,-1.872202140061657652e-02,5.877852522886737457e-02,-1.100000000000000006e-01,-7.366311896064395848e-01,-5.877852522886737457e-02,1.100000000000000006e-01,-6.233688103935605129e-01,6.934710979461339297e-02,-1.298355693540188538e-01,-4.173292937140294923e-01,3.065289020538599155e-02,9.016443064598113344e-02,-3.226707062859706654e-01
+-3.793666227275751535e-01,2.922088815114949334e-01,-7.120691346058034832e-02,-2.782043068322550411e-03,3.145830796566113641e-01,-1.851921758796115647e-01,6.714023036890650609e-01,-2.142641032472771545e-01,-3.490610897375456267e-01,1.639386155557270158e-02,-1.703940665424293413e-02,-1.958198324590208414e-02,4.539904997353932242e-02,-1.100000000000000006e-01,-7.423704566933339022e-01,-4.539904997353932242e-02,1.100000000000000006e-01,-6.176295433066661955e-01,6.022419547689229768e-02,-1.299917285603390538e-01,-4.192687205456118171e-01,3.977580452310706949e-02,9.000827143966093347e-02,-3.207312794543882295e-01
+-4.622966703114987363e-01,2.418044428682880886e-01,-9.227356492688580658e-02,-8.810760645645201311e-03,3.717175438111154917e-01,-1.520718893927644755e-01,7.407176961238917112e-01,-1.930679167295550058e-01,-3.490656931085965864e-01,3.098756273301174133e-02,-1.457753668239769422e-02,-1.996643096951080526e-02,3.090169943705198263e-02,-1.100000000000000006e-01,-7.465739561407614966e-01,-3.090169943705198263e-02,1.100000000000000006e-01,-6.134260438592386011e-01,5.084952753436913775e-02,-1.296556250607606986e-01,-4.199949879638529282e-01,4.915047246563022249e-02,9.034437493923930251e-02,-3.200050120361470629e-01
+-5.348385334553236170e-01,1.915338529927006761e-01,-1.124415214081887632e-01,-1.318858593762393255e-02,4.184620240923538903e-01,-1.189504629193969959e-01,7.942577162637889376e-01,-1.744406738130604706e-01,-3.490659808192873026e-01,4.719277263904360364e-02,-1.166413896003294301e-02,-1.985221780111769488e-02,1.564344650356669364e-02,-1.100000000000000006e-01,-7.491381838417102701e-01,-1.564344650356669364e-02,1.100000000000000006e-01,-6.108618161582898276e-01,4.145394140453125681e-02,-1.288355348389070287e-01,-4.194902128545719977e-01,5.854605859546811036e-02,9.116446516109297238e-02,-3.205097871454279379e-01
+-5.953693400296476979e-01,1.421519329427805012e-01,-1.297194457240427035e-01,-1.591602986316018389e-02,4.543397535397966647e-01,-8.632316183491646477e-02,8.301158477202841279e-01,-1.582451059994422760e-01,-3.490659988012054238e-01,6.451373185778890018e-02,-8.703821904282340455e-03,-1.924197278442849740e-02,-4.586187822233612810e-13,-1.100000000000000006e-01,-7.500000000000000000e-01,4.586187822233612810e-13,1.100000000000000006e-01,-6.100000000000000977e-01,3.226878760005609525e-02,-1.275516512377634637e-01,-4.177668244562123823e-01,6.773121239994328580e-02,9.244834876223652353e-02,-3.222331755437874978e-01
+-6.433256773744611134e-01,9.447163462173462090e-02,-1.426945809661414044e-01,-1.705646484155124917e-02,4.797609735122790875e-01,-5.475217720561666862e-02,8.476869101484489910e-01,-1.444180509876213658e-01,-3.459210837701059416e-01,8.251230611445239949e-02,-5.985677071168198950e-03,-1.815963020592212609e-02,-1.564344650447263910e-02,-1.100000000000000006e-01,-7.491381838416097949e-01,1.564344650447263910e-02,1.100000000000000006e-01,-6.108618161583903028e-01,2.352023509138750218e-02,-1.258355877325555705e-01,-4.148672583107397838e-01,7.647976490861192744e-02,9.416441226744441673e-02,-3.251327416892599853e-01
+-6.773332858462121076e-01,4.934908311028606692e-02,-1.498575406398077459e-01,-1.673834903912491470e-02,4.945905135247894990e-01,-2.485129274830290974e-02,8.412338040716058618e-01,-1.329767390239914582e-01,-3.118859117671097247e-01,1.008067836228982300e-01,-3.185372749424259745e-03,-1.664499566588997781e-02,-3.090169943792432650e-02,-1.100000000000000006e-01,-7.465739561405630997e-01,3.090169943792432650e-02,1.100000000000000006e-01,-6.134260438594369980e-01,1.542370227606994909e-02,-1.237295995020697703e-01,-4.108629113597641047e-01,8.457629772392953604e-02,9.627040049793023080e-02,-3.291370886402356088e-01
+-6.991592328524065536e-01,7.673188383935203999e-03,-1.516888329904665378e-01,-1.515302578479477656e-02,5.007475828907398396e-01,2.725583435903678776e-03,8.177541401311226865e-01,-1.240306783855864153e-01,-2.714130818269261947e-01,1.190744289971339548e-01,-7.917428048142238469e-04,-1.474786567653478195e-02,-4.539904997435405265e-02,-1.100000000000000006e-01,-7.423704566930433568e-01,4.539904997435405265e-02,1.100000000000000006e-01,-6.176295433069567409e-01,8.178552662868293632e-03,-1.212855429659148027e-01,-4.058523839148838186e-01,9.182144733713124007e-02,9.871445703408519845e-02,-3.341476160851157839e-01
+-7.098632864870715320e-01,-2.963590179966771321e-02,-1.487310921672151121e-01,-1.254818146282095717e-02,4.994660274917220866e-01,2.728787781539833424e-02,7.809684223224651056e-01,-1.178014005986675744e-01,-2.278042664162204523e-01,1.370588412570311332e-01,1.026656369190571917e-03,-1.252216408634030526e-02,-5.877852522960713699e-02,-1.100000000000000006e-01,-7.366311896060633302e-01,5.877852522960713699e-02,1.100000000000000006e-01,-6.233688103939367675e-01,1.963185880532493377e-03,-1.185635989073694080e-01,-3.999590517907791742e-01,9.803681411946713053e-02,1.014364010926305931e-01,-3.400409482092203728e-01
+-7.103901144864673833e-01,-6.161585822283967284e-02,-1.416878746223880492e-01,-9.217067174983285469e-03,4.917885642700468019e-01,4.810022722882728585e-02,7.340487569083432584e-01,-1.146525911130785169e-01,-1.832300851370447514e-01,1.545832616041342977e-01,2.367965080479989513e-03,-1.002054977256738519e-02,-7.071067811896679378e-02,-1.100000000000000006e-01,-7.294974746828399859e-01,7.071067811896679378e-02,1.100000000000000006e-01,-6.305025253171601118e-01,-3.069355113136704172e-03,-1.156307906227693194e-01,-3.933280283831934176e-01,1.030693551131364183e-01,1.043692093772306817e-01,-3.466719716168061294e-01
+-7.018536152207824896e-01,-8.723604095495601785e-02,-1.314589164204580107e-01,-5.483080760977213954e-03,4.787833981380669179e-01,6.436012173415454896e-02,6.803817301669998763e-01,-1.151334353456438253e-01,-1.398613826568625707e-01,1.715712081083803908e-01,3.411449538262556046e-03,-7.290000458993906723e-03,-8.090169943775377126e-02,-1.100000000000000006e-01,-7.211449676602236236e-01,8.090169943775377126e-02,1.100000000000000006e-01,-6.388550323397764741e-01,-6.795152456829774146e-03,-1.125593335855134963e-01,-3.861225914955248584e-01,1.067951524568295785e-01,1.074406664144865048e-01,-3.538774085044746331e-01
+-6.854951399738630213e-01,-1.053548694616949361e-01,-1.190053900475371157e-01,-1.678016517491820068e-03,4.615221586751473426e-01,7.516005639120029724e-02,6.233272708726026456e-01,-1.200377521515249152e-01,-9.974724695613357284e-02,1.880758526940820297e-01,4.366040839622075710e-03,-4.369022085602093305e-03,-8.910065241903528110e-02,-1.100000000000000006e-01,-7.117793349814955928e-01,8.910065241903528110e-02,1.100000000000000006e-01,-6.482206650185045049e-01,-9.122464654731238243e-03,-1.094248572614416881e-01,-3.785201628974245169e-01,1.091224646547311328e-01,1.105751427385583130e-01,-3.614798371025749746e-01
+-6.625800878595416998e-01,-1.146620808152170046e-01,-1.052190971441225864e-01,1.890103041015299846e-03,4.410041489832716710e-01,7.943570573498641429e-02,5.658964679599494119e-01,-1.304791654643458199e-01,-6.461523056182248703e-02,2.043186049001659843e-01,5.419406970917408847e-03,-1.287435098051897516e-03,-9.510565162964940145e-02,-1.100000000000000006e-01,-7.016311896059576059e-01,9.510565162964940145e-02,1.100000000000000006e-01,-6.583688103940424918e-01,-9.993985556623223576e-03,-1.063045428603825171e-01,-3.707079396119901671e-01,1.099939855566232222e-01,1.136954571396174840e-01,-3.692920603880092689e-01
+-6.342675291544840332e-01,-1.136141537207099594e-01,-9.083235139007142522e-02,4.987495030913922239e-03,4.180607698334695699e-01,7.590858215707982359e-02,5.104581687377998112e-01,-1.479745070387303019e-01,-3.567820158522271023e-02,2.207334564722172598e-01,6.698175941201549646e-03,1.929766589192971182e-03,-9.876883405958108986e-02,-1.100000000000000006e-01,-6.909504125525187668e-01,9.876883405958108986e-02,1.100000000000000006e-01,-6.690495874474813309e-01,-9.388255425489114292e-03,-1.032752228786197601e-01,-3.628782845037917815e-01,1.093882554254892170e-01,1.167247771213802410e-01,-3.771217154962076545e-01
+-6.015091030965670216e-01,-1.003892154372199030e-01,-7.639017381957881325e-02,7.536003586240631880e-03,3.932898026085279719e-01,6.304935679305741225e-02,4.585879697247078890e-01,-1.745055716389154188e-01,-1.353823766671841469e-02,2.380022910161813388e-01,8.248665217481026754e-03,5.252174634814198682e-03,-1.000000000000000056e-01,-1.100000000000000006e-01,-6.799999999997012878e-01,1.000000000000000056e-01,1.100000000000000006e-01,-6.800000000002988099e-01,-7.320189347460474838e-03,-1.004114892278410304e-01,-3.552239896667285790e-01,1.073201893474606816e-01,1.195885107721589707e-01,-3.847760103332708570e-01
+-5.650199172964349703e-01,-7.293045398862942064e-02,-6.227748628581749463e-02,9.739606996875831493e-03,3.670525667956805460e-01,3.912876259621993202e-02,4.111058022723696470e-01,-2.124776593403397973e-01,1.772078937630193387e-03,2.570391413970863903e-01,1.003981562878180495e-02,8.624325639788012893e-03,-9.876883405944754390e-02,-1.100000000000000006e-01,-6.690495874468911364e-01,9.876883405944754390e-02,1.100000000000000006e-01,-6.909504125531089613e-01,-3.840709972896164115e-03,-9.778385653471553807e-02,-3.479335292428371584e-01,1.038407099728964611e-01,1.222161434652844630e-01,-3.920664707571623331e-01
+-5.253190287849448525e-01,-2.922878092639389497e-02,-4.877165008267265317e-02,1.225311428526359124e-02,3.395273341123755673e-01,2.497974192173506303e-03,3.682489008897496530e-01,-2.643954788354004326e-01,1.064761765359479445e-02,2.788295816942066851e-01,1.198181587149812349e-02,1.193481551196080327e-02,-9.510565162938561246e-02,-1.100000000000000006e-01,-6.583688103934741687e-01,9.510565162938561246e-02,1.100000000000000006e-01,-7.016311896065259290e-01,9.645063682721041753e-04,-9.545702583676095310e-02,-3.411864185634045921e-01,9.903549363172828301e-02,1.245429741632390480e-01,-3.988135814365949550e-01
+-4.828051591273137544e-01,3.191699582643395955e-02,-3.609134981990288343e-02,1.631742097942165057e-02,3.107876914946190450e-01,-4.768801171590379695e-02,3.298837045289642056e-01,-3.319682847532218206e-01,1.374068819079663287e-02,3.039753575654686735e-01,1.395079121644774225e-02,1.498012027520944506e-02,-8.910065241864773000e-02,-1.100000000000000006e-01,-6.482206650179720420e-01,8.910065241864773000e-02,1.100000000000000006e-01,-7.117793349820280557e-01,6.977139302126095233e-03,-9.348829142806922010e-02,-3.351487938857349858e-01,9.302286069787435441e-02,1.265117085719307810e-01,-4.048512061142646168e-01
+-4.378336598923776024e-01,1.095522403432790115e-01,-2.442778464451337075e-02,2.363195766993489433e-02,2.808774127899463791e-01,-1.102372783072896045e-01,2.956860640207755742e-01,-4.144794111120361779e-01,1.181813277396247773e-02,3.318676187603694649e-01,1.581207081675166035e-02,1.744878856008896112e-02,-8.090169943725034063e-02,-1.100000000000000006e-01,-6.388550323392914176e-01,8.090169943725034063e-02,1.100000000000000006e-01,-7.211449676607086801e-01,1.404913785105110086e-02,-9.192613008363699489e-02,-3.299693215671190560e-01,8.595086214894942511e-02,1.280738699163629923e-01,-4.100306784328806020e-01
+-3.907770986518431799e-01,1.980260120109441357e-01,-1.395745259011499720e-02,3.546144753814869932e-02,2.498681818951911660e-01,-1.798060562185828937e-01,2.652653009979650256e-01,-5.040411986105819420e-01,5.665123502403063803e-03,3.478089728116781076e-01,1.743836329121996667e-02,1.886183327924566971e-02,-7.071067811836319328e-02,-1.100000000000000006e-01,-6.305025253167376720e-01,7.071067811836319328e-02,1.100000000000000006e-01,-7.294974746832624257e-01,2.200636594015255298e-02,-9.080900740028097218e-02,-3.257755374057261788e-01,7.799363405984802156e-02,1.291909925997190289e-01,-4.142244625942735903e-01
+-3.420655581754198371e-01,2.895443046028720047e-01,-4.841596824398482733e-03,5.160187264071232349e-02,2.178979182508225254e-01,-2.492728734071482655e-01,2.382376078098953909e-01,-5.905773675910074294e-01,-3.968751818094931605e-03,3.489874358007298838e-01,1.872202140061237849e-02,1.860051970966682816e-02,-5.877852522891653664e-02,-1.100000000000000006e-01,-6.233688103935854929e-01,5.877852522891653664e-02,1.100000000000000006e-01,-7.366311896064146048e-01,3.065289020535209158e-02,-9.016443064598270163e-02,-3.226707062859803243e-01,6.934710979464853153e-02,1.298355693540172995e-01,-4.173292937140195002e-01
+-2.922088815116906102e-01,3.793666227272375902e-01,2.782043068296049908e-03,7.120691346049982939e-02,1.851921758797396844e-01,-3.145830796563718335e-01,2.142641032473661666e-01,-6.714023036887694085e-01,-1.639386155552410157e-02,3.490610897375456267e-01,1.958198324589991920e-02,1.703940665425116366e-02,-4.539904997359345967e-02,-1.100000000000000006e-01,-6.176295433066854024e-01,4.539904997359345967e-02,1.100000000000000006e-01,-7.423704566933146953e-01,3.977580452307177827e-02,-9.000827143966057264e-02,-3.207312794543933365e-01,6.022419547692885872e-02,1.299917285603394146e-01,-4.192687205456065436e-01
+-2.418044428684952285e-01,4.622966703111866527e-01,8.810760645623817375e-03,9.227356492680222066e-02,1.520718893929003945e-01,-3.717175438109077690e-01,1.930679167296387722e-01,-7.407176961236465740e-01,-3.098756273295075539e-02,3.490656931085965864e-01,1.996643096951022933e-02,1.457753668240879992e-02,-3.090169943711247591e-02,-1.100000000000000006e-01,-6.134260438592523679e-01,3.090169943711247591e-02,1.100000000000000006e-01,-7.465739561407477298e-01,4.915047246559271082e-02,-9.034437493923695717e-02,-3.200050120361475070e-01,5.084952753440794698e-02,1.296556250607630301e-01,-4.199949879638524841e-01
+-1.915338529929054567e-01,5.348385334550578296e-01,1.318858593760939384e-02,1.124415214081133513e-01,1.189504629195316243e-01,-4.184620240921894663e-01,1.744406738131339951e-01,-7.942577162636135224e-01,-4.719277263897713598e-02,3.490659808192873026e-01,1.985221780111906184e-02,1.166413896004493689e-02,-1.564344650362951492e-02,-1.100000000000000006e-01,-6.108618161582968220e-01,1.564344650362951492e-02,1.100000000000000006e-01,-7.491381838417032757e-01,5.854605859543097340e-02,-9.116446516108869802e-02,-3.205097871454234415e-01,4.145394140456967053e-02,1.288355348389113031e-01,-4.194902128545766051e-01
+-1.421519329429800360e-01,5.953693400294310933e-01,1.591602986315231172e-02,1.297194457239819465e-01,8.632316183504763762e-02,-4.543397535396750397e-01,1.582451059995058640e-01,-8.301158477201798780e-01,-6.451373185771780427e-02,3.490659988012054238e-01,1.924197278443159909e-02,8.703821904293820855e-03,3.950129609048407979e-13,-1.100000000000000006e-01,-6.100000000000000977e-01,-3.950129609048407979e-13,1.100000000000000006e-01,-7.500000000000000000e-01,6.773121239990745335e-02,-9.244834876223041731e-02,-3.222331755437782275e-01,3.226878760009317670e-02,1.275516512377695699e-01,-4.177668244562219302e-01
+-9.447163462192638417e-02,6.433256773742996870e-01,1.705646484154945894e-02,1.426945809661017694e-01,5.475217720574440672e-02,-4.797609735122008723e-01,1.444180509876757390e-01,-8.476869101484327818e-01,-8.251230611437584961e-02,3.459210837702134667e-01,1.815963020592759741e-02,5.985677071177894319e-03,1.564344650440981435e-02,-1.100000000000000006e-01,-6.108618161583833084e-01,-1.564344650440981435e-02,1.100000000000000006e-01,-7.491381838416167893e-01,7.647976490857825993e-02,-9.416441226743665904e-02,-3.251327416892461630e-01,2.352023509142232849e-02,1.258355877325633421e-01,-4.148672583107540501e-01
+-4.934908311046525692e-02,6.773332858461015293e-01,1.673834903912885252e-02,1.498575406397904819e-01,2.485129274842163768e-02,-4.945905135247488649e-01,1.329767390240352010e-01,-8.412338040716716980e-01,-1.008067836228208614e-01,3.118859117672611037e-01,1.664499566589714222e-02,3.185372749434804696e-03,3.090169943786383322e-02,-1.100000000000000006e-01,-6.134260438594232312e-01,-3.090169943786383322e-02,1.100000000000000006e-01,-7.465739561405768665e-01,8.457629772389888001e-02,-9.627040049792098819e-02,-3.291370886402175677e-01,1.542370227610166677e-02,1.237295995020790129e-01,-4.108629113597827009e-01
+-7.673188384090706346e-03,6.991592328523453803e-01,1.515302578480305293e-02,1.516888329904694244e-01,-2.725583435801026515e-03,-5.007475828907317350e-01,1.240306783856180289e-01,-8.177541401312429237e-01,-1.190744289970639969e-01,2.714130818270913403e-01,1.474786567654276168e-02,7.917428048224313657e-04,4.539904997429991540e-02,-1.100000000000000006e-01,-6.176295433069374230e-01,-4.539904997429991540e-02,1.100000000000000006e-01,-7.423704566930626747e-01,9.182144733710556617e-02,-9.871445703407516481e-02,-3.341476160850949673e-01,8.178552662894904290e-03,1.212855429659248363e-01,-4.058523839149054124e-01
+2.963590179953126680e-02,7.098632864870516590e-01,1.254818146283267002e-02,1.487310921672354291e-01,-2.728787781530894740e-02,-4.994660274917409049e-01,1.178014005986885576e-01,-7.809684223226315281e-01,-1.370588412569659353e-01,2.278042664163967002e-01,1.252216408634920092e-02,-1.026656369184220877e-03,5.877852522955798187e-02,-1.100000000000000006e-01,-6.233688103939116765e-01,-5.877852522955798187e-02,1.100000000000000006e-01,-7.366311896060884212e-01,9.803681411944566160e-02,-1.014364010926196158e-01,-3.400409482091965030e-01,1.963185880554725593e-03,1.185635989073803853e-01,-3.999590517908039322e-01
+6.161585822272591662e-02,7.103901144864842587e-01,9.217067174997149379e-03,1.416878746224225216e-01,-4.810022722875394174e-02,-4.917885642700881021e-01,1.146525911130864689e-01,-7.340487569085422104e-01,-1.545832616040705709e-01,1.832300851372197781e-01,1.002054977257718638e-02,-2.367965080475235937e-03,7.071067811892382815e-02,-1.100000000000000006e-01,-6.305025253171300248e-01,-7.071067811892382815e-02,1.100000000000000006e-01,-7.294974746828700729e-01,1.030693551131197094e-01,-1.043692093772190105e-01,-3.466719716167797061e-01,-3.069355113119391631e-03,1.156307906227809906e-01,-3.933280283832207291e-01
+8.723604095486538201e-02,7.018536152208333379e-01,5.483080760992767484e-03,1.314589164205041405e-01,-6.436012173409821902e-02,-4.787833981381282022e-01,1.151334353456349990e-01,-6.803817301672251405e-01,-1.715712081083132778e-01,1.398613826570304641e-01,7.290000459005398399e-03,-3.411449538258539728e-03,8.090169943771638450e-02,-1.100000000000000006e-01,-6.388550323397405029e-01,-8.090169943771638450e-02,1.100000000000000006e-01,-7.211449676602595948e-01,1.067951524568174770e-01,-1.074406664144738899e-01,-3.538774085044450457e-01,-6.795152456817256381e-03,1.125593335855261112e-01,-3.861225914955555005e-01
+1.053548694616375375e-01,6.854951399739426243e-01,1.678016517506999115e-03,1.190053900475905591e-01,-7.516005639116833670e-02,-4.615221586752241145e-01,1.200377521514958135e-01,-6.233272708728355704e-01,-1.880758526940163600e-01,9.974724695628647830e-02,4.369022085614275401e-03,-4.366040839618078907e-03,8.910065241900640143e-02,-1.100000000000000006e-01,-6.482206650184647589e-01,-8.910065241900640143e-02,1.100000000000000006e-01,-7.117793349815353388e-01,1.091224646547247490e-01,-1.105751427385455871e-01,-3.614798371025441659e-01,-9.122464654724618538e-03,1.094248572614544140e-01,-3.785201628974563803e-01
+1.146620808151987414e-01,6.625800878596451726e-01,-1.890103041001673159e-03,1.052190971441798045e-01,-7.943570573498366649e-02,-4.410041489833595452e-01,1.304791654642908916e-01,-5.658964679601780068e-01,-2.043186049001004256e-01,6.461523056195207781e-02,1.287435098064656190e-03,-5.419406970912651368e-03,9.510565162962975050e-02,-1.100000000000000006e-01,-6.583688103940001923e-01,-9.510565162962975050e-02,1.100000000000000006e-01,-7.016311896059999054e-01,1.099939855566226810e-01,-1.136954571396049940e-01,-3.692920603879780161e-01,-9.993985556622675404e-03,1.063045428603950071e-01,-3.707079396120225301e-01
+1.136141537207372432e-01,6.342675291546066019e-01,-4.987495030902463523e-03,9.083235139012965642e-02,-7.590858215711161761e-02,-4.180607698335656597e-01,1.479745070386431216e-01,-5.104581687380156385e-01,-2.207334564721500636e-01,3.567820158532517688e-02,-1.929766589179787283e-03,-6.698175941195924805e-03,9.876883405957113948e-02,-1.100000000000000006e-01,-6.690495874474373661e-01,-9.876883405957113948e-02,1.100000000000000006e-01,-6.909504125525627316e-01,1.093882554254945599e-01,-1.167247771213682644e-01,-3.771217154961767348e-01,-9.388255425494637652e-03,1.032752228786317367e-01,-3.628782845038238114e-01
+1.003892154373007412e-01,6.015091030967059105e-01,-7.536003586231287792e-03,7.639017381963639219e-02,-6.304935679313061758e-02,-3.932898026086306120e-01,1.745055716387869660e-01,-4.585879697249071185e-01,-2.380022910161098959e-01,1.353823766679318474e-02,-5.252174634801017386e-03,-8.248665217474283884e-03,1.000000000000000056e-01,-1.100000000000000006e-01,-6.800000000002542899e-01,-1.000000000000000056e-01,1.100000000000000006e-01,-6.799999999997458078e-01,1.073201893474717561e-01,-1.195885107721478130e-01,-3.847760103332409920e-01,-7.320189347471944830e-03,1.004114892278521881e-01,-3.552239896667594987e-01
+7.293045398876848995e-02,5.650199172965808536e-01,-9.739606996867340022e-03,6.227748628587062574e-02,-3.912876259633858711e-02,-3.670525667957836302e-01,2.124776593401640767e-01,-4.111058022725422312e-01,-2.570391413970054550e-01,-1.772078937584583170e-03,-8.624325639774391844e-03,-1.003981562877453645e-02,9.876883405945706407e-02,-1.100000000000000006e-01,-6.909504125530668839e-01,-9.876883405945706407e-02,1.100000000000000006e-01,-6.690495874469332138e-01,1.038407099729122540e-01,-1.222161434652748457e-01,-3.920664707571355212e-01,-3.840709972912539905e-03,9.778385653472515537e-02,-3.479335292428649140e-01
+2.922878092660034094e-02,5.253190287851022822e-01,-1.225311428525187492e-02,4.877165008272302954e-02,-2.497974192344465036e-03,-3.395273341124835365e-01,2.643954788351647323e-01,-3.682489008899042515e-01,-2.788295816941136485e-01,-1.064761765357317633e-02,-1.193481551194829592e-02,-1.198181587149049938e-02,9.510565162940438910e-02,-1.100000000000000006e-01,-7.016311896064854059e-01,-9.510565162940438910e-02,1.100000000000000006e-01,-6.583688103935146918e-01,9.903549363174890541e-02,-1.245429741632307075e-01,-3.988135814365705301e-01,9.645063682507185043e-04,9.545702583676929365e-02,-3.411864185634299051e-01
+-3.191699582615576541e-02,4.828051591274801768e-01,-1.631742097940021632e-02,3.609134981994922831e-02,4.768801171567736696e-02,-3.107876914947304003e-01,3.319682847529188963e-01,-3.298837045291000414e-01,-3.039753575653595941e-01,-1.374068819079606561e-02,-1.498012027519774608e-02,-1.395079121644054662e-02,8.910065241867531904e-02,-1.100000000000000006e-01,-7.117793349819901971e-01,-8.910065241867531904e-02,1.100000000000000006e-01,-6.482206650180099006e-01,9.302286069789933443e-02,-1.265117085719239254e-01,-4.048512061142432450e-01,6.977139302100227036e-03,9.348829142807607573e-02,-3.351487938857571347e-01
+-1.095522403429329550e-01,4.378336598925619549e-01,-2.363195766989617183e-02,2.442778464455784906e-02,1.102372783070138251e-01,-2.808774127900684481e-01,4.144794111116730240e-01,-2.956860640209034163e-01,-3.318676187602530026e-01,-1.181813277398040436e-02,-1.744878856008077669e-02,-1.581207081674458961e-02,8.090169943728774127e-02,-1.100000000000000006e-01,-7.211449676606725978e-01,-8.090169943728774127e-02,1.100000000000000006e-01,-6.388550323393274999e-01,8.595086214897945665e-02,-1.280738699163575522e-01,-4.100306784328618392e-01,1.404913785102002849e-02,9.192613008364243499e-02,-3.299693215671384294e-01
+-1.980260120105735155e-01,3.907770986520351930e-01,-3.546144753809139794e-02,1.395745259015439450e-02,1.798060562182961508e-01,-2.498681818953173983e-01,5.040411986102221187e-01,-2.652653009980784904e-01,-3.478089728116638413e-01,-5.665123502436430342e-03,-1.886183327924353254e-02,-1.743836329121394371e-02,7.071067811840817119e-02,-1.100000000000000006e-01,-7.294974746832310064e-01,-7.071067811840817119e-02,1.100000000000000006e-01,-6.305025253167690913e-01,7.799363405988120335e-02,-1.291909925997154485e-01,-4.142244625942589908e-01,2.200636594011822628e-02,9.080900740028455265e-02,-3.257755374057412778e-01
+-2.895443046024992473e-01,3.420655581756166796e-01,-5.160187264063872264e-02,4.841596824431963764e-03,2.492728734068712648e-01,-2.178979182509518386e-01,5.905773675906630382e-01,-2.382376078099947558e-01,-3.489874358007289956e-01,3.968751818049018679e-03,-1.860051970967092905e-02,-1.872202140060815964e-02,5.877852522896799548e-02,-1.100000000000000006e-01,-7.366311896063884035e-01,-5.877852522896799548e-02,1.100000000000000006e-01,-6.233688103936116942e-01,6.934710979468403091e-02,-1.298355693540156619e-01,-4.173292937140094527e-01,3.065289020531535361e-02,9.016443064598432533e-02,-3.226707062859907049e-01
+-3.793666227268824298e-01,2.922088815118907834e-01,-7.120691346041546632e-02,-2.782043068268822555e-03,3.145830796561204790e-01,-1.851921758798710516e-01,6.714023036884592122e-01,-2.142641032474535412e-01,-3.490610897375455712e-01,1.639386155546709856e-02,-1.703940665425972972e-02,-1.958198324589744202e-02,4.539904997365013656e-02,-1.100000000000000006e-01,-7.423704566932944893e-01,-4.539904997365013656e-02,1.100000000000000006e-01,-6.176295433067056084e-01,6.022419547696582914e-02,-1.299917285603397754e-01,-4.192687205456012700e-01,3.977580452303353803e-02,9.000827143966021182e-02,-3.207312794543988321e-01
+-4.622966703108702946e-01,2.418044428686979830e-01,-9.227356492671741350e-02,-8.810760645602790792e-03,3.717175438106968821e-01,-1.520718893930341209e-01,7.407176961233971069e-01,-1.930679167297172372e-01,-3.490656931085965864e-01,3.098756273288396160e-02,-1.457753668241974256e-02,-1.996643096950960830e-02,3.090169943717296572e-02,-1.100000000000000006e-01,-7.465739561407339631e-01,-3.090169943717296572e-02,1.100000000000000006e-01,-6.134260438592661346e-01,5.084952753444545864e-02,-1.296556250607653893e-01,-4.199949879638520400e-01,4.915047246555390159e-02,9.034437493923459794e-02,-3.200050120361480066e-01
+-5.348385334547868242e-01,1.915338529931064904e-01,-1.124415214080360936e-01,-1.318858593759495920e-02,4.184620240920217671e-01,-1.189504629196646013e-01,7.942577162634312238e-01,-1.744406738132024681e-01,-3.490659808192873026e-01,4.719277263890427065e-02,-1.166413896005689954e-02,-1.985221780112038023e-02,1.564344650369233966e-02,-1.100000000000000006e-01,-7.491381838416963923e-01,-1.564344650369233966e-02,1.100000000000000006e-01,-6.108618161583037054e-01,4.145394140460680749e-02,-1.288355348389155774e-01,-4.194902128545810460e-01,5.854605859539255969e-02,9.116446516108440978e-02,-3.205097871454188896e-01
+-5.953693400292178195e-01,1.421519329431659706e-01,-1.297194457239214116e-01,-1.591602986314501894e-02,4.543397535395547471e-01,-8.632316183517092789e-02,8.301158477200716312e-01,-1.582451059995610421e-01,-3.490659988012054238e-01,6.451373185764772145e-02,-8.703821904305093088e-03,-1.924197278443486037e-02,-3.342493105293607560e-13,-1.100000000000000006e-01,-7.500000000000000000e-01,3.342493105293607560e-13,1.100000000000000006e-01,-6.100000000000000977e-01,3.226878760012738545e-02,-1.275516512377753986e-01,-4.177668244562307565e-01,6.773121239987200948e-02,9.244834876222458864e-02,-3.222331755437690681e-01
+-6.433256773741395929e-01,9.447163462210300677e-02,-1.426945809660616071e-01,-1.705646484154811279e-02,4.797609735121227681e-01,-5.475217720586138953e-02,8.476869101484086899e-01,-1.444180509877212859e-01,-3.459210837703209362e-01,8.251230611430802886e-02,-5.985677071187825611e-03,-1.815963020593238178e-02,-1.564344650434979986e-02,-1.100000000000000006e-01,-7.491381838416234507e-01,1.564344650434979986e-02,1.100000000000000006e-01,-6.108618161583766470e-01,2.352023509145446598e-02,-1.258355877325707528e-01,-4.148672583107672063e-01,7.647976490854496712e-02,9.416441226742923443e-02,-3.251327416892325073e-01
+-6.773332858459929495e-01,4.934908311063082587e-02,-1.498575406397727461e-01,-1.673834903913271055e-02,4.945905135247083972e-01,-2.485129274853152895e-02,8.412338040717309839e-01,-1.329767390240721159e-01,-3.118859117674122605e-01,1.008067836227540259e-01,-3.185372749445664065e-03,-1.664499566590442112e-02,-3.090169943780604264e-02,-1.100000000000000006e-01,-7.465739561405899671e-01,3.090169943780604264e-02,1.100000000000000006e-01,-6.134260438594101306e-01,1.542370227613092809e-02,-1.237295995020878531e-01,-4.108629113597999094e-01,8.457629772386854317e-02,9.627040049791214804e-02,-3.291370886401997486e-01
+-6.991592328522791000e-01,7.673188384249204561e-03,-1.516888329904718391e-01,-1.515302578481170052e-02,5.007475828907220761e-01,2.725583435696305595e-03,8.177541401313658254e-01,-1.240306783856465478e-01,-2.714130818272628143e-01,1.190744289969895009e-01,-7.917428048308668923e-04,-1.474786567655112131e-02,-4.539904997424323851e-02,-1.100000000000000006e-01,-7.423704566930828808e-01,4.539904997424323851e-02,1.100000000000000006e-01,-6.176295433069172169e-01,8.178552662921806382e-03,-1.212855429659353418e-01,-4.058523839149271728e-01,9.182144733707774120e-02,9.871445703406465932e-02,-3.341476160850724297e-01
+-7.098632864870286774e-01,-2.963590179939218708e-02,-1.487310921672559128e-01,-1.254818146284484084e-02,4.994660274917591680e-01,2.728787781521779116e-02,7.809684223228017252e-01,-1.178014005987058910e-01,-2.278042664165755848e-01,1.370588412568934655e-01,1.026656369177981728e-03,-1.252216408635875404e-02,-5.877852522950652303e-02,-1.100000000000000006e-01,-7.366311896061145115e-01,5.877852522950652303e-02,1.100000000000000006e-01,-6.233688103938855862e-01,1.963185880577200670e-03,-1.185635989073918761e-01,-3.999590517908289677e-01,9.803681411942241630e-02,1.014364010926081250e-01,-3.400409482091706348e-01
+-7.103901144865011341e-01,-6.161585822261007178e-02,-1.416878746224579655e-01,-9.217067175011670749e-03,4.917885642701304572e-01,4.810022722867930006e-02,7.340487569087472686e-01,-1.146525911130908543e-01,-1.832300851373987183e-01,1.545832616040003771e-01,2.367965080470607695e-03,-1.002054977258785319e-02,-7.071067811887886412e-02,-1.100000000000000006e-01,-7.294974746829014922e-01,7.071067811887886412e-02,1.100000000000000006e-01,-6.305025253170986055e-01,-3.069355113101891741e-03,-1.156307906227931892e-01,-3.933280283832484292e-01,1.030693551131015850e-01,1.043692093772068119e-01,-3.466719716167511178e-01
+-7.018536152208842971e-01,-8.723604095477741072e-02,-1.314589164205505756e-01,-5.483080761008155349e-03,4.787833981381899862e-01,6.436012173404374870e-02,6.803817301674504048e-01,-1.151334353456227588e-01,-1.398613826571972196e-01,1.715712081082433893e-01,3.411449538254831756e-03,-7.290000459016962933e-03,-8.090169943767899774e-02,-1.100000000000000006e-01,-7.211449676602956771e-01,8.090169943767899774e-02,1.100000000000000006e-01,-6.388550323397044206e-01,-6.795152456805161889e-03,-1.125593335855387261e-01,-3.861225914955850880e-01,1.067951524568049593e-01,1.074406664144612750e-01,-3.538774085044144035e-01
+-6.854951399740231155e-01,-1.053548694615821096e-01,-1.190053900476444326e-01,-1.678016517522126121e-03,4.615221586753016081e-01,7.516005639113784720e-02,6.233272708730689393e-01,-1.200377521514640472e-01,-9.974724695643755190e-02,1.880758526939480813e-01,4.366040839614219148e-03,-4.369022085626588468e-03,-8.910065241897752175e-02,-1.100000000000000006e-01,-7.117793349815749737e-01,8.910065241897752175e-02,1.100000000000000006e-01,-6.482206650184251240e-01,-9.122464654718234756e-03,-1.094248572614671261e-01,-3.785201628974871890e-01,1.091224646547181293e-01,1.105751427385328750e-01,-3.614798371025122470e-01
+-6.625800878597459809e-01,-1.146620808151820464e-01,-1.052190971442351075e-01,1.890103040988636495e-03,4.410041489834447548e-01,7.943570573498157095e-02,5.658964679603992742e-01,-1.304791654642375454e-01,-6.461523056207704729e-02,2.043186049000374482e-01,5.419406970908120270e-03,-1.287435098076905289e-03,-9.510565162961095997e-02,-1.100000000000000006e-01,-7.016311896060404285e-01,9.510565162961095997e-02,1.100000000000000006e-01,-6.583688103939596692e-01,-9.993985556622161925e-03,-1.063045428604069559e-01,-3.707079396120523396e-01,1.099939855566221536e-01,1.136954571395930452e-01,-3.692920603879470964e-01
+-6.342675291547267280e-01,-1.136141537207638746e-01,-9.083235139018619453e-02,4.987495030891601552e-03,4.180607698336590294e-01,7.590858215714238466e-02,5.104581687382262478e-01,-1.479745070385589389e-01,-3.567820158542543002e-02,2.207334564720844217e-01,6.698175941190362415e-03,1.929766589167069375e-03,-9.876883405956163320e-02,-1.100000000000000006e-01,-6.909504125526046980e-01,9.876883405956163320e-02,1.100000000000000006e-01,-6.690495874473953997e-01,-9.388255425499737739e-03,-1.032752228786431858e-01,-3.628782845038533433e-01,1.093882554254998474e-01,1.167247771213568153e-01,-3.771217154961461482e-01
+-6.015091030968420238e-01,-1.003892154373783041e-01,-7.639017381969234743e-02,7.536003586222288914e-03,3.932898026087302545e-01,6.304935679320097797e-02,4.585879697251020737e-01,-1.745055716386632316e-01,-1.353823766686646467e-02,2.380022910160396743e-01,8.248665217467681526e-03,5.252174634787767568e-03,-1.000000000000000056e-01,-1.100000000000000006e-01,-6.799999999997883293e-01,1.000000000000000056e-01,1.100000000000000006e-01,-6.800000000002117684e-01,-7.320189347482533582e-03,-1.004114892278628601e-01,-3.552239896667880314e-01,1.073201893474827195e-01,1.195885107721371410e-01,-3.847760103332114601e-01
+-5.650199172967369510e-01,-7.293045398890928011e-02,-6.227748628592717078e-02,9.739606996858400992e-03,3.670525667958933758e-01,3.912876259645862304e-02,4.111058022727271943e-01,-2.124776593399863023e-01,1.772078937535223782e-03,2.570391413969245753e-01,1.003981562876682040e-02,8.624325639760793347e-03,-9.876883405946701444e-02,-1.100000000000000006e-01,-6.690495874469771787e-01,9.876883405946701444e-02,1.100000000000000006e-01,-6.909504125530229190e-01,-3.840709972929096105e-03,-9.778385653473523065e-02,-3.479335292428930027e-01,1.038407099729293792e-01,1.222161434652647705e-01,-3.920664707571065444e-01
+-5.253190287852709250e-01,-2.922878092680929879e-02,-4.877165008277662556e-02,1.225311428523954971e-02,3.395273341125985556e-01,2.497974192517899220e-03,3.682489008900711180e-01,-2.643954788349273666e-01,1.064761765354832294e-02,2.788295816940190575e-01,1.198181587148246761e-02,1.193481551193479977e-02,-9.510565162942404005e-02,-1.100000000000000006e-01,-6.583688103935569913e-01,9.510565162942404005e-02,1.100000000000000006e-01,-7.016311896064431064e-01,9.645063682291038498e-04,-9.545702583677802278e-02,-3.411864185634554403e-01,9.903549363177127640e-02,1.245429741632219783e-01,-3.988135814365441068e-01
+-4.828051591276595889e-01,3.191699582587860518e-02,-3.609134981999913977e-02,1.631742097937874392e-02,3.107876914948504155e-01,-4.768801171545167250e-02,3.298837045292493664e-01,-3.319682847526205238e-01,1.374068819079325883e-02,3.039753575652551221e-01,1.395079121643261547e-02,1.498012027518666120e-02,-8.910065241870419872e-02,-1.100000000000000006e-01,-6.482206650180496466e-01,8.910065241870419872e-02,1.100000000000000006e-01,-7.117793349819504511e-01,6.977139302074081284e-03,-9.348829142808325054e-02,-3.351487938857795612e-01,9.302286069792636836e-02,1.265117085719167367e-01,-4.048512061142200413e-01
+-4.378336598927508039e-01,1.095522403425960439e-01,-2.442778464460316004e-02,2.363195766985830976e-02,2.808774127901932371e-01,-1.102372783067450818e-01,2.956860640210366431e-01,-4.144794111113219159e-01,1.181813277399591106e-02,3.318676187601403704e-01,1.581207081673748072e-02,1.744878856007246737e-02,-8.090169943732511415e-02,-1.100000000000000006e-01,-6.388550323393634711e-01,8.090169943732511415e-02,1.100000000000000006e-01,-7.211449676606366266e-01,1.404913785098999002e-02,-9.192613008364787508e-02,-3.299693215671571922e-01,8.595086214901054289e-02,1.280738699163521122e-01,-4.100306784328424659e-01
+-3.907770986522331458e-01,1.980260120102157462e-01,-1.395745259019487948e-02,3.546144753803608801e-02,2.498681818954475997e-01,-1.798060562180196220e-01,2.652653009981992827e-01,-5.040411986098780606e-01,5.665123502468658034e-03,3.478089728116498525e-01,1.743836329120777504e-02,1.886183327924142658e-02,-7.071067811845314910e-02,-1.100000000000000006e-01,-6.305025253168006216e-01,7.071067811845314910e-02,1.100000000000000006e-01,-7.294974746831994761e-01,2.200636594008504449e-02,-9.080900740028813312e-02,-3.257755374057558218e-01,7.799363405991553699e-02,1.291909925997118680e-01,-4.142244625942438918e-01
+-3.420655581758107466e-01,2.895443046021461964e-01,-4.841596824464920040e-03,5.160187264056869533e-02,2.178979182510790424e-01,-2.492728734066083085e-01,2.382376078100968131e-01,-5.905773675903366327e-01,-3.968751818006805918e-03,3.489874358007281074e-01,1.872202140060382283e-02,1.860051970967456850e-02,-5.877852522901714366e-02,-1.100000000000000006e-01,-6.233688103936366742e-01,5.877852522901714366e-02,1.100000000000000006e-01,-7.366311896063634235e-01,3.065289020528145711e-02,-9.016443064598587964e-02,-3.226707062860003639e-01,6.934710979471915560e-02,1.298355693540141076e-01,-4.173292937139994607e-01
+-2.922088815120883476e-01,3.793666227265469204e-01,2.782043068241936076e-03,7.120691346033540536e-02,1.851921758800006423e-01,-3.145830796558820031e-01,2.142641032475444685e-01,-6.714023036881666684e-01,-1.639386155541575074e-02,3.490610897375454602e-01,1.958198324589488851e-02,1.703940665426762965e-02,-4.539904997370428075e-02,-1.100000000000000006e-01,-6.176295433067249263e-01,4.539904997370428075e-02,1.100000000000000006e-01,-7.423704566932751714e-01,3.977580452299825375e-02,-9.000827143965986488e-02,-3.207312794544039392e-01,6.022419547700239018e-02,1.299917285603401362e-01,-4.192687205455959409e-01
+-2.418044428688946867e-01,4.622966703105672037e-01,8.810760645582598610e-03,9.227356492663577048e-02,1.520718893931631566e-01,-3.717175438104943219e-01,1.930679167297961463e-01,-7.407176961231553003e-01,-3.098756273282863086e-02,3.490656931085965309e-01,1.996643096950927523e-02,1.457753668243058631e-02,-3.090169943723075630e-02,-1.100000000000000006e-01,-6.134260438592792353e-01,3.090169943723075630e-02,1.100000000000000006e-01,-7.465739561407208624e-01,4.915047246551809690e-02,-9.034437493923234974e-02,-3.200050120361483952e-01,5.084952753448256091e-02,1.296556250607676375e-01,-4.199949879638515959e-01
+-1.915338529933013068e-01,5.348385334545291414e-01,1.318858593758126876e-02,1.124415214079624997e-01,1.189504629197929569e-01,-4.184620240918619505e-01,1.744406738132720514e-01,-7.942577162632570298e-01,-4.719277263884465862e-02,3.490659808192873026e-01,1.985221780112220863e-02,1.166413896006862974e-02,-1.564344650375235415e-02,-1.100000000000000006e-01,-6.108618161583103667e-01,1.564344650375235415e-02,1.100000000000000006e-01,-7.491381838416897310e-01,5.854605859535711582e-02,-9.116446516108032971e-02,-3.205097871454146152e-01,4.145394140464353505e-02,1.288355348389196575e-01,-4.194902128545854314e-01
+-1.421519329433657275e-01,5.953693400290004378e-01,1.591602986313713289e-02,1.297194457238604048e-01,8.632316183530285014e-02,-4.543397535394325670e-01,1.582451059996249076e-01,-8.301158477199664931e-01,-6.451373185757706963e-02,3.490659988012054238e-01,1.924197278443834716e-02,8.703821904316682775e-03,2.706434892108403234e-13,-1.100000000000000006e-01,-6.100000000000000977e-01,-2.706434892108403234e-13,1.100000000000000006e-01,-7.500000000000000000e-01,6.773121239983616315e-02,-9.244834876221849629e-02,-3.222331755437598533e-01,3.226878760016445996e-02,1.275516512377815048e-01,-4.177668244562403044e-01
+-9.447163462229385411e-02,6.433256773739777223e-01,1.705646484154649603e-02,1.426945809660219999e-01,5.475217720598777454e-02,-4.797609735120446084e-01,1.444180509877753815e-01,-8.476869101483922586e-01,-8.251230611423579497e-02,3.459210837704325692e-01,1.815963020593777330e-02,5.985677071197630268e-03,1.564344650428697511e-02,-1.100000000000000006e-01,-6.108618161583696526e-01,-1.564344650428697511e-02,1.100000000000000006e-01,-7.491381838416304451e-01,7.647976490851129960e-02,-9.416441226742146287e-02,-3.251327416892187405e-01,2.352023509148929228e-02,1.258355877325785244e-01,-4.148672583107815282e-01
+-4.934908311080949544e-02,6.773332858458823713e-01,1.673834903913669347e-02,1.498575406397556764e-01,2.485129274864982321e-02,-4.945905135246678741e-01,1.329767390241164415e-01,-8.412338040717970422e-01,-1.008067836226815006e-01,3.118859117675671366e-01,1.664499566591138777e-02,3.185372749456353864e-03,3.090169943774555283e-02,-1.100000000000000006e-01,-6.134260438593963638e-01,-3.090169943774555283e-02,1.100000000000000006e-01,-7.465739561406037339e-01,8.457629772383788713e-02,-9.627040049790289156e-02,-3.291370886401817630e-01,1.542370227616265271e-02,1.237295995020971096e-01,-4.108629113598185612e-01
+-7.673188384412192239e-03,6.991592328522145960e-01,1.515302578482037588e-02,1.516888329904747534e-01,-2.725583435589134379e-03,-5.007475828907133053e-01,1.240306783856796741e-01,-8.177541401314903924e-01,-1.190744289969137837e-01,2.714130818274305690e-01,1.474786567655971166e-02,7.917428048390518598e-04,4.539904997418656163e-02,-1.100000000000000006e-01,-6.176295433068970109e-01,-4.539904997418656163e-02,1.100000000000000006e-01,-7.423704566931030868e-01,9.182144733705083217e-02,-9.871445703405415384e-02,-3.341476160850506139e-01,8.178552662949631347e-03,1.212855429659458473e-01,-4.058523839149497103e-01
+2.963590179924924933e-02,7.098632864870066950e-01,1.254818146285714697e-02,1.487310921672766739e-01,-2.728787781512406752e-02,-4.994660274917779308e-01,1.178014005987267632e-01,-7.809684223229730327e-01,-1.370588412568191916e-01,2.278042664167524989e-01,1.252216408636869574e-02,-1.026656369171891764e-03,5.877852522945506419e-02,-1.100000000000000006e-01,-6.233688103938593850e-01,-5.877852522945506419e-02,1.100000000000000006e-01,-7.366311896061407127e-01,9.803681411939993429e-02,-1.014364010925966203e-01,-3.400409482091455993e-01,1.963185880600459843e-03,1.185635989074033808e-01,-3.999590517908548359e-01
+6.161585822249636413e-02,7.103901144865174544e-01,9.217067175025626599e-03,1.416878746224920771e-01,-4.810022722860599065e-02,-4.917885642701712023e-01,1.146525911130981956e-01,-7.340487569089443332e-01,-1.545832616039340135e-01,1.832300851375704698e-01,1.002054977259805336e-02,-2.367965080466072261e-03,7.071067811883589849e-02,-1.100000000000000006e-01,-6.305025253170685184e-01,-7.071067811883589849e-02,1.100000000000000006e-01,-7.294974746829315793e-01,1.030693551130848762e-01,-1.043692093771951407e-01,-3.466719716167246945e-01,-3.069355113084579201e-03,1.156307906228048604e-01,-3.933280283832757407e-01
+8.723604095469064679e-02,7.018536152209339241e-01,5.483080761023041011e-03,1.314589164205952898e-01,-6.436012173398981961e-02,-4.787833981382496051e-01,1.151334353456147930e-01,-6.803817301676682305e-01,-1.715712081081808282e-01,1.398613826573626429e-01,7.290000459027803220e-03,-3.411449538250859240e-03,8.090169943764327631e-02,-1.100000000000000006e-01,-6.388550323396700037e-01,-8.090169943764327631e-02,1.100000000000000006e-01,-7.211449676603300940e-01,1.067951524567934130e-01,-1.074406664144492290e-01,-3.538774085043861484e-01,-6.795152456793199236e-03,1.125593335855507721e-01,-3.861225914956143423e-01
+1.053548694615270703e-01,6.854951399740997209e-01,1.678016517536557936e-03,1.190053900476956000e-01,-7.516005639110709402e-02,-4.615221586753752714e-01,1.200377521514368329e-01,-6.233272708732925382e-01,-1.880758526938866304e-01,9.974724695658561402e-02,4.369022085638205911e-03,-4.366040839610275254e-03,8.910065241894993271e-02,-1.100000000000000006e-01,-6.482206650183872654e-01,-8.910065241894993271e-02,1.100000000000000006e-01,-7.117793349816128323e-01,1.091224646547120231e-01,-1.105751427385207319e-01,-3.614798371024828816e-01,-9.122464654711906484e-03,1.094248572614792692e-01,-3.785201628975176646e-01
+1.146620808151638110e-01,6.625800878598493426e-01,-1.890103040975052960e-03,1.052190971442921036e-01,-7.943570573497880927e-02,-4.410041489835325734e-01,1.304791654641826726e-01,-5.658964679606276471e-01,-2.043186048999719728e-01,6.461523056220709604e-02,1.287435098089621897e-03,-5.419406970903599581e-03,9.510565162959130903e-02,-1.100000000000000006e-01,-6.583688103939173697e-01,-9.510565162959130903e-02,1.100000000000000006e-01,-7.016311896060827280e-01,1.099939855566216262e-01,-1.136954571395805413e-01,-3.692920603879158437e-01,-9.993985556621613753e-03,1.063045428604194598e-01,-3.707079396120847026e-01
+1.136141537207915608e-01,6.342675291548496297e-01,-4.987495030880216562e-03,9.083235139024438409e-02,-7.590858215717449786e-02,-4.180607698337551192e-01,1.479745070384712036e-01,-5.104581687384422972e-01,-2.207334564720167258e-01,3.567820158552814647e-02,-1.929766589153811751e-03,-6.698175941184603133e-03,9.876883405955168282e-02,-1.100000000000000006e-01,-6.690495874473514348e-01,-9.876883405955168282e-02,1.100000000000000006e-01,-6.909504125526486629e-01,1.093882554255051764e-01,-1.167247771213448387e-01,-3.771217154961151730e-01,-9.388255425505268037e-03,1.032752228786551624e-01,-3.628782845038853178e-01
diff --git a/src/mjlab/asset_zoo/robots/__init__.py b/src/mjlab/asset_zoo/robots/__init__.py
index f855d966c..a0c4d8e97 100644
--- a/src/mjlab/asset_zoo/robots/__init__.py
+++ b/src/mjlab/asset_zoo/robots/__init__.py
@@ -1,3 +1,9 @@
+from mjlab.asset_zoo.robots.humanoid.humanoid_constants import (
+ HUMANOID_ACTION_SCALE as HUMANOID_ACTION_SCALE,
+)
+from mjlab.asset_zoo.robots.humanoid.humanoid_constants import (
+ get_humanoid_robot_cfg as get_humanoid_robot_cfg,
+)
from mjlab.asset_zoo.robots.i2rt_yam.yam_constants import (
YAM_ACTION_SCALE as YAM_ACTION_SCALE,
)
diff --git a/src/mjlab/asset_zoo/robots/humanoid/__init__.py b/src/mjlab/asset_zoo/robots/humanoid/__init__.py
new file mode 100644
index 000000000..397f9759e
--- /dev/null
+++ b/src/mjlab/asset_zoo/robots/humanoid/__init__.py
@@ -0,0 +1,25 @@
+"""Humanoid robot configuration."""
+
+from mjlab.asset_zoo.robots.humanoid.humanoid_constants import (
+ HUMANOID_ACTION_SCALE,
+ HUMANOID_ARTICULATION,
+ HUMANOID_XML,
+ FEET_ONLY_COLLISION,
+ FULL_COLLISION,
+ HOME_KEYFRAME,
+ get_humanoid_robot_cfg,
+ get_assets,
+ get_spec,
+)
+
+__all__ = [
+ "HUMANOID_ACTION_SCALE",
+ "HUMANOID_ARTICULATION",
+ "HUMANOID_XML",
+ "FEET_ONLY_COLLISION",
+ "FULL_COLLISION",
+ "HOME_KEYFRAME",
+ "get_humanoid_robot_cfg",
+ "get_assets",
+ "get_spec",
+]
diff --git a/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/base_link.stl b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/base_link.stl
new file mode 100755
index 000000000..781e84af8
Binary files /dev/null and b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/base_link.stl differ
diff --git a/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/camera_link.stl b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/camera_link.stl
new file mode 100755
index 000000000..2875818f6
Binary files /dev/null and b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/camera_link.stl differ
diff --git a/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/chest_link.stl b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/chest_link.stl
new file mode 100755
index 000000000..29edf81be
Binary files /dev/null and b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/chest_link.stl differ
diff --git a/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/head_link.stl b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/head_link.stl
new file mode 100755
index 000000000..1c480b6e6
Binary files /dev/null and b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/head_link.stl differ
diff --git a/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/humanoid_pkg.urdf b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/humanoid_pkg.urdf
new file mode 100755
index 000000000..2fef9de75
--- /dev/null
+++ b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/humanoid_pkg.urdf
@@ -0,0 +1,2062 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
\ No newline at end of file
diff --git a/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/humanoid_pkg.xml b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/humanoid_pkg.xml
new file mode 100644
index 000000000..755ffc859
--- /dev/null
+++ b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/humanoid_pkg.xml
@@ -0,0 +1,209 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/left_ankle1_link.stl b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/left_ankle1_link.stl
new file mode 100755
index 000000000..5dbb74860
Binary files /dev/null and b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/left_ankle1_link.stl differ
diff --git a/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/left_ankle2_link.stl b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/left_ankle2_link.stl
new file mode 100755
index 000000000..0101bd7c4
Binary files /dev/null and b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/left_ankle2_link.stl differ
diff --git a/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/left_elbow_forearm_yaw_link.stl b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/left_elbow_forearm_yaw_link.stl
new file mode 100755
index 000000000..a97d4eabf
Binary files /dev/null and b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/left_elbow_forearm_yaw_link.stl differ
diff --git a/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/left_elbow_yaw_link.stl b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/left_elbow_yaw_link.stl
new file mode 100755
index 000000000..a98bccbb7
Binary files /dev/null and b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/left_elbow_yaw_link.stl differ
diff --git a/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/left_foot1_link.stl b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/left_foot1_link.stl
new file mode 100755
index 000000000..fa4429a48
Binary files /dev/null and b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/left_foot1_link.stl differ
diff --git a/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/left_foot2_link.stl b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/left_foot2_link.stl
new file mode 100755
index 000000000..6cd39a0fb
Binary files /dev/null and b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/left_foot2_link.stl differ
diff --git a/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/left_hip_pitch_link.stl b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/left_hip_pitch_link.stl
new file mode 100755
index 000000000..4ec959c79
Binary files /dev/null and b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/left_hip_pitch_link.stl differ
diff --git a/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/left_hip_roll_link.stl b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/left_hip_roll_link.stl
new file mode 100755
index 000000000..880e6db30
Binary files /dev/null and b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/left_hip_roll_link.stl differ
diff --git a/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/left_hip_yaw_link.stl b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/left_hip_yaw_link.stl
new file mode 100755
index 000000000..ad2baf1a9
Binary files /dev/null and b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/left_hip_yaw_link.stl differ
diff --git a/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/left_knee_link.stl b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/left_knee_link.stl
new file mode 100644
index 000000000..620e6233f
Binary files /dev/null and b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/left_knee_link.stl differ
diff --git a/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/left_shoulder_pitch_link.stl b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/left_shoulder_pitch_link.stl
new file mode 100755
index 000000000..9598c0c0f
Binary files /dev/null and b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/left_shoulder_pitch_link.stl differ
diff --git a/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/left_shoulder_roll_link.stl b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/left_shoulder_roll_link.stl
new file mode 100755
index 000000000..e57f2ba41
Binary files /dev/null and b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/left_shoulder_roll_link.stl differ
diff --git a/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/left_wrist_yaw_link.stl b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/left_wrist_yaw_link.stl
new file mode 100755
index 000000000..56a08e8ee
Binary files /dev/null and b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/left_wrist_yaw_link.stl differ
diff --git a/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/neck_link.stl b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/neck_link.stl
new file mode 100755
index 000000000..ce26e0e36
Binary files /dev/null and b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/neck_link.stl differ
diff --git a/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/neck_yaw_link.stl b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/neck_yaw_link.stl
new file mode 100755
index 000000000..b71143407
Binary files /dev/null and b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/neck_yaw_link.stl differ
diff --git a/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/right_ankle1_link.stl b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/right_ankle1_link.stl
new file mode 100755
index 000000000..690e7e7d6
Binary files /dev/null and b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/right_ankle1_link.stl differ
diff --git a/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/right_ankle2_link.stl b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/right_ankle2_link.stl
new file mode 100755
index 000000000..e86044c6b
Binary files /dev/null and b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/right_ankle2_link.stl differ
diff --git a/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/right_elbow_forearm_yaw_link.stl b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/right_elbow_forearm_yaw_link.stl
new file mode 100755
index 000000000..f7cb79929
Binary files /dev/null and b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/right_elbow_forearm_yaw_link.stl differ
diff --git a/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/right_elbow_yaw_link.stl b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/right_elbow_yaw_link.stl
new file mode 100755
index 000000000..958278a05
Binary files /dev/null and b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/right_elbow_yaw_link.stl differ
diff --git a/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/right_foot1_link.stl b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/right_foot1_link.stl
new file mode 100755
index 000000000..ca1c289d0
Binary files /dev/null and b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/right_foot1_link.stl differ
diff --git a/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/right_foot2_link.stl b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/right_foot2_link.stl
new file mode 100755
index 000000000..5f8b71165
Binary files /dev/null and b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/right_foot2_link.stl differ
diff --git a/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/right_hip_pitch_link.stl b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/right_hip_pitch_link.stl
new file mode 100755
index 000000000..0a7aceb09
Binary files /dev/null and b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/right_hip_pitch_link.stl differ
diff --git a/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/right_hip_roll_link.stl b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/right_hip_roll_link.stl
new file mode 100755
index 000000000..7b1cbff38
Binary files /dev/null and b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/right_hip_roll_link.stl differ
diff --git a/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/right_hip_yaw_link.stl b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/right_hip_yaw_link.stl
new file mode 100755
index 000000000..5630771d1
Binary files /dev/null and b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/right_hip_yaw_link.stl differ
diff --git a/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/right_knee_link.stl b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/right_knee_link.stl
new file mode 100644
index 000000000..62c3421d9
Binary files /dev/null and b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/right_knee_link.stl differ
diff --git a/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/right_shoulder_pitch_link.stl b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/right_shoulder_pitch_link.stl
new file mode 100755
index 000000000..1c2a9730c
Binary files /dev/null and b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/right_shoulder_pitch_link.stl differ
diff --git a/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/right_shoulder_roll_link.stl b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/right_shoulder_roll_link.stl
new file mode 100755
index 000000000..bc2314e29
Binary files /dev/null and b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/right_shoulder_roll_link.stl differ
diff --git a/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/right_wrist_yaw_link.stl b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/right_wrist_yaw_link.stl
new file mode 100755
index 000000000..2e2a4722c
Binary files /dev/null and b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/right_wrist_yaw_link.stl differ
diff --git a/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/torso_link.stl b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/torso_link.stl
new file mode 100755
index 000000000..2478d66ef
Binary files /dev/null and b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/torso_link.stl differ
diff --git a/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/urdf_to_mjcf.py b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/urdf_to_mjcf.py
new file mode 100644
index 000000000..533c5e2b4
--- /dev/null
+++ b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/urdf_to_mjcf.py
@@ -0,0 +1,14 @@
+import mujoco
+import os
+
+BASE_DIR = "/home/ahmed/E_Disk/worksapce/humanoid_ws/src/humanoid_pkg/meshes"
+
+
+os.chdir(BASE_DIR)
+
+urdf_path = os.path.join(BASE_DIR, "humanoid_pkg.urdf")
+
+model = mujoco.MjModel.from_xml_path(urdf_path)
+mujoco.mj_saveLastXML("humanoid_pkg.xml", model)
+
+print(" MJCF generated successfully")
diff --git a/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/waist_pitch_link.stl b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/waist_pitch_link.stl
new file mode 100755
index 000000000..7bc7068e9
Binary files /dev/null and b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/waist_pitch_link.stl differ
diff --git a/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/waist_rod_link.stl b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/waist_rod_link.stl
new file mode 100755
index 000000000..213c04572
Binary files /dev/null and b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/waist_rod_link.stl differ
diff --git a/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/waist_roll_link.stl b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/waist_roll_link.stl
new file mode 100755
index 000000000..a65fe74af
Binary files /dev/null and b/src/mjlab/asset_zoo/robots/humanoid/assets/meshes/waist_roll_link.stl differ
diff --git a/src/mjlab/asset_zoo/robots/humanoid/humanoid_constants.py b/src/mjlab/asset_zoo/robots/humanoid/humanoid_constants.py
new file mode 100644
index 000000000..9ac229f9c
--- /dev/null
+++ b/src/mjlab/asset_zoo/robots/humanoid/humanoid_constants.py
@@ -0,0 +1,337 @@
+"""Humanoid robot constants.
+
+Humanoid is a 12-DOF bipedal robot with 6 joints per leg:
+- hip_pitch, hip_roll, hip_yaw, knee, foot1, foot2
+
+Motor specifications from Synapticon datasheets:
+- Hip pitch: EC-A6416-P2-25 (peak 120 Nm, rated 55 Nm)
+- Hip roll: EC-A5013-H17-100 (peak 90 Nm, rated 45 Nm)
+- Hip yaw: EC-A3814-H14-107 (peak 60 Nm, rated 30 Nm)
+- Knee: EC-A4315-P2-36 (peak 75 Nm, rated 50 Nm)
+- Ankle pitch/roll: EC-A4310-P2-36 (peak 36 Nm, rated 18 Nm)
+"""
+
+from pathlib import Path
+
+import mujoco
+
+from mjlab import MJLAB_SRC_PATH
+from mjlab.actuator import BuiltinPositionActuatorCfg
+from mjlab.entity import EntityArticulationInfoCfg, EntityCfg
+from mjlab.utils.os import update_assets
+from mjlab.utils.spec_config import CollisionCfg
+
+##
+# MJCF and assets.
+##
+
+HUMANOID_XML: Path = (
+ MJLAB_SRC_PATH / "asset_zoo" / "robots" / "humanoid" / "xmls" / "humanoid.xml"
+)
+assert HUMANOID_XML.exists(), f"Humanoid XML not found at {HUMANOID_XML}"
+
+HUMANOID_WALKING_REFERENCE: Path = (
+ MJLAB_SRC_PATH / "asset_zoo" / "robots" / "humanoid" / "assets" / "walking_reference.csv"
+)
+
+
+def get_assets(meshdir: str) -> dict[str, bytes]:
+ assets: dict[str, bytes] = {}
+ update_assets(assets, HUMANOID_XML.parent.parent / "assets" / "meshes", meshdir)
+ return assets
+
+
+def get_spec() -> mujoco.MjSpec:
+ spec = mujoco.MjSpec.from_file(str(HUMANOID_XML))
+ spec.assets = get_assets(spec.meshdir)
+ return spec
+
+
+##
+# Actuator config.
+#
+# Using physics-based PD gains:
+# KP = J_reflected * omega_n^2 (with omega_n = 10 Hz * 2*pi)
+# KD = 5.0 Nm·s/rad (hardware max for all motors)
+##
+
+NATURAL_FREQ = 10 * 2.0 * 3.1415926535 # 10Hz
+DAMPING_RATIO = 2.0
+
+# Reflected inertias from motor spec sheets (J_rotor * gear_ratio^2)
+# Hip pitch: 104.395 kg·mm² * 25² = 0.0652 kg·m²
+# Hip roll: 10 kg·mm² * 100² = 0.100 kg·m²
+# Hip yaw: 3 kg·mm² * 107² = 0.0343 kg·m²
+# Knee: 25.5 kg·mm² * 36² = 0.0330 kg·m²
+# Ankle: 18.2 kg·mm² * 36² = 0.0236 kg·m²
+ARMATURE_HIP_PITCH = 0.0652
+ARMATURE_HIP_ROLL = 0.100
+ARMATURE_HIP_YAW = 0.0343
+ARMATURE_KNEE = 0.0330
+ARMATURE_FOOT1 = 0.0236
+ARMATURE_FOOT2 = 0.0236
+ARMATURE_TORSO = 0.0330 # No armature for torso
+ARMATURE_SHOULDER = 0.02
+ARMATURE_ELBOW = 0.015
+ARMATURE_WAIST_ROLL = 0.01
+ARMATURE_WAIST_PITCH = 0.01
+ARMATURE_WRIST_YAW=0.01
+
+
+# Stiffness (KP) - physics based
+STIFFNESS_HIP_PITCH = ARMATURE_HIP_PITCH * NATURAL_FREQ**2
+STIFFNESS_HIP_ROLL = ARMATURE_HIP_ROLL * NATURAL_FREQ**2
+STIFFNESS_HIP_YAW = ARMATURE_HIP_YAW * NATURAL_FREQ**2
+STIFFNESS_KNEE = ARMATURE_KNEE * NATURAL_FREQ**2
+STIFFNESS_FOOT1 = ARMATURE_FOOT1 * NATURAL_FREQ**2
+STIFFNESS_FOOT2 = ARMATURE_FOOT2 * NATURAL_FREQ**2
+STIFFNESS_TORSO = ARMATURE_TORSO * NATURAL_FREQ**2
+STIFFNESS_SHOULDER = ARMATURE_SHOULDER * NATURAL_FREQ**2
+STIFFNESS_ELBOW = ARMATURE_ELBOW * NATURAL_FREQ**2
+STIFFNESS_WAIST_ROLL = ARMATURE_WAIST_ROLL * NATURAL_FREQ**2
+STIFFNESS_WAIST_PITCH = ARMATURE_WAIST_PITCH * NATURAL_FREQ**2
+STIFFNESS_WRIST_YAW = ARMATURE_WRIST_YAW * NATURAL_FREQ**2
+
+# Damping (KD) - capped at hardware max 5.0 Nm·s/rad for sim2real
+DAMPING_HIP_PITCH = 5.0
+DAMPING_HIP_ROLL = 5.0
+DAMPING_HIP_YAW = 5.0
+DAMPING_KNEE = 5.0
+DAMPING_ANKLE = 5.0
+DAMPING_TORSO = 5.0
+DAMPING_SHOULDER = 5.0
+DAMPING_ELBOW = 5.0
+DAMPING_WAIST_ROLL = 5.0
+DAMPING_WAIST_PITCH = 5.0
+DAMPING_WRIST_YAW = 5.0
+
+# Effort limits (peak torque from datasheets)
+EFFORT_HIP_PITCH = 140.0 # EC-A6416-P2-25: peak 120 Nm
+EFFORT_HIP_ROLL = 100.0 # EC-A5013-H17-100: peak 90 Nm
+EFFORT_HIP_YAW = 80.0 # EC-A3814-H14-107: peak 60 Nm
+EFFORT_KNEE = 95.0 # EC-A4315-P2-36: peak 75 Nm
+EFFORT_ANKLE = 36.0 # EC-A4310-P2-36: peak 36 Nm
+EFFORT_TORSO = 10.0 # motor for torso
+EFFORT_SHOULDER = 10.0
+EFFORT_ELBOW = 10.0
+EFFORT_WAIST_ROLL = 10.0
+EFFORT_WAIST_PITCH = 10.0
+EFFORT_WRIST_YAW = 10.0
+
+
+
+
+
+
+HUMANOID_ACTUATOR_HIP_PITCH = BuiltinPositionActuatorCfg(
+ joint_names_expr=(".*_hip_pitch_joint",),
+ stiffness=STIFFNESS_HIP_PITCH,
+ damping=DAMPING_HIP_PITCH,
+ effort_limit=EFFORT_HIP_PITCH,
+ armature=ARMATURE_HIP_PITCH,
+)
+
+HUMANOID_ACTUATOR_HIP_ROLL = BuiltinPositionActuatorCfg(
+ joint_names_expr=(".*_hip_roll_joint",),
+ stiffness=STIFFNESS_HIP_ROLL,
+ damping=DAMPING_HIP_ROLL,
+ effort_limit=EFFORT_HIP_ROLL,
+ armature=ARMATURE_HIP_ROLL,
+)
+
+HUMANOID_ACTUATOR_HIP_YAW = BuiltinPositionActuatorCfg(
+ joint_names_expr=(".*_hip_yaw_joint",),
+ stiffness=STIFFNESS_HIP_YAW,
+ damping=DAMPING_HIP_YAW,
+ effort_limit=EFFORT_HIP_YAW,
+ armature=ARMATURE_HIP_YAW,
+)
+
+HUMANOID_ACTUATOR_KNEE = BuiltinPositionActuatorCfg(
+ joint_names_expr=(".*_knee_joint",),
+ stiffness=STIFFNESS_KNEE,
+ damping=DAMPING_KNEE,
+ effort_limit=EFFORT_KNEE,
+ armature=ARMATURE_KNEE,
+)
+
+HUMANOID_ACTUATOR_ANKLE = BuiltinPositionActuatorCfg(
+ joint_names_expr=(".*_foot1_joint", ".*_foot2_joint"),
+ stiffness=STIFFNESS_FOOT1,
+ damping=DAMPING_ANKLE,
+ effort_limit=EFFORT_ANKLE,
+ armature=ARMATURE_FOOT1,
+)
+HUMANOID_ACTION_TORSO = BuiltinPositionActuatorCfg(
+ joint_names_expr=("torso_joint",),
+ stiffness=STIFFNESS_TORSO,
+ damping=DAMPING_TORSO,
+ effort_limit=EFFORT_TORSO,
+ armature=ARMATURE_TORSO,
+)
+HUMANOID_ACTUATOR_WAIST_ROLL = BuiltinPositionActuatorCfg(
+ joint_names_expr=("waist_roll_joint",),
+ stiffness=STIFFNESS_WAIST_ROLL,
+ damping=DAMPING_WAIST_ROLL,
+ effort_limit=EFFORT_WAIST_ROLL,
+ armature=ARMATURE_WAIST_ROLL,
+)
+HUMANOID_ACTUATOR_WAIST_PITCH = BuiltinPositionActuatorCfg(
+ joint_names_expr=("waist_pitch_joint",),
+ stiffness=STIFFNESS_WAIST_PITCH,
+ damping=DAMPING_WAIST_PITCH,
+ effort_limit=EFFORT_WAIST_PITCH,
+ armature=ARMATURE_WAIST_PITCH,
+)
+
+HUMANOID_ACTUATOR_SHOULDER = BuiltinPositionActuatorCfg(
+ joint_names_expr=(".*_shoulder_.*_joint",),
+ stiffness=STIFFNESS_SHOULDER,
+ damping=DAMPING_SHOULDER,
+ effort_limit=EFFORT_SHOULDER,
+ armature=ARMATURE_SHOULDER,
+)
+
+HUMANOID_ACTUATOR_ELBOW = BuiltinPositionActuatorCfg(
+ joint_names_expr=(".*_elbow_.*_joint",),
+ stiffness=STIFFNESS_ELBOW,
+ damping=DAMPING_ELBOW,
+ effort_limit=EFFORT_ELBOW,
+ armature=ARMATURE_ELBOW,
+)
+
+HUMANOID_ACTUATOR_WRIST_YAW = BuiltinPositionActuatorCfg(
+ joint_names_expr=(".*_wrist_yaw_joint",),
+ stiffness=STIFFNESS_WRIST_YAW,
+ damping=DAMPING_WRIST_YAW,
+ effort_limit=EFFORT_WRIST_YAW,
+ armature=ARMATURE_WRIST_YAW,
+)
+##
+# Keyframe config.
+##
+
+HOME_KEYFRAME = EntityCfg.InitialStateCfg(
+ pos=(0, 0, 0.75), # Standing height (~0.72m + margin)
+ joint_pos={".*": 0.0}, # All joints at zero = straight standing
+ joint_vel={".*": 0.0},
+)
+
+# Knees bent pose for stability
+# NOTE: Left and right sides have OPPOSITE axis directions!
+# Knees:
+# - Left knee: axis=(0, 1, 0), range=[0, 1.5] → positive = extend back
+# - Right knee: axis=(0, -1, 0), range=[-1.5, 0] → negative = extend back
+# Hip pitch:
+# - Left: axis=(0, 0.707, -0.707) → positive = forward lean
+# - Right: axis=(0, -0.707, -0.707) → negative = forward lean
+# Ankle pitch:
+# - Left: axis=(0, 1, 0) → negative = pitch down
+# - Right: axis=(0, -1, 0) → positive = pitch down
+KNEES_BENT_KEYFRAME = EntityCfg.InitialStateCfg(
+ pos=(0, 0, 0.70), # Lower height for bent knees
+ joint_pos={
+ "left_hip_pitch_joint": 0.0,
+ "right_hip_pitch_joint": 0.0,
+ ".*_hip_roll_joint": 0.0,
+ ".*_hip_yaw_joint": 0.0,
+ "left_knee_joint": 0.4, # [0, 1.5] range
+ "right_knee_joint": -0.4, # [-1.5, 0] range
+ "left_foot1_joint": -0.2, # Compensate for knee bend
+ "right_foot1_joint": 0.2, # Opposite sign
+ ".*_foot2_joint": 0.0,
+ "torso_joint": 0.4,
+ "waist_roll_joint": 0.0,
+ "waist_pitch_joint": 0.0,
+ ".*_shoulder_.*_joint": 0.0,
+ ".*_elbow_.*_joint": 0.0,
+ ".*_wrist_yaw_joint": 0.0,
+
+ },
+ joint_vel={".*": 0.0},
+)
+
+##
+# Collision config.
+##
+
+# Full collision including self-collisions
+FULL_COLLISION = CollisionCfg(
+ geom_names_expr=(".*_collision",),
+ condim={
+ r"^(left|right)_foot2_link_collision$": 3,
+ ".*_collision": 1,
+ },
+ priority={r"^(left|right)_foot2_link_collision$": 1},
+ friction={r"^(left|right)_foot2_link_collision$": (0.6,)},
+)
+
+# Feet only collision (disable self-collision)
+FEET_ONLY_COLLISION = CollisionCfg(
+ geom_names_expr=(r"^(left|right)_foot2_link_collision$",),
+ contype=0,
+ conaffinity=1,
+ condim=3,
+ priority=1,
+ friction=(0.6,),
+)
+
+##
+# Final config.
+##
+
+HUMANOID_ARTICULATION = EntityArticulationInfoCfg(
+ actuators=(
+ HUMANOID_ACTUATOR_HIP_PITCH,
+ HUMANOID_ACTUATOR_HIP_ROLL,
+ HUMANOID_ACTUATOR_HIP_YAW,
+ HUMANOID_ACTUATOR_KNEE,
+ HUMANOID_ACTUATOR_ANKLE,
+ HUMANOID_ACTION_TORSO,
+ HUMANOID_ACTUATOR_WAIST_ROLL,
+ HUMANOID_ACTUATOR_WAIST_PITCH,
+ HUMANOID_ACTUATOR_SHOULDER,
+ HUMANOID_ACTUATOR_ELBOW,
+ HUMANOID_ACTUATOR_WRIST_YAW,
+
+ ),
+ soft_joint_pos_limit_factor=0.9,
+)
+
+
+def get_humanoid_robot_cfg() -> EntityCfg:
+ """Get a fresh Humanoid robot configuration instance.
+
+ Returns a new EntityCfg instance each time to avoid mutation issues when
+ the config is shared across multiple places.
+ """
+ return EntityCfg(
+ init_state=HOME_KEYFRAME,
+ collisions=(FEET_ONLY_COLLISION,),
+ spec_fn=get_spec,
+ articulation=HUMANOID_ARTICULATION,
+ )
+
+
+# Action scale: how much the action scales joint position target
+# Using 0.3 * effort_limit / stiffness (like humanoid-mjlab)
+HUMANOID_ACTION_SCALE: dict[str, float] = {}
+for a in HUMANOID_ARTICULATION.actuators:
+ assert isinstance(a, BuiltinPositionActuatorCfg)
+ e = a.effort_limit
+ s = a.stiffness
+ names = a.joint_names_expr
+ assert e is not None
+ assert s is not None
+ for n in names:
+ HUMANOID_ACTION_SCALE[n] = 0.3 * e / s
+
+
+if __name__ == "__main__":
+ import mujoco.viewer as viewer
+
+ from mjlab.entity.entity import Entity
+
+ robot = Entity(get_humanoid_robot_cfg())
+
+ viewer.launch(robot.spec.compile())
diff --git a/src/mjlab/asset_zoo/robots/humanoid/xmls/asimov4.xml b/src/mjlab/asset_zoo/robots/humanoid/xmls/asimov4.xml
new file mode 100644
index 000000000..666699db4
--- /dev/null
+++ b/src/mjlab/asset_zoo/robots/humanoid/xmls/asimov4.xml
@@ -0,0 +1,302 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/src/mjlab/asset_zoo/robots/humanoid/xmls/humanoid.xml b/src/mjlab/asset_zoo/robots/humanoid/xmls/humanoid.xml
new file mode 100644
index 000000000..e41fc57b1
--- /dev/null
+++ b/src/mjlab/asset_zoo/robots/humanoid/xmls/humanoid.xml
@@ -0,0 +1,346 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
\ No newline at end of file
diff --git a/src/mjlab/scripts/play.py b/src/mjlab/scripts/play.py
index 3fd8602d9..3c3f350a0 100644
--- a/src/mjlab/scripts/play.py
+++ b/src/mjlab/scripts/play.py
@@ -133,6 +133,7 @@ def run_play(task_id: str, cfg: PlayConfig):
resume_path, was_cached = get_wandb_checkpoint_path(
log_root_path, Path(cfg.wandb_run_path), cfg.wandb_checkpoint_name
)
+# resume_path = None
# Extract run_id and checkpoint name from path for display.
run_id = resume_path.parent.name
checkpoint_name = resume_path.name
diff --git a/src/mjlab/tasks/velocity/config/humanoid/__init__.py b/src/mjlab/tasks/velocity/config/humanoid/__init__.py
new file mode 100644
index 000000000..6606925d7
--- /dev/null
+++ b/src/mjlab/tasks/velocity/config/humanoid/__init__.py
@@ -0,0 +1,31 @@
+"""humanoid velocity task configurations."""
+
+from mjlab.tasks.registry import register_mjlab_task
+from mjlab.tasks.velocity.rl import VelocityOnPolicyRunner
+
+from .env_cfgs import humanoid_balance_env_cfg, humanoid_flat_env_cfg, humanoid_rough_env_cfg
+from .rl_cfg import humanoid_ppo_runner_cfg
+
+register_mjlab_task(
+ task_id="Mjlab-Velocity-Rough-Humanoid",
+ env_cfg=humanoid_rough_env_cfg(),
+ play_env_cfg=humanoid_rough_env_cfg(play=True),
+ rl_cfg=humanoid_ppo_runner_cfg(),
+ runner_cls=VelocityOnPolicyRunner,
+)
+
+register_mjlab_task(
+ task_id="Mjlab-Velocity-Flat-Humanoid",
+ env_cfg=humanoid_flat_env_cfg(),
+ play_env_cfg=humanoid_flat_env_cfg(play=True),
+ rl_cfg=humanoid_ppo_runner_cfg(),
+ runner_cls=VelocityOnPolicyRunner,
+)
+
+register_mjlab_task(
+ task_id="Mjlab-Balance-Humanoid",
+ env_cfg=humanoid_balance_env_cfg(),
+ play_env_cfg=humanoid_balance_env_cfg(play=True),
+ rl_cfg=humanoid_ppo_runner_cfg(),
+ runner_cls=VelocityOnPolicyRunner,
+)
diff --git a/src/mjlab/tasks/velocity/config/humanoid/env_cfgs.py b/src/mjlab/tasks/velocity/config/humanoid/env_cfgs.py
new file mode 100644
index 000000000..4348ab17f
--- /dev/null
+++ b/src/mjlab/tasks/velocity/config/humanoid/env_cfgs.py
@@ -0,0 +1,246 @@
+"""humanoid bipedal robot velocity tracking environment configurations."""
+
+from mjlab.asset_zoo.robots.humanoid.humanoid_constants import (
+ HUMANOID_ACTION_SCALE,
+ HUMANOID_WALKING_REFERENCE,
+ get_humanoid_robot_cfg,
+)
+from mjlab.envs import ManagerBasedRlEnvCfg
+from mjlab.envs.mdp.actions import JointPositionActionCfg
+from mjlab.managers.manager_term_config import ObservationTermCfg, RewardTermCfg
+from mjlab.sensor import ContactMatch, ContactSensorCfg
+from mjlab.tasks.velocity import mdp
+from mjlab.tasks.velocity.mdp import UniformVelocityCommandCfg
+from mjlab.tasks.velocity.velocity_env_cfg import make_velocity_env_cfg
+
+
+def humanoid_rough_env_cfg(play: bool = False) -> ManagerBasedRlEnvCfg:
+ """Create humanoid rough terrain velocity tracking configuration."""
+ cfg = make_velocity_env_cfg()
+
+ cfg.scene.entities = {"robot": get_humanoid_robot_cfg()}
+
+ # humanoid feet sites
+ site_names = ("left_foot", "right_foot")
+ geom_names = (
+ "left_foot2_link_collision",
+ "right_foot2_link_collision",
+ )
+
+ feet_ground_cfg = ContactSensorCfg(
+ name="feet_ground_contact",
+ primary=ContactMatch(
+ mode="subtree",
+ pattern=r"^(left_foot2_link|right_foot2_link)$",
+ entity="robot",
+ ),
+ secondary=ContactMatch(mode="body", pattern="terrain"),
+ fields=("found", "force"),
+ reduce="netforce",
+ num_slots=1,
+ track_air_time=True,
+ )
+
+ self_collision_cfg = ContactSensorCfg(
+ name="self_collision",
+ primary=ContactMatch(mode="subtree", pattern="pelvis_link", entity="robot"),
+ secondary=ContactMatch(mode="subtree", pattern="pelvis_link", entity="robot"),
+ fields=("found",),
+ reduce="none",
+ num_slots=1,
+ )
+
+ cfg.scene.sensors = (feet_ground_cfg, self_collision_cfg)
+
+ if cfg.scene.terrain is not None and cfg.scene.terrain.terrain_generator is not None:
+ cfg.scene.terrain.terrain_generator.curriculum = True
+
+ joint_pos_action = cfg.actions["joint_pos"]
+ assert isinstance(joint_pos_action, JointPositionActionCfg)
+ joint_pos_action.scale = HUMANOID_ACTION_SCALE
+
+ cfg.viewer.body_name = "pelvis_link"
+
+ assert cfg.commands is not None
+ twist_cmd = cfg.commands["twist"]
+ assert isinstance(twist_cmd, UniformVelocityCommandCfg)
+ twist_cmd.viz.z_offset = 0.8 # humanoid is shorter than G1
+
+ # More conservative velocity commands due to:
+ # 1. Narrow stance (11.3 cm hip width)
+ # 2. Canted hip pitch (less stable)
+ # 3. Limited ankle ROM
+ twist_cmd.ranges.lin_vel_x = (-0.8, 0.8)
+ twist_cmd.ranges.lin_vel_y = (-0.6, 0.6)
+ twist_cmd.ranges.ang_vel_z = (-0.6, 0.6)
+
+ # Remove base_lin_vel - not available on real robot IMU
+ del cfg.observations["policy"].terms["base_lin_vel"]
+ del cfg.observations["critic"].terms["base_lin_vel"]
+
+ # Add gait clock observation for phase-aware locomotion
+ gait_clock_cfg = ObservationTermCfg(
+ func=mdp.gait_clock,
+ params={
+ "command_name": "twist",
+ "command_threshold": 0.1,
+ "gait_frequency": 1.25, # Match imitation data frequency
+ },
+ )
+ cfg.observations["policy"].terms["gait_clock"] = gait_clock_cfg
+ cfg.observations["critic"].terms["gait_clock"] = gait_clock_cfg
+
+ cfg.observations["critic"].terms["foot_height"].params[
+ "asset_cfg"
+ ].site_names = site_names
+
+ cfg.events["foot_friction"].params["asset_cfg"].geom_names = geom_names
+
+ cfg.rewards["pose"].params["std_standing"] = {".*": 0.05}
+ cfg.rewards["pose"].params["std_walking"] = {
+ # Larger variance for canted hip pitch (allows coupled roll/pitch motion)
+ r".*hip_pitch.*": 0.5,
+ # Moderate hip roll (asymmetric ranges)
+ r".*hip_roll.*": 0.25,
+ # Standard hip yaw
+ r".*hip_yaw.*": 0.2,
+ # Large knee variance (extends backwards, different from G1)
+ r".*knee.*": 0.5,
+ # Lower ankle variance due to limited ROM (±20° pitch, ±15° roll)
+ r".*foot1.*": 0.2,
+ r".*foot2.*": 0.12,
+ r".*torso.*": 0.3,
+ r".*waist_roll.*": 0.3,
+ r".*waist_pitch.*": 0.1,
+ r".*shoulder.*": 0.1,
+ r".*elbow.*": 0.1,
+ r".*wrist_yaw.*": 0.1,
+ }
+ cfg.rewards["pose"].params["std_running"] = {
+ # Even larger variance for dynamic motion with canted hips
+ r".*hip_pitch.*": 0.8,
+ r".*hip_roll.*": 0.35,
+ r".*hip_yaw.*": 0.3,
+ r".*knee.*": 0.8,
+
+ # Keep feet constrained even when running
+ r".*foot1.*": 0.25,
+ r".*foot2.*": 0.15,
+ r".*torso.*": 0.3,
+ r".*waist_roll.*": 0.15,
+ r".*waist_pitch.*": 0.15,
+ r".*shoulder.*": 0.15,
+ r".*elbow.*": 0.15,
+ r".*wrist_yaw.*": 0.15,
+ }
+
+ cfg.rewards["upright"].params["asset_cfg"].body_names = ("pelvis_link",)
+ cfg.rewards["body_ang_vel"].params["asset_cfg"].body_names = ("pelvis_link",)
+
+ for reward_name in ["foot_clearance", "foot_swing_height", "foot_slip"]:
+ cfg.rewards[reward_name].params["asset_cfg"].site_names = site_names
+
+ # Increase body angular velocity penalty (narrow stance = less stable)
+ cfg.rewards["body_ang_vel"].weight = -0.08
+ cfg.rewards["angular_momentum"].weight = -0.03
+ # Enable air time reward for lighter robot (better for jumping)
+ cfg.rewards["air_time"].weight = 0.5
+
+ cfg.rewards["self_collisions"] = RewardTermCfg(
+ func=mdp.self_collision_cost,
+ weight=-1.0,
+ params={"sensor_name": self_collision_cfg.name},
+ )
+
+ # Imitation reward for walking reference motion
+ cfg.rewards["imitation"] = RewardTermCfg(
+ func=mdp.imitation_joint_pos,
+ weight=1.5,
+ params={
+ "data_path": str(HUMANOID_WALKING_REFERENCE),
+ "gait_frequency": 1.25, # Match the reference data frequency
+ "std": 0.5, # Tolerance for joint position matching
+ "command_name": "twist",
+ "command_threshold": 0.1,
+ },
+ )
+
+ # Alternating feet contact reward for proper bipedal gait
+ cfg.rewards["alternating_feet"] = RewardTermCfg(
+ func=mdp.alternating_feet_contact,
+ weight=0.5,
+ params={
+ "sensor_name": feet_ground_cfg.name,
+ "command_name": "twist",
+ "command_threshold": 0.1,
+ "gait_frequency": 1.25, # Match imitation data frequency
+ },
+ )
+
+ # Apply play mode overrides.
+ if play:
+ # Effectively infinite episode length.
+ cfg.episode_length_s = int(1e9)
+
+ cfg.observations["policy"].enable_corruption = False
+ cfg.events.pop("push_robot", None)
+
+ if cfg.scene.terrain is not None:
+ if cfg.scene.terrain.terrain_generator is not None:
+ cfg.scene.terrain.terrain_generator.curriculum = False
+ cfg.scene.terrain.terrain_generator.num_cols = 5
+ cfg.scene.terrain.terrain_generator.num_rows = 5
+ cfg.scene.terrain.terrain_generator.border_width = 10.0
+
+ return cfg
+
+
+def humanoid_flat_env_cfg(play: bool = False) -> ManagerBasedRlEnvCfg:
+ """Create humanoid flat terrain velocity tracking configuration."""
+ cfg = humanoid_rough_env_cfg(play=play)
+
+ # Switch to flat terrain.
+ assert cfg.scene.terrain is not None
+ cfg.scene.terrain.terrain_type = "plane"
+ cfg.scene.terrain.terrain_generator = None
+
+ # Disable terrain curriculum.
+ assert cfg.curriculum is not None
+ assert "terrain_levels" in cfg.curriculum
+ del cfg.curriculum["terrain_levels"]
+
+ if play:
+ commands = cfg.commands
+ assert commands is not None
+ twist_cmd = commands["twist"]
+ assert isinstance(twist_cmd, UniformVelocityCommandCfg)
+ twist_cmd.ranges.lin_vel_x = (-1.0, 1.5)
+ twist_cmd.ranges.ang_vel_z = (-0.7, 0.7)
+
+ return cfg
+
+
+def humanoid_balance_env_cfg(play: bool = False) -> ManagerBasedRlEnvCfg:
+ """Create humanoid balance-only config with reactive stepping.
+
+ The robot learns to balance in place and take small corrective steps
+ when disturbed. No velocity tracking - just stay upright.
+ """
+ cfg = humanoid_flat_env_cfg(play=play)
+
+ # Zero out velocity commands (not trying to go anywhere)
+ assert cfg.commands is not None
+ twist_cmd = cfg.commands["twist"]
+ assert isinstance(twist_cmd, UniformVelocityCommandCfg)
+ twist_cmd.ranges.lin_vel_x = (0.0, 0.0)
+ twist_cmd.ranges.lin_vel_y = (0.0, 0.0)
+ twist_cmd.ranges.ang_vel_z = (0.0, 0.0)
+
+ # Disable velocity tracking rewards (not trying to go anywhere)
+ cfg.rewards["track_linear_velocity"].weight = 0.0
+ cfg.rewards["track_angular_velocity"].weight = 0.0
+
+ # Keep foot rewards for reactive stepping
+ # Keep upright, pose, body_ang_vel for balance
+
+ return cfg
diff --git a/src/mjlab/tasks/velocity/config/humanoid/rl_cfg.py b/src/mjlab/tasks/velocity/config/humanoid/rl_cfg.py
new file mode 100644
index 000000000..eb4e1471c
--- /dev/null
+++ b/src/mjlab/tasks/velocity/config/humanoid/rl_cfg.py
@@ -0,0 +1,39 @@
+"""RL configuration for humanoid velocity task."""
+
+from mjlab.rl import (
+ RslRlOnPolicyRunnerCfg,
+ RslRlPpoActorCriticCfg,
+ RslRlPpoAlgorithmCfg,
+)
+
+
+def humanoid_ppo_runner_cfg() -> RslRlOnPolicyRunnerCfg:
+ """Create RL runner configuration for humanoid velocity task."""
+ return RslRlOnPolicyRunnerCfg(
+ policy=RslRlPpoActorCriticCfg(
+ init_noise_std=1.0,
+ actor_obs_normalization=True,
+ critic_obs_normalization=True,
+ actor_hidden_dims=(256, 256, 128), # Smaller network for 12-DOF robot
+ critic_hidden_dims=(256, 256, 128),
+ activation="elu",
+ ),
+ algorithm=RslRlPpoAlgorithmCfg(
+ value_loss_coef=1.0,
+ use_clipped_value_loss=True,
+ clip_param=0.2,
+ entropy_coef=0.01,
+ num_learning_epochs=5,
+ num_mini_batches=4,
+ learning_rate=1.0e-3,
+ schedule="adaptive",
+ gamma=0.99,
+ lam=0.95,
+ desired_kl=0.01,
+ max_grad_norm=1.0,
+ ),
+ experiment_name="humanoid_velocity",
+ save_interval=50,
+ num_steps_per_env=24,
+ max_iterations=30_000,
+ )
diff --git a/src/mjlab/tasks/velocity/mdp/observations.py b/src/mjlab/tasks/velocity/mdp/observations.py
index 8d72f9f4f..1791c47f0 100644
--- a/src/mjlab/tasks/velocity/mdp/observations.py
+++ b/src/mjlab/tasks/velocity/mdp/observations.py
@@ -42,3 +42,47 @@ def foot_contact_forces(env: ManagerBasedRlEnv, sensor_name: str) -> torch.Tenso
assert sensor_data.force is not None
forces_flat = sensor_data.force.flatten(start_dim=1) # [B, N*3]
return torch.sign(forces_flat) * torch.log1p(torch.abs(forces_flat))
+
+
+class gait_clock:
+ """Gait clock observation - sin/cos of gait phase like Booster.
+
+ Returns [cos(2*pi*phase), sin(2*pi*phase)] as a 2D observation.
+ The phase advances based on gait_frequency when robot is commanded to move.
+ """
+
+ def __init__(self, cfg, env: ManagerBasedRlEnv):
+ self.gait_phase = torch.zeros(env.num_envs, device=env.device, dtype=torch.float32)
+ self.gait_frequency = cfg.params.get("gait_frequency", 1.5)
+ self.step_dt = env.step_dt
+
+ def __call__(
+ self,
+ env: ManagerBasedRlEnv,
+ command_name: str,
+ command_threshold: float = 0.1,
+ gait_frequency: float = 1.5,
+ ) -> torch.Tensor:
+ command = env.command_manager.get_command(command_name)
+ assert command is not None
+
+ # Only advance phase when moving
+ linear_norm = torch.norm(command[:, :2], dim=1)
+ angular_norm = torch.abs(command[:, 2])
+ total_command = linear_norm + angular_norm
+ active = (total_command > command_threshold).float()
+
+ # Update gait phase
+ self.gait_phase = torch.fmod(
+ self.gait_phase + self.step_dt * gait_frequency * active, 1.0
+ )
+
+ # Reset phase on episode reset (only if termination_manager exists)
+ if hasattr(env, 'termination_manager') and env.termination_manager is not None:
+ reset_ids = env.termination_manager.terminated.nonzero(as_tuple=False).flatten()
+ if len(reset_ids) > 0:
+ self.gait_phase[reset_ids] = torch.rand(len(reset_ids), device=env.device)
+
+ # Return cos/sin of phase
+ phase_2pi = 2.0 * 3.14159265359 * self.gait_phase
+ return torch.stack([torch.cos(phase_2pi), torch.sin(phase_2pi)], dim=1)
diff --git a/src/mjlab/tasks/velocity/mdp/rewards.py b/src/mjlab/tasks/velocity/mdp/rewards.py
index 772dad74c..1f5c68a6f 100644
--- a/src/mjlab/tasks/velocity/mdp/rewards.py
+++ b/src/mjlab/tasks/velocity/mdp/rewards.py
@@ -300,6 +300,159 @@ def soft_landing(
return cost
+class alternating_feet_contact:
+ """Reward alternating foot contacts to encourage walking gait.
+
+ Tracks a gait phase (0 to 1) and rewards:
+ - Left foot in air when phase is 0.0-0.5
+ - Right foot in air when phase is 0.5-1.0
+ """
+
+ def __init__(self, cfg: RewardTermCfg, env: ManagerBasedRlEnv):
+ self.gait_phase = torch.zeros(env.num_envs, device=env.device, dtype=torch.float32)
+ self.gait_frequency = cfg.params.get("gait_frequency", 1.5) # Hz
+ self.step_dt = env.step_dt
+
+ def __call__(
+ self,
+ env: ManagerBasedRlEnv,
+ sensor_name: str,
+ command_name: str,
+ command_threshold: float = 0.1,
+ gait_frequency: float = 1.5,
+ ) -> torch.Tensor:
+ contact_sensor: ContactSensor = env.scene[sensor_name]
+ command = env.command_manager.get_command(command_name)
+ assert command is not None
+
+ # Update gait phase
+ self.gait_phase = torch.fmod(self.gait_phase + self.step_dt * gait_frequency, 1.0)
+
+ # Check foot contact (assume 2 feet: left=0, right=1)
+ assert contact_sensor.data.found is not None
+ in_contact = contact_sensor.data.found > 0 # [B, 2]
+ left_contact = in_contact[:, 0]
+ right_contact = in_contact[:, 1]
+
+ # Desired: left swing (not contact) when phase 0.0-0.5, right swing when 0.5-1.0
+ left_should_swing = self.gait_phase < 0.5
+ right_should_swing = self.gait_phase >= 0.5
+
+ # Reward when foot is in air at the right time
+ left_reward = (left_should_swing & ~left_contact).float()
+ right_reward = (right_should_swing & ~right_contact).float()
+ reward = left_reward + right_reward
+
+ # Only apply when moving
+ linear_norm = torch.norm(command[:, :2], dim=1)
+ angular_norm = torch.abs(command[:, 2])
+ total_command = linear_norm + angular_norm
+ active = (total_command > command_threshold).float()
+ reward = reward * active
+
+ # Reset phase on episode reset
+ reset_ids = env.termination_manager.terminated.nonzero(as_tuple=False).flatten()
+ if len(reset_ids) > 0:
+ self.gait_phase[reset_ids] = torch.rand(len(reset_ids), device=env.device)
+
+ return reward
+
+
+class imitation_joint_pos:
+ """Reward for tracking reference joint positions from imitation data.
+
+ Loads cyclic walking trajectory from CSV and rewards matching the reference
+ pose based on gait phase computed from velocity command.
+ """
+
+ def __init__(self, cfg: RewardTermCfg, env: ManagerBasedRlEnv):
+ import numpy as np
+ import os
+
+ self.step_dt = env.step_dt
+ self.gait_phase = torch.zeros(env.num_envs, device=env.device, dtype=torch.float32)
+
+ # Load imitation data
+ data_path = cfg.params.get("data_path", None)
+ if data_path is None or not os.path.exists(data_path):
+ print(f"[WARNING] Imitation data not found at {data_path}, reward disabled")
+ self.enabled = False
+ self.ref_joint_pos = None
+ return
+
+ self.enabled = True
+ data = np.loadtxt(data_path, delimiter=",", skiprows=1)
+ # First 12 columns are joint positions
+ ref_joint_pos = data[:, :12]
+ self.ref_joint_pos = torch.tensor(ref_joint_pos, device=env.device, dtype=torch.float32)
+ self.num_frames = self.ref_joint_pos.shape[0]
+ self.gait_frequency = cfg.params.get("gait_frequency", 1.25) # Hz
+ print(f"[INFO] Loaded imitation data: {self.num_frames} frames at {self.gait_frequency} Hz")
+
+ # Joint mapping from CSV to mjlab order
+ # CSV order: L_hip_pitch, R_hip_pitch, L_hip_roll, R_hip_roll, L_hip_yaw, R_hip_yaw,
+ # L_knee, R_knee, L_ankle_pitch, R_ankle_pitch, L_ankle_roll, R_ankle_roll
+ # mjlab order: L_hip_pitch, L_hip_roll, L_hip_yaw, L_knee, L_ankle_pitch, L_ankle_roll,
+ # R_hip_pitch, R_hip_roll, R_hip_yaw, R_knee, R_ankle_pitch, R_ankle_roll
+ # For mjlab[i], which CSV index to use:
+ # mjlab[0]=CSV[0], mjlab[1]=CSV[2], mjlab[2]=CSV[4], mjlab[3]=CSV[6], mjlab[4]=CSV[8], mjlab[5]=CSV[10]
+ # mjlab[6]=CSV[1], mjlab[7]=CSV[3], mjlab[8]=CSV[5], mjlab[9]=CSV[7], mjlab[10]=CSV[9], mjlab[11]=CSV[11]
+ csv_to_mjlab = [0, 2, 4, 6, 8, 10, 1, 3, 5, 7, 9, 11]
+ self.ref_joint_pos_reordered = self.ref_joint_pos[:, csv_to_mjlab].clone()
+
+ def __call__(
+ self,
+ env: ManagerBasedRlEnv,
+ data_path: str,
+ gait_frequency: float,
+ std: float,
+ command_name: str,
+ command_threshold: float = 0.1,
+ asset_cfg: SceneEntityCfg = _DEFAULT_ASSET_CFG,
+ ) -> torch.Tensor:
+ del data_path # Used in __init__
+
+ if not self.enabled:
+ return torch.zeros(env.num_envs, device=env.device)
+
+ asset: Entity = env.scene[asset_cfg.name]
+ command = env.command_manager.get_command(command_name)
+ assert command is not None
+
+ # Update gait phase based on velocity
+ linear_speed = torch.norm(command[:, :2], dim=1)
+ angular_speed = torch.abs(command[:, 2])
+ total_speed = linear_speed + angular_speed
+ active = (total_speed > command_threshold).float()
+
+ # Advance phase proportional to speed
+ phase_delta = self.step_dt * gait_frequency * (total_speed / 0.5).clamp(min=0.5, max=2.0)
+ self.gait_phase = torch.fmod(self.gait_phase + phase_delta, 1.0)
+
+ # Get frame index from phase
+ frame_idx = (self.gait_phase * self.num_frames).long() % self.num_frames
+
+ # Get reference joint positions for each env
+ ref_pos = self.ref_joint_pos_reordered[frame_idx] # [B, 12]
+
+ # Get current joint positions
+ current_pos = asset.data.joint_pos[:, asset_cfg.joint_ids] # [B, 12]
+
+ # Compute error
+ error_sq = torch.sum(torch.square(current_pos - ref_pos), dim=1)
+ reward = torch.exp(-error_sq / (std ** 2))
+
+ # Only apply when moving
+ reward = reward * active
+
+ # Reset phase on episode reset
+ reset_ids = env.termination_manager.terminated.nonzero(as_tuple=False).flatten()
+ if len(reset_ids) > 0:
+ self.gait_phase[reset_ids] = torch.rand(len(reset_ids), device=env.device)
+
+ return reward
+
+
class variable_posture:
"""Penalize deviation from default pose with speed-dependent tolerance.